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 gz::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 UpdateInfo &_info, 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
Odometry Publisher which can be attached to any entity in order to periodically publish 2D or 3D odometry data in the form of gz::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 fromodom_frame
torobot_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.
Components
This system uses the following components:
- components::Pose: Pose represented by gz::math::Pose3d. Used to calculate the odometry to publish.
Constructor & Destructor Documentation
◆ OdometryPublisher()
Constructor.
◆ ~OdometryPublisher()
|
overridedefault |
Destructor.
Member Function Documentation
◆ Configure()
|
overridevirtual |
Configure the system.
- Parameters
-
[in] _entity The entity this plugin is attached to. [in] _sdf The SDF Element associated with this system plugin. [in] _ecm The EntityComponentManager of the given simulation instance. [in] _eventMgr The EventManager of the given simulation instance.
Implements ISystemConfigure.
◆ PostUpdate()
|
overridevirtual |
Implements ISystemPostUpdate.
◆ PreUpdate()
|
overridevirtual |
Implements ISystemPreUpdate.
The documentation for this class was generated from the following file: