Gazebo Sim

API Reference

7.9.0
gz::sim::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 ForceRender = gz::common::EventT< void(void), struct ForceRenderTag >
 The force render event may be emitted outside the rendering thread to force rendering calls ie. to ensure rendering occurs even if it wasn't seemingly necessary. More...
 
using LoadPlugins = common::EventT< void(Entity, sdf::ElementPtr), struct LoadPluginsTag >
 Please use the LoadSdfPlugins event. The LoadPlugins event is deprecrated in Gazebo 7 (Garden). Also make sure to connect to only LoadSdfPlugins or LoadPlugins, and not both events. More...
 
using LoadSdfPlugins = common::EventT< void(Entity, sdf::Plugins), 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. Makre sure that you don't also connect to the LoadPlugins event. 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 post render event is emitted after rendering updates. The event is emitted in the rendering thread so rendering calls can be made in this event callback. More...
 
using PreRender = gz::common::EventT< void(void), struct PreRenderTag >
 The pre render event is emitted before rendering updates. The event is emitted in the rendering thread so rendering calls can be made in this event callback. More...
 
using Render = gz::common::EventT< void(void), struct RenderTag >
 The render event is emitted during rendering updates. The event is emitted in the rendering thread so rendering calls can be made in this event callback. More...
 
using RenderTeardown = gz::common::EventT< void(void), struct RenderTeardownTag >
 The render teardown event is emitted right before the rendering thread is torn down. The event is emitted in the rendering thread so last minute, cleanup rendering calls can be made in this event callback. More...
 
using SceneUpdate = gz::common::EventT< void(void), struct SceneUpdateTag >
 The render event is emitted when the the scene manager is updated with contents from the ECM. This event is emitted before the PreRender event on the server side in the rendering thread. It is also accessible on the GUI side. 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.

◆ ForceRender

using ForceRender = gz::common::EventT<void(void), struct ForceRenderTag>

The force render event may be emitted outside the rendering thread to force rendering calls ie. to ensure rendering occurs even if it wasn't seemingly necessary.

Useful for custom, out-of-tree rendering sensors that need the rendering thread to perform an update.

For example:

eventManager.Emit<events::ForceRender>();

◆ LoadPlugins

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

Please use the LoadSdfPlugins event. The LoadPlugins event is deprecrated in Gazebo 7 (Garden). Also make sure to connect to only LoadSdfPlugins or LoadPlugins, and not both events.

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.

Deprecated:
Use the sdf::Plugins interface.

◆ LoadSdfPlugins

using LoadSdfPlugins = common::EventT<void(Entity, sdf::Plugins), 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. Makre sure that you don't also connect to the LoadPlugins event.

◆ 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<events::Pause>(true);

◆ Policy

using Policy = physics::FeaturePolicy3d

◆ PostRender

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

The post render event is emitted after rendering updates. The event is emitted in the rendering thread so rendering calls can be made in this event callback.

For example:

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

◆ PreRender

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

The pre render event is emitted before rendering updates. The event is emitted in the rendering thread so rendering calls can be made in this event callback.

For example:

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

◆ Render

using Render = gz::common::EventT<void(void), struct RenderTag>

The render event is emitted during rendering updates. The event is emitted in the rendering thread so rendering calls can be made in this event callback.

For example:

eventManager.Emit<events::Render>();

◆ RenderTeardown

using RenderTeardown = gz::common::EventT<void(void), struct RenderTeardownTag>

The render teardown event is emitted right before the rendering thread is torn down. The event is emitted in the rendering thread so last minute, cleanup rendering calls can be made in this event callback.

For example:

eventManager.Emit<events::RenderTeardown>();

◆ SceneUpdate

using SceneUpdate = gz::common::EventT<void(void), struct SceneUpdateTag>

The render event is emitted when the the scene manager is updated with contents from the ECM. This event is emitted before the PreRender event on the server side in the rendering thread. It is also accessible on the GUI side.

For example:

eventManager.Emit<events::SceneUpdate>();

◆ 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<events::Stop>();