Gazebo Sim

API Reference

8.7.0
PosePublisher Class Reference

Pose publisher system. Attach to an entity to publish the transform of its child entities in the form of gz::msgs::Pose messages, or a single gz::msgs::Pose_V message if "use_pose_vector_msg" is true. More...

#include <PosePublisher.hh>

Public Member Functions

 PosePublisher ()
 Constructor. More...
 
 ~PosePublisher () override=default
 Destructor. More...
 
void Configure (const Entity &_entity, const std::shared_ptr< const sdf::Element > &_sdf, EntityComponentManager &_ecm, EventManager &_eventMgr) override
 Configure the system. More...
 
void PostUpdate (const UpdateInfo &_info, const EntityComponentManager &_ecm) override
 
- Public Member Functions inherited from System
 System ()=default
 Constructor. More...
 
virtual ~System ()=default
 Destructor. More...
 

Additional Inherited Members

- Public Types inherited from System
using PriorityType = int32_t
 Signed integer type used for specifying priority of the execution order of PreUpdate and Update phases. More...
 
- Static Public Attributes inherited from System
constexpr static PriorityType kDefaultPriority = {0}
 Default priority value for execution order of the PreUpdate and Update phases. More...
 
constexpr static std::string_view kPriorityElementName
 Name of the XML element from which the priority value will be parsed. More...
 

Detailed Description

Pose publisher system. Attach to an entity to publish the transform of its child entities in the form of gz::msgs::Pose messages, or a single gz::msgs::Pose_V message if "use_pose_vector_msg" is true.

System Parameters

  • <publish_link_pose>: Set to true to publish link pose
  • <publish_visual_pose>: Set to true to publish visual pose
  • <publish_collision_pose>: Set to true to publish collision pose
  • <publish_sensor_pose>: Set to true to publish sensor pose
  • <publish_model_pose>: Set to true to publish model pose.
  • <publish_nested_model_pose>: Set to true to publish nested model pose. The pose of the model that contains this system is also published unless publish_model_pose is set to false
  • <use_pose_vector_msg>: Set to true to publish a gz::msgs::Pose_V message instead of mulitple gz::msgs::Pose messages.
  • <update_frequency>: Frequency of pose publications in Hz. A negative frequency publishes as fast as possible (i.e, at the rate of the simulation step)
  • <static_publisher>: Set to true to publish static poses on a "<scoped_entity_name>/pose_static" topic. This will cause only dynamic poses to be published on the "<scoped_entity_name>/pose" topic.
  • <static_update_frequency>: Frequency of static pose publications in Hz. A negative frequency publishes as fast as possible (i.e, at the rate of the simulation step).

Constructor & Destructor Documentation

◆ PosePublisher()

Constructor.

◆ ~PosePublisher()

~PosePublisher ( )
overridedefault

Destructor.

Member Function Documentation

◆ Configure()

void Configure ( const Entity _entity,
const std::shared_ptr< const sdf::Element > &  _sdf,
EntityComponentManager _ecm,
EventManager _eventMgr 
)
overridevirtual

Configure the system.

Parameters
[in]_entityThe entity this plugin is attached to.
[in]_sdfThe SDF Element associated with this system plugin.
[in]_ecmThe EntityComponentManager of the given simulation instance.
[in]_eventMgrThe EventManager of the given simulation instance.

Implements ISystemConfigure.

◆ PostUpdate()

void PostUpdate ( const UpdateInfo _info,
const EntityComponentManager _ecm 
)
overridevirtual

Implements ISystemPostUpdate.


The documentation for this class was generated from the following file: