Gazebo offers a Differential Drive plugin that can be used in ROS. The plugin accepts velocity commands and publishes odometry information. This plugin is useful in learning about moving robot bases with differential drive configuration.
For your reference, you may clone the source code from my git repository.
1 | $ git clone https://kiranpalla@bitbucket.org/kiranpalla/learn-ros.git |
This post assumes you have a URDF description file mybot/urdf/mybot.xacro
with base_footprint
,base_link
, left_wheel
and right_wheel
links. Refer to the git repository if you don’t have a URDF file.
Adding Differential Drive Plugin
Create a new xacro file mybot/urdf/mybot_gazebo_plugins.xacro
and paste below code to add the plugin.
1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 20 | <?xml version="1.0"?> <robot> <!--Gazebo Differential Drive Plugin--> <gazebo> <plugin name="differential_drive_controller" filename="libgazebo_ros_diff_drive.so"> <alwaysOn>true</alwaysOn> <legacyMode>false</legacyMode> <updateRate>40</updateRate> <leftJoint>left_wheel_joint</leftJoint> <rightJoint>right_wheel_joint</rightJoint> <wheelSeparation>${wheel_separation}</wheelSeparation> <wheelDiameter>${wheel_radius * 2}</wheelDiameter> <torque>20</torque> <commandTopic>cmd_vel</commandTopic> <odometryTopic>odom</odometryTopic> <odometryFrame>odom</odometryFrame> <robotBaseFrame>base_footprint</robotBaseFrame> </plugin> </gazebo> </robot> |
Above code is how you would add a Differential Drive Gazebo plugin to the robot model. Any plugin within
<plugin>
tags must be included under <gazebo>
tags. filename
is the gazebo_ros library name containing the plugin implementation.A plugin may have its own parameters. Here left_wheel_joint
and right_wheel_joint
are the wheel joint names already defined in kbot.xacro
. Similarly, values for <wheelSeparation>
and <wheelDiameter>
come from the main xacro file.
This plugin subscribes to the topic /cmd_vel
and publishes topic /odom
. You may add namespaces to avoid confusion (and collision) with similar topics from other robots or other controllers on the same robot.
Finally, the TF frame for odometry is odom
and base frame of the robot is, of course, base_footprint
.
To make this plugin a part of the robot model, include plugin xacro file to the main xacro file mybot_description/urdf/mybot.xacro
1 | <xacro:include filename="$(find mybot_description)/urdf/mybot_gazebo_plugins.xacro"/> |
Using teleop_twist_keyboard to Steer the Robot
ROS provides a package to steer a robot base using the keyboard. A node of package teleop_twist_keyboard publishes a topic called cmd_vel that represents velocity commands for the robot. When using a name-spaced topic, you need to map *cmd_vel* to corresponding topic subscribed by Differential Drive Plugin (i.e. publisher-subscriber binding).
In one terminal, launch *rviz* and Gazebo simulator.
1 | $ roslaunch mybot_description mybot.launch |
In another terminal, launch *teleop_twist_keyboard* node.
1 | $ rosrun teleop_twist_keyboard teleop_twist_keyboard.py |
Staying on the terminal, use keys to steer the robot. For example, press ‘i’ to move the robot forward. Alternatively, you may implement a custom publisher to send simple navigation (velocity) commands using geometry_msgs/Twist
ROS messages.