Gazebo Gazebo

API Reference

3.15.2
ignition::gazebo::events Namespace Reference

Namespace for all events. Refer to the EventManager class for more information about events. More...

Typedefs

using CollectContactSurfaceProperties = gz::common::EventT< void(const Entity &, const Entity &, const math::Vector3d &, const std::optional< math::Vector3d >, const std::optional< math::Vector3d >, const std::optional< double >, const size_t, physics::SetContactPropertiesCallbackFeature::ContactSurfaceParams< Policy > &), struct CollectContactSurfacePropertiesTag >
 This event is called when the physics engine needs to collect what customizations it should do to the surface of a contact point. It is called during the Update phase after collision checking has been finished and before the physics update has happened. The event subscribers are expected to change the params argument. More...
 
using LoadPlugins = common::EventT< void(Entity, sdf::ElementPtr), struct LoadPluginsTag >
 Event used to load plugins for an entity into simulation. Pass in the entity which will own the plugins, and an SDF element for the entity, which may contain multiple <plugin> tags. More...
 
using Pause = gz::common::EventT< void(bool), struct PauseTag >
 The pause event can be used to pause or unpause simulation. Emit a value of true to pause simulation, and emit a value of false to unpause simulation. More...
 
using Policy = physics::FeaturePolicy3d
 
using PostRender = gz::common::EventT< void(void), struct PostRenderTag >
 The render event is emitted after rendering updates. The event is emitted in the rendering thread so rendering calls can ben make in this event callback. More...
 
using PreRender = gz::common::EventT< void(void), struct PreRenderTag >
 The render event is emitted before rendering updates. The event is emitted in the rendering thread so rendering calls can ben make in this event callback. More...
 
using Stop = gz::common::EventT< void(void), struct StopTag >
 The stop event can be used to terminate simulation. Emit this signal to terminate an active simulation. More...
 

Detailed Description

Namespace for all events. Refer to the EventManager class for more information about events.

Typedef Documentation

◆ CollectContactSurfaceProperties

using CollectContactSurfaceProperties = gz::common::EventT< void( const Entity& , const Entity& , const math::Vector3d & , const std::optional<math::Vector3d> , const std::optional<math::Vector3d> , const std::optional<double> , const size_t , physics::SetContactPropertiesCallbackFeature:: ContactSurfaceParams<Policy>& ), struct CollectContactSurfacePropertiesTag>

This event is called when the physics engine needs to collect what customizations it should do to the surface of a contact point. It is called during the Update phase after collision checking has been finished and before the physics update has happened. The event subscribers are expected to change the params argument.

◆ LoadPlugins

using LoadPlugins = common::EventT<void(Entity, sdf::ElementPtr), struct LoadPluginsTag>

Event used to load plugins for an entity into simulation. Pass in the entity which will own the plugins, and an SDF element for the entity, which may contain multiple <plugin> tags.

◆ Pause

using Pause = gz::common::EventT<void(bool), struct PauseTag>

The pause event can be used to pause or unpause simulation. Emit a value of true to pause simulation, and emit a value of false to unpause simulation.

For example, to pause simulation use:

eventManager.Emit<gz::sim::events::Pause>(true);

◆ Policy

using Policy = physics::FeaturePolicy3d

◆ PostRender

using PostRender = gz::common::EventT<void(void), struct PostRenderTag>

The render event is emitted after rendering updates. The event is emitted in the rendering thread so rendering calls can ben make in this event callback.

For example:

eventManager.Emit<gz::sim::events::PostRender>();

◆ PreRender

using PreRender = gz::common::EventT<void(void), struct PreRenderTag>

The render event is emitted before rendering updates. The event is emitted in the rendering thread so rendering calls can ben make in this event callback.

For example:

eventManager.Emit<gz::sim::events::PreRender>();

◆ Stop

using Stop = gz::common::EventT<void(void), struct StopTag>

The stop event can be used to terminate simulation. Emit this signal to terminate an active simulation.

For example:

eventManager.Emit<gz::sim::events::Stop>();
gz::common::EventT< void(bool), struct PauseTag > Pause
The pause event can be used to pause or unpause simulation. Emit a value of true to pause simulation,...
Definition: gz/sim/Events.hh:45
gz::common::EventT< void(void), struct StopTag > Stop
The stop event can be used to terminate simulation. Emit this signal to terminate an active simulatio...
Definition: gz/sim/Events.hh:54
gz::common::EventT< void(void), struct PostRenderTag > PostRender
The render event is emitted after rendering updates. The event is emitted in the rendering thread so ...
Definition: gz/sim/rendering/Events.hh:55
gz::common::EventT< void(void), struct PreRenderTag > PreRender
The render event is emitted before rendering updates. The event is emitted in the rendering thread so...
Definition: gz/sim/rendering/Events.hh:44