You are currently viewing ROS Tutorial: Simulate the UR5 robot in Gazebo – URDF explained

ROS Tutorial: Simulate the UR5 robot in Gazebo – URDF explained

Today’s goal is to set up our ur5 robot in Gazebo. Gazebo is a popular simulation tool that allows you to not only visualize your robot like in Rviz but also has a physics engine built-in. That way you can test your robot applications in a more realistic environment. We will look at the properties we need to add to the description of our robot – our URDF – in order to simulate it and how to spawn our robot in Gazebo.

Note: If you just want to get the UR5 robot running in Gazebo without learning about the properties defined in the URDF and how to connect the URDF description to the Gazebo environment then you can skip to the Quickstart section. There you get all the commands necessary to quickly spawn the UR5 in Gazebo.

Gazebo

If you don’t have ROS installed yet, please do so by following the instruction on the ROS wiki. If you are missing Gazebo (which should already be installed if you chose the full ROS installation), just run this command in your Linux terminal:

$ curl -sSL http://get.gazebosim.org | sh

This already allows us to spawn the Gazebo environment e.g. by running:

$ roslaunch gazebo_ros empty_world.launch

An empty world, of course, is a boring thing so let’s get our robot in there. The previous tutorial in which we worked with Rviz already went through the description files of the UR5 robot to understand URDFs. If you are interested in learning the basics of URDFs check out this previous article if you have not done so yet.

Gazebo can use the URDF description file to simulate our robot. Under the hood it converts the URDF to another format called SDF which is better suited for simulations. However, in order for Gazebo to be able to work with our URDF we need to add some lines to it. Gazebo needs some additional attributes, which is basically all the properties that influence how exactly the robot moves, in order to to get the simulation right. You can find the modified URDF for use with Gazebo here. There you can follow along while we discuss the added properties in detail.

Adding intertia

Gazebo has to know the weight of the robot parts (i.e. the links) and their inertia which is a measure of how this weight is distributed. That information should be included in the URDF inside the <link> and after the <visual> and <collision> sections. This is an example for the base joint:

</collision>
    <inertial>
      <mass value="2.275"/>
      <origin rpy="0 0 0" xyz="0.0 0.0 0.25"/>
      <inertia ixx="0.049443313556" ixy="0.0" ixz="0.0" iyy="0.049443313556" iyz="0.0" izz="0.004095"/>
    </inertial>

For rigid bodies rotating in three dimensions the general inertia matrix which is defined inside the <inertia> tag looks like this:

\begin{equation*} \begin{pmatrix} I_{xx} & I_{xy} & I_{xz} \\ I_{yx} & I_{yy} & I_{yz} \\ I_{zx} & I_{zy} & I_{zz} \end{pmatrix} \end{equation*}

The matrix elements define moments of intertia. \(I_{xx}\) e.g. defines the moment of intertia around the x-axis, while \(I_{xy}\) defines the xy product of intertia. A more detailed discussion would exceed the scope of this article, but a google search will bring you more information about this if you are interested. The only thing we have to know in addition is that the elements above the diagonal of the matrix equal the ones below it, which means \(I_{xy} = I_{yx}\), \(I_{xz} = I_{zx}\) and \(I_{yz} = I_{zy}\). This is why we only have to define six elements of the 3×3 rotational intertia matrix.

The <origin> tag defines the center of mass or center of gravity of our link, respectively. This is the average position of all of the parts of our system which are weighted in accordance to their masses. It is a useful attribute when calculating accelerations.

Collision properties

For a proper simulation, Gazebo has to know when the robot bumps into things, especially itself. Therefore we need to tell it the geometry of our links. For simplicity, we are using the .stl file that comes right from the CAD model of our robot and describes only the link geometry without any definition of colors or material. Often, these detailed geometric models are simplified by defining approximate geometries or reducing the resolution of the model in order to make computation of collisions faster.

    <collision>
      <geometry>
        <mesh filename="package://ur_description/meshes/ur5/collision/shoulder.stl"/>
      </geometry>
    </collision>

Limits and dynamics

Moreover, we will define some limits for the joint properties. This must be added inside the <joint> tag.

    <limit effort="28.0" lower="-3.14159265" upper="3.14159265" velocity="3.2"/>
    <dynamics damping="0.0" friction="0.0"/>

The effort determines the maximum force (or torque) that can be applied to the robot which mostly depends on how powerful the motors are. With the lower and upper limits we define the range in which the joints can move in radiants. By restricting the maximum velocity, we limit the speed at which the single joints can move. Inside the <dynamics> tag, damping and friction are additional parameters that further define the dynamics of our joints. We set them to zero for now as we do not have accurate data for it, but in order to get your simulation to be more realistic you would want to have these in your URDF.

Note that the definition of limits and dynamics is optional and not a prerequisite for using the URDF with Gazebo.

Tying the robot to the ground (A fixed world joint)

As a last step, in order to connect the robot with our gazebo environment, we add an additional joint to our URDF. This joint – we call it world joint – is fixed and its sole purpose is to anchor our robot in the simulated world. That is why we define world as the parent link and base_link as the child link

  <link name="world"/>
  <joint name="world_joint" type="fixed">
    <parent link="world"/>
    <child link="base_link"/>
    <!-- TODO: check base_link name of robot -->
    <origin rpy="0.0 0.0 0.0" xyz="0.0 0.0 0.0"/>
  </joint>

As we now added everything Gazebo asks for, we can spawn the robot. First, copy the content of the URDF file for Gazebo into a text file and store it anywhere on your file system under the name ur5_gazebo.urdf. Second, if you don’t have the ur_description package installed already from the previous tutorial, please run the following commands and as always replace <distro> with your ROS version:

~/catkin_ws/src$ git clone -b <distro>-devel https://github.com/ros-industrial/universal_robot.git $
$ rosdep update
$ rosdep install --rosdistro $ROS_DISTRO --ignore-src --from-paths src

Then build your workspace:

~/catkin_ws/src$ cd ..
~/catkin_ws$ catkin_make
$ source $HOME/catkin_ws/devel/setup.bash

Now let’s start up an empty world in gazebo as before:

$ roslaunch gazebo_ros empty_world.launch

In a new terminal we can spawn the robot with the spawn_model command:

$ rosrun gazebo_ros spawn_model -file /<path-to-your-gazebo-urdf-file>/ur5_gazebo.urdf -urdf -x 0 -y 0 -z 0.1 -model ur5

We hand over the path to our URDF file as an argument and the coordinate the robot should be spawned at. We define a small offset of 0.1 for the z-axis because at the very center of our empty world, a ground plate is located that also appears on the left hand side under Models. This plate is invisible but it causes collisions when we try to place our robot exactly at the same location.

In the above picture, the shadows are disabled for better visibility. You can do this by clicking on Scene in the World tab and removing the tick from the shadows option. When you look at the robot in Gazebo now it might look a bit pitful, just lying limp on the ground. This is because we don’t control anything on our robot right now so everything that is happening in the simulation is a robot with a bunch of weights defined and no force or friction in its joints just falling to the ground due to gravity. That is why we need robot controllers to move the robot and do some cool stuff with it. In the next article we will add the ros_control package and set up some nice position controllers in order to move our joints. You can find an overview of all tutorials here.

Qickstart

As always, for busy people, these are the commands you need:

Install Gazebo if needed:

$ curl -sSL http://get.gazebosim.org | sh

If not already done from the previous tutorials please install the universal_robot package:

~/catkin_ws/src$ git clone -b <distro>-devel https://github.com/ros-industrial/universal_robot.git $
$ rosdep update
$ rosdep install --rosdistro $ROS_DISTRO --ignore-src --from-paths src

Then build your workspace:

~/catkin_ws/src$ cd ..
~/catkin_ws$ catkin_make
$ source $HOME/catkin_ws/devel/setup.bash

Now copy the content of the URDF for Gazebo to your local file system into a file named ur5_gazebo.urdf. Then run the following two commands to spawn the robot in Gazebo:

$ roslaunch gazebo_ros empty_world.launch
$ rosrun gazebo_ros spawn_model -file <path-to-your-gazebo-urdf/ur5_.urdf -urdf -x 0 -y 0 -z 0.1 -model ur5

Alternatively, you could simply start the simulation with a launch file from the ur5_gazebo package which also launches a controller:

$ roslaunch ur_gazebo ur5.launch

If you want to move the robot by controlling it’s joints with the ros_control package, check out this tutorial. You can find an overview of all tutorials here.