---
title:Autonomous Differential Drive Mobile Robot - Gazebo Package
excerpt: "ROS Gazebo Package for ROS Melodic running on a Raspberry Pi 4 for an autonomous 2WD Robot to act in an environment according to sensor information."
categories: [robotics]
tags: [2wd, differential drive, robot, ros, noetic, raspberry, pi, autonomous, ubuntu, focal, package, gazebo, simulation]
---
As described in the Creating your own Gazebo ROS Package, it is common in ROS to create a package that contains all the world files and launch files used with Gazebo. These files are located in a ROS package named /MYROBOT_gazebo
. For DiffBot the package is named diffbot_gazebo
. Another example that follows best pratices is rrbot
which can be found in the gazebo_ros_demos repository.
fjp@ubuntu:~/git/diffbot/ros/src$ catkin create pkg diffbot_gazebo
Creating package "diffbot_gazebo" in "/home/fjp/git/diffbot/ros/src"...
Created file diffbot_gazebo/package.xml
Created file diffbot_gazebo/CMakeLists.txt
Successfully created package files in /home/fjp/git/diffbot/ros/src/diffbot_gazebo.
The diffbot_gazebo
package contains a launch file to lauch a world in Gazebo and spawn the robot model,
which is defined in the previously created diffbot_description
package.
For the launch files the convention is to have a folder named launch
and for Gazebo world files a folder named world
inside a package.
fjp@ubuntu:~/git/diffbot/ros/src/diffbot_gazebo$ mkdir launch world
Inside the launch
folder is the diffbot.launch
.
<launch>
<!-- these are the arguments you can pass this launch file, for example paused:=true -->
<arg name="paused" default="false"/>
<arg name="use_sim_time" default="true"/>
<arg name="gui" default="true"/>
<arg name="headless" default="false"/>
<arg name="debug" default="false"/>
<!-- We resume the logic in empty_world.launch, changing only the name of the world to be launched -->
<include file="$(find gazebo_ros)/launch/empty_world.launch">
<arg name="world_name" value="$(find diffbot_gazebo)/worlds/diffbot.world"/>
<arg name="debug" value="$(arg debug)" />
<arg name="gui" value="$(arg gui)" />
<arg name="paused" value="$(arg paused)"/>
<arg name="use_sim_time" value="$(arg use_sim_time)"/>
<arg name="headless" value="$(arg headless)"/>
</include>
</launch>
In the world
folder of the diffbot_gazebo
package is the diffbot.world
file:
<?xml version="1.0" ?>
<sdf version="1.4">
<world name="default">
<include>
<uri>model://ground_plane</uri>
</include>
<include>
<uri>model://sun</uri>
</include>
<include>
<uri>model://gas_station</uri>
<name>gas_station</name>
<pose>-2.0 7.0 0 0 0 0</pose>
</include>
</world>
</sdf>
With these files build the catkin workspace and source it to make the new diffbot_gazebo
package visible to roslaunch
:
catkin build
source devel/setup.zsh
Then its possible to launch the diffbot.launch
with:
roslaunch diffbot_gazebo diffbot.launch
This will lead to the following output:
roslaunch diffbot_gazebo diffbot.launch
... logging to /home/fjp/.ros/log/6be90ef2-fdd8-11ea-9cb3-317fd602d5f2/roslaunch-tensorbook-393333.log
Checking log directory for disk usage. This may take a while.
Press Ctrl-C to interrupt
Done checking log file disk usage. Usage is <1GB.
started roslaunch server http://tensorbook:32837/
SUMMARY
========
PARAMETERS
* /gazebo/enable_ros_network: True
* /rosdistro: noetic
* /rosversion: 1.15.8
* /use_sim_time: True
NODES
/
gazebo (gazebo_ros/gzserver)
gazebo_gui (gazebo_ros/gzclient)
ROS_MASTER_URI=http://localhost:11311
process[gazebo-1]: started with pid [393352]
process[gazebo_gui-2]: started with pid [393357]
[ INFO] [1600950165.494721382]: Finished loading Gazebo ROS API Plugin.
[ INFO] [1600950165.495515766]: waitForService: Service [/gazebo/set_physics_properties] has not been advertised, waiting...
[ INFO] [1600950165.649461740]: Finished loading Gazebo ROS API Plugin.
[ INFO] [1600950165.650277038]: waitForService: Service [/gazebo_gui/set_physics_properties] has not been advertised, waiting...
[ INFO] [1600950166.640929113]: waitForService: Service [/gazebo/set_physics_properties] is now available.
[ INFO] [1600950166.659917502, 0.007000000]: Physics dynamic reconfigure ready.
Also, the Gazebo simulator will open a new window with the objects defined in diffbot.world
except for the Gas station because it is a model
that has to be downloaded first, which is happening in the background. TODO: gas station is not showing this way.

To get the Gas station or other available models it is possible to clone the gazebo models repository into your /home/your_username/.gazebo
folder, e.g.:
/home/fjp/.gazeb$ git clone osrf/gazebo_models
Then add this path inside Gazebo to insert these models into your world file.
According to the Gazebo roslaunch tutorial the recommended way
to spawn a robot into Gazebo is to use a launch file. Therefore, edit the diffbot.launch
inside the diffbot_gazebo
package by adding the following inside the <launch> </launch
tag:
<!-- Load the URDF into the ROS Parameter Server -->
<param name="robot_description"
command="$(find xacro)/xacro --inorder '$(find diffbot_description)/urdf/diffbot.xacro'" />
<!-- Run a python script to the send a service call to gazebo_ros to spawn a URDF robot -->
<node name="urdf_spawner" pkg="gazebo_ros" type="spawn_model" respawn="false" output="screen"
args="-urdf -model diffbot -param robot_description"/>
See also the complete diffbot.launch
file.
This will open Gazebo simulator and show the DiffBot model:

Note that the robot cannot be moved without having either a Gazebo plugin loaded or making use of ROS Control
and its Gazebo plugin gazebo_ros_control
, see also the Gazebo ROS Control Tutorial. Using the ROS Control and its Gazebo plugin is done in case of DiffBot.
An alternative would be to use the existing differential_drive_controller
Gazebo plugin without having to rely on ROS Control.
The next section explains the diffbot_control
package in more detail and how to setup the
diff_drive_controller
from the ros_controllers
package.
To add sensors to a robot model make use of link and joint tags to define the desired location and shape, possibly using meshes.
For the simulation of these sensor there exist common Gazebo plugins that can be used. See, the [Tutorial: Using Gazebo plugins with ROS]
for existing plugins and more details how to use them. For a full list of plugins see also gazebo_ros_pkgs
which is a package or interface
for using ROS with the Gazebo simulator.
This section follows Gazebo tutorial Adding a Camera.
This section follows Gazebo tutorial Adding a Laser GPU.
See the source of the gazebo_ros_range
plugin.
This section follows Gazebo tutorial [Adding an IMU](http://gazebosim.org/tutorials?tut=ros_gzplugins#IMU(GazeboRosImu). Note use GazeboRosImuSensor?
A quick way to verify if the conversion from xacro to urdf to sdf is working is the following (source: Tutorial URDF in Gazebo):
First convert the xacro model to a urdf model with the xacro
command:
xacro src/diffbot_description/urdf/diffbot.xacro -o diffbot.urdf
This will output the urdf into a file named diffbot.urdf
in the current working directory.
Then use the gz
command to create a sdf:
# gazebo3 and above
gz sdf -p MODEL.urdf
DiffBot sdf.
```xml -0.012273 0 0.040818 0 -0 0 5.5 0.0387035 0 0.000552273 0.0188626 0 0.0561591 0 0 0 0 -0 0 0.001 0.001 0.001 0 0 0.04 0 -0 0 0.3 0.15 0.02 -0.135 0 0.029 0 -0 0 0.025 0 0 0.04 0 -0 0 0.3 0.15 0.02 <script> Gazebo/White file://media/materials/scripts/gazebo.material </script> -0.115 0 0.029 0 -0 0 0.025 1 0.105 -0.085 0.04 0 -0 0 base_footprint front_left_wheel 0 1 0 -1e+16 1e+16 0 0 0 0 0 0 -0 0 0 0 0 0 -0 0 2.5 0.00108333 0 0 0.00108333 0 0.002 0 0 0 1.5708 -0 0 0.02 0.04 1e+07 1 1 1 1 0 0 0 0 0 1.5708 -0 0 0.02 0.04 <script> Gazebo/Grey file://media/materials/scripts/gazebo.material </script> 1 0.105 0.085 0.04 0 -0 0 base_footprint front_right_wheel 0 1 0 -1e+16 1e+16 0 0 0 0 0 0 -0 0 0 0 0 0 -0 0 2.5 0.00108333 0 0 0.00108333 0 0.002 0 0 0 1.5708 -0 0 0.02 0.04 1e+07 1 1 1 1 0 0 0 0 0 1.5708 -0 0 0.02 0.04 <script> Gazebo/Grey file://media/materials/scripts/gazebo.material </script> 1 /diffbot gazebo_ros_control/DefaultRobotHWSim 0 1 Debug 0 / 1 0 1 100.0 front_left_wheel_joint front_right_wheel_joint 0.3 0.08 1 30 1.8 cmd_vel odom odom base_footprint ```In case the output looks like the following, there are most certainly missing <inertial>
tags in the <link>
tag.
For the Gazebo simulator the <inertial>
must be present, in order to simulate the dynamics of the robot.
See also http://wiki.ros.org/urdf/XML/link and the Gazebo tutorials on URDF.
<sdf version='1.7'>
<model name='diffbot'/>
</sdf>