Tutorial 7: Simulation - Basic issues

Objective: This tutorial session is devoted to learn the basic issues related to simulation using Gazebo within a ROS environment.

Contents

After this session you will be able to:

  • Understand the Gazebo simulation infrastructure: the files to model the world, the simulation server and the client, the GUI and the plugins.

  • Understand how Gazebo is integrated within ROS by means of the gazebo_ros package: the topics and the services used to communicate with the simulated environments.

  • Use Gazebo from ROS by configuring launch files and tunning the urdf robot models.

Provided packages:

This tutorial will use the following packages:

Package rrbot_description
Package rrbot_gazebo
Package gazebo_plugin_demo
Package gazebo_ros_plugin_demo

Prepare the catkin workspace to work with them:

  1. If you have not yet done so, follow the steps in Exercise 0 to:

  • clone in your ~/git-projects folder the meta-repository containing all the required packages,

  • create the catkin workspace folders (use catkin_ws7 for the current tutorial).

  1. In your catkin_ws7/src folder create a symbolic link to the packages to be used:

$ ln -s ~/git-projects/all_introduction_to_ros_packages/rrbot_description
$ ln -s ~/git-projects/all_introduction_to_ros_packages/rrbot_gazebo
$ ln -s ~/git-projects/all_introduction_to_ros_packages/gazebo_plugin_demo
$ ln -s ~/git-projects/all_introduction_to_ros_packages/gazebo_ros_plugin_demo

References:

This tutorial is partially based on several of the tutorials from gazebosim.org and on chapter 3 of the book Mastering ROS for Robotics Programming from Lentin Joseph.

Complementary tutorials:

Gazebo basics

Gazebo is a simulation tool for robotic systems that has a robust physics engine, high-quality graphics, and convenient programmatic and graphical interfaces. It is a standalone application that is also integrated as a ROS package.

Gazebo files

To run a Gazebo simulation you need:

  • A world file: A file with extension .world that contains all the elements in a simulation, including robots, lights, sensors, and static objects, formatted using the Simulation Description Format (SDF). Some world files can be found at <install_path>/share/gazebo-<version>/worlds (e.g. /usr/share/gazebo-11/worlds).

  • Model files: SDF files used to describe objects and robots (one per file, i.e. they contain a single <model> … </model>).

    The components of a model are:

    • Links: A link contains the physical properties of one body of the model. It contains collision elements to encapsulate the geometry used for collision checking, (optional) visual elements used to visualize parts of a link, an inertial element to describe the dynamic properties of the link (such as mass and rotational inertia matrix), (optional) sensor elements to collect data from the world for use in plugins, (optional) light elements to describe light sources attached to the link.

    • Joints (optional): A joint connects two links. A parent and child relationship is established along with other parameters such as axis of rotation, and joint limits.

    • Plugins (optional): A plugin is a shared library created by a third party to control a model.

    <model name="horseB1">
     <pose>0 0 0.5 0 0 0</pose>
      <link name="link">
        <collision name="collision">
          <geometry>
            <box>
              <size>1 1 1</size>
            </box>
          </geometry>
        </collision>
        <visual name="visual">
          <geometry>
            <uri>model://horseB1/meshes/horseB1.dae</uri>
          </geometry>
        </visual>
      </link>
    </model>
    

    Models are included in world files using the include tag:

    <?xml version="1.0" ?>
    <sdf version="1.5">
      <world name="default">
        <!-- A global light source -->
        <include>
          <uri>model://sun</uri>
        </include>
        <!-- A ground plane -->
        <include>
          <uri>model://ground_plane</uri>
        </include>
        <include>
          <uri>model://horseB1</uri>
        </include>
       </world>
     </sdf>
    

    The Gazebo tutorials Make a model and Model Editor will guide you to build your models. A Gazebo model database is available from a Bitbucket repository.

    The Gazebo tutorial Building a world will guide you to build your own world.

Gazebo executables

The gazebo command actually runs two different executables (that can be run separately):

  • gzserver: Is the core of gazebo and it runs the physics update-loop and sensor data generation, and can be used independently of a graphical interface.

  • gzclient: Is a Qt-based user interface. Multiple instances can be executed.

Gazebo uses some environment variables to locate files. Default values that work for most cases are compiled in, i.e. you do not need to set them, and are also included in /usr/share/gazebo/setup.sh:

1
2
3
4
5
6
7
export GAZEBO_MASTER_URI=http://localhost:11345
export GAZEBO_MODEL_DATABASE_URI=http://models.gazebosim.org
export GAZEBO_RESOURCE_PATH=/usr/share/gazebo-11:${GAZEBO_RESOURCE_PATH}
export GAZEBO_PLUGIN_PATH=/usr/lib/x86_64-linux-gnu/gazebo-11/plugins:${GAZEBO_PLUGIN_PATH}
export GAZEBO_MODEL_PATH=/usr/share/gazebo-11/models:${GAZEBO_MODEL_PATH}
export LD_LIBRARY_PATH=${LD_LIBRARY_PATH}:/usr/lib/x86_64-linux-gnu/gazebo-11/plugins
export OGRE_RESOURCE_PATH=/usr/lib/x86_64-linux-gnu/OGRE-1.9.0
  • GAZEBO_MASTER_URI: URI of the Gazebo master. This specifies the IP and port where the server will be started and tells the clients where to connect to.

  • GAZEBO_MODEL_DATABASE_URI: URI of the online model database where Gazebo will download models from.

  • GAZEBO_RESOURCE_PATH: colon-separated set of directories where Gazebo will search for other resources such as world and media files.

  • GAZEBO_PLUGIN_PATH: colon-separated set of directories where Gazebo will search for the plugin shared libraries at runtime.

  • GAZEBO_MODEL_PATH: colon-separated set of directories where Gazebo will search for models

You can change these variables in the /usr/share/gazebo/setup.sh file and source it if you want to e.g. extend the path it searches for models.

The GUI

Run gazebo opening an empty world:

$ gazebo

Information on the pannels, toolbars and mouse control can be found in the GUI tutorial (use the F11 key to change the full screen mode when desired).

Close gazebo and reopen it loading a non-empty world (this may take a while depending on the world selected), by passing a <world_filename> which can be:

  1. relative to the current directory,

  2. an absolute path, or

  3. relative to a path component in GAZEBO_RESOURCE_PATH.

For instance, the worlds installed with Gazebo are stored at /usr/share/gazebo-11/worlds, with the path /usr/share/gazebo-11 being defined in GAZEBO_RESOURCE_PATH. Then, they can be called by worlds/<world_name>, where <world_name> is a world, e.g.:

$ gazebo worlds/stacks.world
../_images/stacks_world.png

Exercise

From the World tab in the left panel, select one of the cubes or spheres in the bottom of the columns and change its pose by e.g. moving it in the x-direction, and observe the simulation of the objects falling.

Try another world:

$ gazebo worlds/simple_arm.world

Exercise

Click and drag the bar of the right panel to open it (it is hidden by default). Select the robot by clicking on it and then, from the Force tab in the right panel, apply a 0.5 Nm at the arm_shoulder_pan_joint, and observe the robot moving.

Gazebo plugins

A plugin is a chunk of code that is compiled as a shared library and inserted into the simulation. Plugins have direct access to all the functionality of Gazebo through the standard C++ classes. There are currently 6 types of plugins

  1. World: Attached to the world to control world properties.

<?xml version="1.0" ?>
<sdf version="1.4">
  <world name="default">
    <include>
      <uri>model://ground_plane</uri>
    </include>

    <include>
      <uri>model://sun</uri>
    </include>

    <!-- reference to your plugin -->
    <plugin name="hello_world_plugin" filename="libhello_world_plugin.so"/>
  </world>
</sdf>
  1. Model: Attached to a model to control the joints and the state.

<model name="box">
 <pose>0 0 0.5 0 0 0</pose>
  <link name="link">
    <collision name="collision">
      <geometry>
        <box>
          <size>1 1 1</size>
        </box>
      </geometry>
    </collision>
    <visual name="visual">
      <geometry>
        <box>
          <size>1 1 1</size>
        </box>
      </geometry>
    </visual>
  </link>
 <plugin name="model_push" filename="libmodel_push.so"/>
</model>
  1. Sensor: Attached to a sensor to acquire sensor information and control sensor properties.

  2. System: Specified at the command line this plugin loads first during a Gazebo startup, to give the user control over the startup process.

  3. Visual: A plugin to access the visual rendering functions.

  4. GUI: A plugin loaded within the gzclient on startup to control the GUI.

To illustrate Gazebo plugins, the folder gazebo_plugin_demo contains:

  • A world plugin that simply writes “Hello world” when the world is loaded.

  • A model plugin that applies a linear velocity to the model.

Move to that directory and follow the steps to execute them:

$ mkdir build
$ cd build
$ cmake ..
$ make
$ export GAZEBO_PLUGIN_PATH=${GAZEBO_PLUGIN_PATH}:$(pwd)
$ gazebo ../worlds/hello.world --verbose

You can gain insight on the world plugin with the tutorial Overview of Gazebo Plugins.

Run now the model plugin by launching Gazebo in a paused state and then clicking on the play button in the gui to unpause the simulation. You should see the box moving:

$ gazebo -u ../worlds/model_push.world

You can gain insight on the model plugins with the tutorial Model plugins.

Integration to ROS

A set of ROS packages named gazebo_ros_pkgs are provided for the Gazebo-ROS integration:

  • gazebo_ros: Package that wraps gzserver and gzclient by using two Gazebo plugins that provide the necessary ROS interface for messages and services:

    • The gazebo_ros_api_plugin: enables a user to manipulate the properties of the simulation environment over ROS, as well as spawn and introspect on the state of models in the environment.

    • The gazebo_ros_paths_plugin: allows Gazebo to find ROS resources, i.e. resolving ROS package path names.

  • gazebo_msgs: Msg and Srv data structures for interacting with Gazebo from ROS.

  • gazebo_plugins: Robot-independent Gazebo plugins related to sensors, like gazebo_ros_camera or gazebo_ros_laser, or motors, like gazebo_ros_joint_trajectory or gazebo_ros_diffdrive.

Starting Gazebo

The available nodes to run are:

../_images/gazebo_ros_executables.png

Use them to start gazebo and spawn the rrbot robot and a coke can:

$ catkin build rrbot_description
$ catkin build rrbot_gazebo
$ source devel/setup.bash
$ roscore
$ rosrun gazebo_ros gazebo `rospack find rrbot_gazebo`/worlds/rrbot.world
$ rosrun xacro xacro `rospack find rrbot_description`/urdf/rrbot.xacro > `rospack find rrbot_description`/urdf/rrbot.urdf
$ rosparam load `rospack find rrbot_description`/urdf/rrbot.urdf robot_description
$ rosrun gazebo_ros spawn_model -param robot_description -urdf -model rrbot1 -robot_namespace rrbot1 -y 1
$ rosrun gazebo_ros spawn_model -database coke_can -sdf -model coke_can -y 0.2 -x 0.2

These nodes, however, will be usually run from launch files, as detailed in Section Configuring launch files.

Gazebo published parameters

/use_sim_time: A bool used to notify ROS to use published /clock topic for ROS time. Check it:

$ rosparam get /use_sim_time

Gazebo topics

Subscribed topics

Gazebo subscribes to the following topics that can be used to set the pose and twist of a model:

  • ~/set_link_state: A gazebo_msgs/LinkState message used to set the state (pose/twist) of a link.

  • ~/set_model_state: A gazebo_msgs/ModelState message used to set the state (pose/twist) of a model.

Verify for the the set_model_state topic:

$ rostopic list
$ rostopic type /gazebo/set_model_state
$ rosmsg show  gazebo_msgs/ModelState

Publish the set_model_state topic to change the location of the coke can with the following instruction (recall that when using ROS command-line tools you can press the tab key to see all the required fields, e.g. press the tab after typing $ rostopic pub -r 20 /gazebo/set_model_state):

$ rostopic pub -r 20 /gazebo/set_model_state gazebo_msgs/ModelState '{model_name: coke_can, pose: { position: { x: 1, y: 0, z: 2 }, orientation: {x: 0, y: 0.491983115673, z: 0, w: 0.870604813099 } }, twist: { linear: { x: 0, y: 0, z: 0 }, angular: { x: 0, y: 0, z: 0}  }, reference_frame: world }'

Stop the publishing by pressing Ctrl+C and see the can falling.

Published topics

Gazebo advertises the clock and the state of the model:

  • /clock: A rosgraph_msgs/Clock message with the simulation time, to be used with /use_sim_time parameter.

  • ~/link_states: A gazebo_msgs/LinkStates message with the states of all the links in simulation.

  • ~/model_states: A gazebo_msgs/ModelStates message with states of all the models in simulation.

Echo the model_states topic to get information of the models in the world:

$ rostopic echo -n 1 /gazebo/model_states

Services

To set/get the state and properties

Several services are provided to set and get the state and different properties:

  • ~/set_link_properties: A service of type gazebo_msgs/SetLinkProperties to set the link properties (name, pose, mass and inertia).

  • ~/set_physics_properties: A service of type gazebo_msgs/SetPhysicsProperties to set the physics properties, like the time step or the gravity.

  • ~/set_model_configuration: A service of type gazebo_msgs/SetModelConfiguration to set model joint positions without invoking dynamics.

  • ~/set_joint_properties: A service of type gazebo_msgs/SetJointProperties to set the ODE joint properties like cfm or erp.

  • ~/set_link_state: A service of type gazebo_msgs/SetLinkState to set the state of the link (name, pose and twist).

  • ~/set_model_state: A service of type gazebo_msgs/SetModelState to set the state of the model (name, pose and twist).

  • ~/get_model_properties: A service of type gazebo_msgs/GetModelProperties that returns the properties of a model.

  • ~/get_model_state: A service of type gazebo_msgs/GetModelState that returns the states of a model.

  • ~/get_world_properties: A service of type gazebo_msgs/GetWorldProperties that returns the properties of the simulation world.

  • ~/get_joint_properties: A service of type gazebo_msgs/GetJointProperties that returns the properties of a joint.

  • ~/get_link_properties: A service of type gazebo_msgs/GetLinkProperties that returns the properties of a link.

  • ~/get_link_state: A service of type gazebo_msgs/GetLinkState that returns the state of a link.

  • ~/get_physics_properties: A service of type gazebo_msgs/GetPhysicsProperties that returns the properties of the physics engine used.

Exercise

Use the Service Type Browser of rqt to see the request and response of these services.

Get world and model properties:

$ rosservice list
$ rosservice call /gazebo/get_world_properties
$ rosservice call /gazebo/get_model_properties '{model_name: rrbot1}'

Now let’s place the coke can next to the robot and try to hit it. End by verifying its final pose:

$ rosservice call /gazebo/set_model_state '{model_state: { model_name: coke_can, pose: { position: { x: -0.3, y: 1.2 ,z: 0 }, orientation: {x: 0, y: 0.0, z: 0, w: 1.0 } }, twist: { linear: {x: 0.0 , y: 0 ,z: 0 } , angular: { x: 0.0 , y: 0 , z: 0.0 } } , reference_frame: world } }'
$ rosservice call /gazebo/get_joint_properties 'joint1'
$ rosservice call /gazebo/get_joint_properties 'joint2'
$ rosservice call /gazebo/set_model_configuration '{model_name: 'rrbot1', urdf_param_name: '', joint_names: ['joint1', 'joint2'], joint_positions: [-3.5, -1.5]}'
$ rosservice call /gazebo/get_model_state '{model_name: coke_can}'

Try to improve the hit!

For force control

These services allow the user to apply wrenches and forces to bodies and joints in simulation:

  • ~/apply_body_wrench: A service of type gazebo_msgs/ApplyBodyWrench used to apply a wrench to a body.

  • ~/apply_joint_effort: A service of type gazebo_msgs/ApplyJointEffort used to apply an effort to a joint.

  • ~/clear_joint_forces: A service of type gazebo_msgs/JointRequest used to clear applied efforts to a joint.

  • ~/clear_body_wrenches: A service of type gazebo_msgs/ClearBodyWrenches used to clear applied wrenches to a body.

Exercise

Use the Service Type Browser of rqt to see the details of these services.

Apply an effort to joint2 for 1 s (recall that when using ROS command-line tools you can press the tab key to see all the required fields, e.g. press the tab after typing $ rosservice call /gazebo/apply_joint_effort):

$ rosservice call /gazebo/apply_joint_effort '{joint_name: "joint2", effort: 5.0, start_time: { secs: 0, nsecs: 0 }, duration: { secs: 1, nsecs: 0 } }'

Apply a wrench to the coke can for 1 s:

$ rosservice call /gazebo/apply_body_wrench '{body_name: "coke_can::link", reference_frame: "world", reference_point: { x: 0.0, y: 0.0, z: 0.0 }, wrench: { force: { x: 5.0, y: 0.0, z: 0.0 }, torque: { x: 0.0, y: 0.0, z: 0.0 } }, start_time: { secs: 0, nsecs: 0 }, duration: { secs: 1, nsecs: 0 } }'

Exercise

Relocate the coke can to its initial pose and repeat the hitting by applying an effort to joint1.

For controlling the simulation

The following are std_srvs/Empty services that allow the user to pause and unpause physics in simulation:

  • ~/pause_physics: Pause physics updates.

  • ~/unpause_physics: Resume physics updates.

  • ~/reset_simulation: Resets the entire simulation including the time.

  • ~/reset_world: Resets the model’s poses.

$ rosservice call /gazebo/reset_world

Configuring launch files

Gazebo is usually run using launch files. Start by trying the empty world:

$ roslaunch gazebo_ros empty_world.launch

Other demo worlds are already included in the gazebo_ros package. Kill Gazebo using Ctrl+C (this may take a while) and restart it with another one:

$ rosls gazebo_ros/launch
$ roslaunch gazebo_ros mud_world.launch

roslaunch arguments

Several arguments can be set in the launch files to change the behavior of Gazebo. The empty_world.launch file contains default values for these arguments. Other launch files include the empty_world.launch file and then set the arguments with the required values, starting with the world_name:

  • world_name: The world_name with respect to GAZEBO_RESOURCE_PATH environmental variable,

  • paused: Start Gazebo in a paused state (default false),

  • use_sim_time: Tells ROS nodes asking for time to get the Gazebo-published simulation time, published over the ROS topic /clock (default true),

  • gui: Launch the user interface window of Gazebo (default true),

  • recording: Enable gazebo state log recording (default false),

  • headless: (deprecated) changed to recording.

  • debug: Start gzserver in debug mode using gdb (default false).

As an example the mud_world.launch is:

 1
 2
 3
 4
 5
 6
 7
 8
 9
10
11
12
13
<?xml version="1.0"?>
<launch>
 <!-- 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="worlds/mud.world"/> <!-- Note: the world_name is with respect to GAZEBO_RESOURCE_PATH environmental variable -->
   <arg name="paused" value="false"/>
   <arg name="use_sim_time" value="true"/>
   <arg name="gui" value="true"/>
   <arg name="headless" value="false"/> <!-- Inert - see gazebo_ros_pkgs issue #491 -->
   <arg name="recording" value="false"/>
   <arg name="debug" value="false"/>
 </include>
</launch>

Spawning models

Launch files run the spawn_model node used before to spawn the urdf models of the robots. As an example, the rrbot_world.launch file first loads the URDF model into the robot_description parameter and then runs the spawn_model node:

 1
 2
 3
 4
 5
 6
 7
 8
 9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
<?xml version="1.0" ?>
<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 rrbot_gazebo)/worlds/rrbot.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>

 <!-- Load the URDF into the ROS Parameter Server -->
 <param name="robot_description"
   command="$(find xacro)/xacro --inorder '$(find rrbot_description)/urdf/rrbot.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 rrbot -param robot_description"/>

 <!-- ros_control rrbot launch file -->
 <!--include file="$(find rrbot_control)/launch/rrbot_control.launch" /-->

</launch>

Exercise

Quit gazebo and launch the rrbot_world.launch file from the rrbot_gazebo package.

Modeling robots for Gazebo

Gazebo ROS package structure

The following file hierarchy is the standard for organizing the robot information for applications using ROS with Gazebo:

../_images/package_structure.png

Exercise

Browse the rrbot_description and the rrbot_gazebo folders describing the rrbot.

Tunning URDF models

To use a URDF file in Gazebo, the following is required:

  • An <inertia> element within each <link> element must be properly specified and configured.

  • A <link name=”world”/> link has to be added if the robot should be rigidly attached to the world/base_link:

    ../_images/fixed_robot.png
  • Some <gazebo> elements, detailed below, are an extension to the URDF and have to be added for simulation purposes in Gazebo. There are three different types of <gazebo> elements, according to the reference property included:

    • For the <robot> tag: <gazebo>, i.e. with no reference.

    • For <link> tags: <gazebo reference=’link_name’>

    • For <joint> tags: <gazebo reference=’joint_name’>

    Sometimes, as done with the rrbot robot, all the <gazebo> elements are grouped in a single file that is then included in the URDF file, e.g. in the rrbot.urdf file we can find this line:

    ../_images/include_gazebo.png

Gazebo will then convert the URDF to SDF automatically.

Robot

When the <gazebo> element has no reference=”” property, it is assumed that it is for the whole robot model.

Some parameters can be used within this <gazebo> element:

  • A bool parameter called static to specify if the model is immovable (when set to true), or if it is simulated in the dynamics engine (when set to false).

  • Parameters that will be directly inserted into the SDF <model>, like plugins. For instance for the rrbot the following is included:

../_images/gazebo_robot.png

Joints

Gazebo uses the damping and friction properties found in the <joint> tags of URDF for simulation purposes, but the <gazebo> element can be used to include some extra parameters to fine-tune the dynamic behavior of a given joint called e.g. “joint_name” if the reference=”joint_name” property is used.

What follows is the list of parameters included in the <gazebo> element associated to a joint:

../_images/gazebo_joint.png

Any parameter included within the <gazebo> tag of the joint but not explicitely defined in the above table, is directly inserted into the SDF <model>, in a similar way as it was done for the robot and the link elements. This is done for instance to insert a <plugin> element associated to the joint.

ROS-aware Gazebo plugins

Gazebo plugins can be implemented such that they are ROS-aware. To illustrate this, the world and model plugins executed before have been reimplemented. They include the header file <ros/ros.h> and ROS functions to print to the terminal and to advertise the pose of the cube in the model plugin demo.

  • Execute the world ros plugin demo; the “Hello World” message will be printed upon loading the scene:

$ catkin build gazebo_ros_plugin_demo
$ roslaunch gazebo_ros_plugin_demo hello.launch
  • Execute the model ros plugin demo. Gazebo is run in paused mode (set in the launch file); upon pressing the play button the cube will be pushed along the x-direction and the pose of the cube will be advertised in the /cube_pose topic:

$ roslaunch gazebo_ros_plugin_demo model_push.launch
$ rostopic echo /cube_pose

Exercise

Take a look at the source code of the plugins and to the launch files.

You can find more details of the world ros plugin in the Gazebo tutorial ROS plugins.