OdometryPublisher Class Reference

Odometry Publisher which can be attached to any entity in order to periodically publish 2D or 3D odometry data in the form of ignition::msgs::Odometry messages. More...

#include <OdometryPublisher.hh>

Public Member Functions

 OdometryPublisher ()
 Constructor. More...
 
 ~OdometryPublisher () 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
 
void PreUpdate (const ignition::gazebo::UpdateInfo &_info, ignition::gazebo::EntityComponentManager &_ecm) override
 
- Public Member Functions inherited from System
 System ()=default
 Constructor. More...
 
virtual ~System ()=default
 Destructor. More...
 

Detailed Description

Odometry Publisher which can be attached to any entity in order to periodically publish 2D or 3D odometry data in the form of ignition::msgs::Odometry messages.

System Parameters

<odom_frame>: Name of the world-fixed coordinate frame for the is {name_of_model}/odom.

<robot_base_frame>: Name of the coordinate frame rigidly attached to the mobile robot base. This element is optional, and the default value is {name_of_model}/base_footprint.

<odom_publish_frequency>: Odometry publication frequency. This element is optional, and the default value is 50Hz.

<odom_topic>: Custom topic on which this system will publish odometry messages. This element is optional, and the default value is /model/{name_of_model}/odometry.

<odom_covariance_topic>: Custom topic on which this system will publish odometry with covariance messages. This element is optional, and the default value is /model/{name_of_model}/odometry_with_covariance.

<tf_topic>: Custom topic on which this system will publish the transform from odom_frame to robot_base_frame. This element is optional, and the default value is /model/{name_of_model}/pose.

<dimensions>: Number of dimensions to represent odometry. Only 2 and 3 dimensional spaces are supported. This element is optional, and the default value is 2.

<xyz_offset>: Position offset relative to the body fixed frame, the default value is 0 0 0. This offset will be added to the odometry message.

<rpy_offset>: Rotation offset relative to the body fixed frame, the default value is 0 0 0. This offset will be added to the odometry message.

<gaussian_noise>: Standard deviation of the Gaussian noise to be added to pose and twist messages. This element is optional, and the default value is 0.

Constructor & Destructor Documentation

🔗OdometryPublisher()

Constructor.

🔗~OdometryPublisher()

~OdometryPublisher ( )
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.

🔗PreUpdate()

void PreUpdate ( const ignition::gazebo::UpdateInfo _info,
ignition::gazebo::EntityComponentManager _ecm 
)
overridevirtual

Implements ISystemPreUpdate.


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