Class GazeboRosDiffDrive

Inheritance Relationships

Base Type

  • public gazebo::ModelPlugin

Class Documentation

class GazeboRosDiffDrive : public gazebo::ModelPlugin

A differential drive plugin for gazebo. Based on the diffdrive plugin.

Example Usage:

<plugin name="gazebo_ros_diff_drive" filename="libgazebo_ros_diff_drive.so">

  <ros>

    <!-- Add a namespace -->
    <namespace>/test</namespace>

  </ros>

  <!-- Update rate in Hz -->
  <update_rate>50</update_rate>

  <!-- wheels -->
  <left_joint>left_wheel_joint</left_joint>
  <right_joint>right_wheel_joint</right_joint>

  <!-- kinematics -->
  <wheel_separation>1.25</wheel_separation>
  <wheel_diameter>0.6</wheel_diameter>

  <!-- limits -->
  <max_wheel_torque>20</max_wheel_torque>
  <max_wheel_acceleration>1.0</max_wheel_acceleration>

  <!-- input -->
  <command_topic>cmd_vel</command_topic>

  <!-- output -->
  <publish_odom>true</publish_odom>
  <publish_odom_tf>true</publish_odom_tf>
  <publish_wheel_tf>true</publish_wheel_tf>

  <odometry_topic>odom</odometry_topic>
  <odometry_frame>odom</odometry_frame>
  <robot_base_frame>chassis</robot_base_frame>

</plugin>

Public Functions

GazeboRosDiffDrive()

Constructor.

~GazeboRosDiffDrive()

Destructor.

Protected Functions

void Load(gazebo::physics::ModelPtr _model, sdf::ElementPtr _sdf) override
void Reset() override