Gazebo Sim

API Reference

9.0.0
DiffDrive Class Reference

Differential drive controller which can be attached to a model with any number of left and right wheels. More...

#include <DiffDrive.hh>

Public Member Functions

 DiffDrive ()
 Constructor.
 
 ~DiffDrive () override=default
 Destructor.
 
void Configure (const Entity &_entity, const std::shared_ptr< const sdf::Element > &_sdf, EntityComponentManager &_ecm, EventManager &_eventMgr) override
 Configure the system.
 
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.
 
virtual ~System ()=default
 Destructor.
 

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.
 
- Static Public Attributes inherited from System
static constexpr PriorityType kDefaultPriority = {0}
 Default priority value for execution order of the PreUpdate and Update phases.
 
static constexpr std::string_view kPriorityElementName
 Name of the XML element from which the priority value will be parsed.
 

Detailed Description

Differential drive controller which can be attached to a model with any number of left and right wheels.

System Parameters

  • <left_joint>: Name of a joint that controls a left wheel. This element can appear multiple times, and must appear at least once.
  • <right_joint>: Name of a joint that controls a right wheel. This element can appear multiple times, and must appear at least once.
  • <wheel_separation>: Distance between wheels, in meters. This element is optional, although it is recommended to be included with an appropriate value. The default value is 1.0m.
  • <wheel_radius>: Wheel radius in meters. This element is optional, although it is recommended to be included with an appropriate value. The default value is 0.2m.
  • <odom_publish_frequency>: Odometry publication frequency. This element is optional, and the default value is 50Hz.
  • <topic>: Custom topic that this system will subscribe to in order to receive command velocity messages. This element if optional, and the default value is /model/{name_of_model}/cmd_vel.
  • <odom_topic>: Custom topic on which this system will publish odometry messages. This element if optional, and the default value is /model/{name_of_model}/odometry.
  • <tf_topic>: Custom topic on which this system will publish the transform from frame_id to child_frame_id. This element is optional, and the default value is /model/{name_of_model}/tf.
  • <frame_id>: Custom frame_id field that this system will use as the origin of the odometry transform in both the <tf_topic> gz.msgs.Pose_V message and the <odom_topic> gz.msgs.Odometry message. This element if optional, and the default value is {name_of_model}/odom.
  • <child_frame_id>: Custom child_frame_id that this system will use as the target of the odometry trasnform in both the <tf_topic> gz.msgs.Pose_V message and the <odom_topic> gz.msgs.Odometry message. This element if optional, and the default value is {name_of_model}/{name_of_link}.
  • <min_velocity>: Sets both the minimum linear and minimum angular velocity.
  • <max_velocity>: Sets both the maximum linear and maximum angular velocity.
  • <min_acceleration>: Sets both the minimum linear and minimum angular acceleration.
  • <max_acceleration>: Sets both the maximum linear and maximum angular acceleration.
  • <min_jerk>: Sets both the minimum linear and minimum angular jerk.
  • <max_jerk>: Sets both the maximum linear and maximum angular jerk.
  • <min_linear_velocity>: Sets the minimum linear velocity. Overrides <min_velocity> if set.
  • <max_linear_velocity>: Sets the maximum linear velocity. Overrides <max_velocity> if set.
  • <min_angular_velocity>: Sets the minimum angular velocity. Overrides <min_velocity> if set.
  • <max_angular_velocity>: Sets the maximum angular velocity. Overrides <max_velocity> if set.
  • <min_linear_acceleration>: Sets the minimum linear acceleration. Overrides <min_acceleration> if set.
  • <max_linear_acceleration>: Sets the maximum linear acceleration. Overrides <max_acceleration> if set.
  • <min_angular_acceleration>: Sets the minimum angular acceleration. Overrides <min_acceleration> if set.
  • <max_angular_acceleration>: Sets the maximum angular acceleration. Overrides <max_acceleration> if set.
  • <min_linear_jerk>: Sets the minimum linear jerk. Overrides <min_jerk> if set.
  • <max_linear_jerk>: Sets the maximum linear jerk. Overrides <max_jerk> if set.
  • <min_angular_jerk>: Sets the minimum angular jerk. Overrides <min_jerk> if set.
  • <max_angular_jerk>: Sets the maximum angular jerk. Overrides <max_jerk> if set.

Constructor & Destructor Documentation

◆ DiffDrive()

DiffDrive ( )

Constructor.

◆ ~DiffDrive()

~DiffDrive ( )
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 UpdateInfo _info,
EntityComponentManager _ecm 
)
overridevirtual

Implements ISystemPreUpdate.


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