Describing robots with URDF

To represent the properties of the robot in the ROS system the model of the robot is described using a domain-specific modelling language called Unified Robotic Description Format (URDF) and stored in a URDF file. URDF is based on XML and its syntax enables encoding the robot's layout and its constituting elements like links, joints, and shapes, and its physical appearence.

The URDF format can be used to describe any kind of shapes and enables modelling the world and the objects that surround the robot. On the other hand, the links and other parts of the robot are nothing more than either more simple or more complex shape.

To show how a shape can be described with the URDF format and visualised in Rviz a simple example will be used.

Modelling a simple shape

This is a simple URDF file with the most basic structure. The main URDF tags are specified at wiki.ros.org/urdf/XML.

<?xml version="1.0"?>
<robot name="myfirst">
  <link name="base_link">
    <visual>
      <origin rpy="0 0 0" xyz="0 0 0.75" />
      <geometry>
        <box size="0.5 0.5 1.5"/>
      </geometry>
    </visual>
  </link>
</robot>

Create a new package in your workspace named urdf_exercise and a folder named urdf in the package directory. Copy the above code into a new file named simple_shape.urdf in the urdf folder. Build the workspace (catkin_make) and source the setup.bash file (source devel/setup.bash).

The first line of the code <?xml version="1.0"?> is the XML declaration. The robot element is the necessary root element of the urdf and contains all other elements. The link element is the only element of the "robot" and its visual properties are represented by a simple geometrical shape, box.

The description of the robot has to be loaded to the parameter server in order to be accessible to the ROS nodes during runtime.

Loading the description step by step

To load the description to the parameter server firs run roscore in the first terminal. In the second terminal, navigate to the urdf folder and run:

rosparam load simple_shape.urdf robot_description -v

The -v option in the command stands for verbose execution.

The description of the shape is now loaded to the parameter server and can be visualised in Rviz. Open Rviz from the third terminal (rosrun rviz rviz). In Rviz, add the RobotModel display to the display pannel and change the Fixed Frame in Global Options to base_link. Save the Rviz configuration to the file simple_config.rviz in the launch folder for future reuse (see next subsection).

The description of the shape can also be inspected directly from the parameter server: rosparam get /robot_description.

Loading the description with launch file

Using a launch file makes running the ROS system with Rviz and loading the description faster. Create a launch file simple_shape.launch in the launch folder in the source space of the package. Paste the following code into the file:

<launch>

  <arg name="model" default="$(find urdf_exercise)/urdf/simple_shape.urdf" />
  <arg name="rvizconfig" default ="$(find urdf_exercise)/launch/simple_config.rviz"/>

  <param name="robot_description" command="$(find xacro)/xacro.py $(arg model)" />

  <node name="rviz" pkg="rviz" type="rviz" args="-d $(arg rvizconfig)" />

</launch>

Adding another shape to the model

To add another shape we use the link tag, as in the above example. To connect the two shapes the joint tag is used. The joint between two links can be rigid or moving. This property is defined by the type attribute. First we will use the fixed joint. Add the code for the second link and the joint to your URDF:

<link name="link_one">
  <visual>
    <origin rpy="0 0 0" xyz="0 0 0.75" />
    <geometry>
      <box size="0.5 0.5 1.5"/>
    </geometry>
    <material name="white"/>
  </visual>
</link>
<joint name="base_to_one" type="fixed">
  <parent link="base_link"/>
  <child link="link_one"/>
  <origin xyz="0.0 0.0 1.5" />
</joint>

To visualize all the shapes correctly, Rviz requires information about transformations between reference frames of the shapes. To provide this data, two additional nodes need to be started:

  • the joint_state_publisher publishes to the joint_states topic the data on the current states of the joints
  • the robot_state_publisher publishes the transforms to the tf topic.

To start the additional nodes, add the following code to the launch file and run it:

<node name="joint_state_publisher" pkg="joint_state_publisher" type="joint_state_publisher" />
<node name="robot_state_publisher" pkg="robot_state_publisher" type="robot_state_publisher" />

Using a movable joint

Among the six types of joints, five of them allow movement around in space with various degrees of freedom. In this section we will use the revolute joint which emulates a hinge, rotates along one axis and has a limited range specified by the upper and lower limits.

In the urdf file, modify the code block for joint definition to the following code:

<joint name="base_to_one" type="revolute">
  <parent link="base_link"/>
  <child link="link_one"/>
  <axis xyz="0.0 1.0 0.0"/>
  <origin xyz="0.0 0.0 1.5" />
  <limit lower="-1.0" upper="1.0" effort="1000.0" velocity="0.5"/>
</joint>

The joint is now movable and it can rotate around the y axis. The movement limits are set to 90 degrees to each direction from the midle position.

To interact with the joint while the ROS system is running, we will use a graphical user interface for setting the joint states instead of the joint_states_publisher. Substitute the line in the launch file with:

<node name="joint_state_publisher_gui" pkg="joint_state_publisher_gui" type="joint_state_publisher_gui" />

The joint_state_publisher_gui node provides a graphical user interface to display joint positions in a window as sliders and enables changing the joint positions during runtime. This is done by parsing the values of the sliders and publishing sensor_msgs/JointState messages, that are used by the robot_state_publisher to calculate all transforms between different links. The resulting transform tree is then used to display all of the shapes in Rviz.

Run the launch file and move the joint using the GUI.

Adding a gripper to the Fanuc model

To get acquainted with more complicated robot models we will work with the Fanuc LR Mate 200id model. We will start with the existing urdf of the robot and add a gripper for manipulation. Create a new file fanuc.urdf in the urdf folder and copy-paste the code for the fanuc arm:

<?xml version="1.0" encoding="utf-8"?>
<robot name="fanuc_lrmate200id">
  <!-- links: main serial chain -->
  <link name="base_link">
    <visual>
      <origin rpy="0 0 0" xyz="0 0 0"/>
      <geometry>
        <mesh filename="package://fanuc_lrmate200id_support/meshes/lrmate200id/visual/base_link.stl"/>
      </geometry>
      <material name="">
        <color rgba="0.278431372549 0.278431372549 0.278431372549 1.0"/>
      </material>
    </visual>
    <collision>
      <origin rpy="0 0 0" xyz="0 0 0"/>
      <geometry>
        <mesh filename="package://fanuc_lrmate200id_support/meshes/lrmate200id/collision/base_link.stl"/>
      </geometry>
    </collision>
    <inertial>
      <mass value="4"/>
      <origin rpy="0 0 0" xyz="0 0 0"/>
      <inertia ixx="0.0216667" ixy="0" ixz="0" iyy="0.0216667" iyz="0" izz="0.0240667"/>
    </inertial>
  </link>
  <link name="link_1">
    <visual>
      <origin rpy="0 0 0" xyz="0 0 0"/>
      <geometry>
        <mesh filename="package://fanuc_lrmate200id_support/meshes/lrmate200id/visual/link_1.stl"/>
      </geometry>
      <material name="">
        <color rgba="0.96 0.76 0.13 1.0"/>
      </material>
    </visual>
    <collision>
      <origin rpy="0 0 0" xyz="0 0 0"/>
      <geometry>
        <mesh filename="package://fanuc_lrmate200id_support/meshes/lrmate200id/collision/link_1.stl"/>
      </geometry>
    </collision>
    <inertial>
      <mass value="4"/>
      <origin rpy="0 0 0" xyz="0 0 0"/>
      <inertia ixx="0.0322667" ixy="0" ixz="0" iyy="0.0226667" iyz="0" izz="0.0226667"/>
    </inertial>
  </link>
  <link name="link_2">
    <visual>
      <origin rpy="0 0 0" xyz="0 0 0"/>
      <geometry>
        <mesh filename="package://fanuc_lrmate200id_support/meshes/lrmate200id/visual/link_2.stl"/>
      </geometry>
      <material name="">
        <color rgba="0.96 0.76 0.13 1.0"/>
      </material>
    </visual>
    <collision>
      <origin rpy="0 0 0" xyz="0 0 0"/>
      <geometry>
        <mesh filename="package://fanuc_lrmate200id_support/meshes/lrmate200id/collision/link_2.stl"/>
      </geometry>
    </collision>
    <inertial>
      <mass value="5"/>
      <origin rpy="0 0 0" xyz="0 0 0"/>
      <inertia ixx="0.0973333" ixy="0" ixz="0" iyy="0.0888333" iyz="0" izz="0.0248333"/>
    </inertial>
  </link>
  <link name="link_3">
    <visual>
      <origin rpy="0 0 0" xyz="0 0 0"/>
      <geometry>
        <mesh filename="package://fanuc_lrmate200id_support/meshes/lrmate200id/visual/link_3.stl"/>
      </geometry>
      <material name="">
        <color rgba="0.96 0.76 0.13 1.0"/>
      </material>
    </visual>
    <collision>
      <origin rpy="0 0 0" xyz="0 0 0"/>
      <geometry>
        <mesh filename="package://fanuc_lrmate200id_support/meshes/lrmate200id/collision/link_3.stl"/>
      </geometry>
    </collision>
    <inertial>
      <mass value="4"/>
      <origin rpy="0 0 0" xyz="0 0 0"/>
      <inertia ixx="0.0104333" ixy="0" ixz="0" iyy="0.0121667" iyz="0" izz="0.0113333"/>
    </inertial>
  </link>
  <link name="link_4">
    <visual>
      <origin rpy="0 0 0" xyz="0 0 0"/>
      <geometry>
        <mesh filename="package://fanuc_lrmate200id_support/meshes/lrmate200id/visual/link_4.stl"/>
      </geometry>
      <material name="">
        <color rgba="0.96 0.76 0.13 1.0"/>
      </material>
    </visual>
    <collision>
      <origin rpy="0 0 0" xyz="0 0 0"/>
      <geometry>
        <mesh filename="package://fanuc_lrmate200id_support/meshes/lrmate200id/collision/link_4.stl"/>
      </geometry>
    </collision>
    <inertial>
      <mass value="5"/>
      <origin rpy="0 0 0" xyz="0 0 0"/>
      <inertia ixx="0.00833333" ixy="0" ixz="0" iyy="0.0368333" iyz="0" izz="0.0368333"/>
    </inertial>
  </link>
  <link name="link_5">
    <visual>
      <origin rpy="0 0 0" xyz="0 0 0"/>
      <geometry>
        <mesh filename="package://fanuc_lrmate200id_support/meshes/lrmate200id/visual/link_5.stl"/>
      </geometry>
      <material name="">
        <color rgba="0.96 0.76 0.13 1.0"/>
      </material>
    </visual>
    <collision>
      <origin rpy="0 0 0" xyz="0 0 0"/>
      <geometry>
        <mesh filename="package://fanuc_lrmate200id_support/meshes/lrmate200id/collision/link_5.stl"/>
      </geometry>
    </collision>
    <inertial>
      <mass value="1.5"/>
      <origin rpy="0 0 0" xyz="0 0 0"/>
      <inertia ixx="0.0018125" ixy="0" ixz="0" iyy="0.0023125" iyz="0" izz="0.002525"/>
    </inertial>
  </link>
  <link name="link_6">
    <visual>
      <origin rpy="0 0 0" xyz="-0.057 0 0"/>
      <geometry>
        <mesh filename="package://fanuc_lrmate200id_support/meshes/lrmate200id/visual/link_6.stl"/>
      </geometry>
      <material name="">
        <color rgba="0.15 0.15 0.15 1.0"/>
      </material>
    </visual>
    <collision>
      <origin rpy="0 0 0" xyz="0 0 0"/>
      <geometry>
        <mesh filename="package://fanuc_lrmate200id_support/meshes/lrmate200id/collision/link_6.stl"/>
      </geometry>
    </collision>
    <inertial>
      <mass value="0.25"/>
      <origin rpy="0 0 0" xyz="0 0 0"/>
      <inertia ixx="6.66666e-05" ixy="0" ixz="0" iyy="3.54167e-05" iyz="0" izz="3.54167e-05"/>
    </inertial>
  </link>
  <!-- joints: main serial chain -->
  <joint name="joint_1" type="revolute">
    <origin rpy="0 0 0" xyz="-0.006 -0.002 0.290"/>
    <parent link="base_link"/>
    <child link="link_1"/>
    <axis xyz="0 0 1"/>
    <dynamics damping="1.0"/>
    <limit effort="100" lower="-2.965" upper="2.965" velocity="7.85"/>
  </joint>
  <joint name="joint_2" type="revolute">
    <origin rpy="0 0 0" xyz="0 0 0.040"/>
    <parent link="link_1"/>
    <child link="link_2"/>
    <axis xyz="0 1 0"/>
    <dynamics damping="1.0"/>
    <limit effort="100" lower="-1.745329" upper="2.530727" velocity="6.63"/>
  </joint>
  <joint name="joint_3" type="revolute">
    <origin rpy="0 0 0" xyz="0.0 0 0.26"/>
    <parent link="link_2"/>
    <child link="link_3"/>
    <axis xyz="0 -1 0"/>
    <dynamics damping="1.0"/>
    <limit effort="100" lower="-2.450966" upper="4.886922" velocity="9.08"/>
  </joint>
  <joint name="joint_4" type="revolute">
    <origin rpy="0 0 0" xyz="0.064 0 0.02"/>
    <parent link="link_3"/>
    <child link="link_4"/>
    <axis xyz="-1 0 0"/>
    <dynamics damping="1.0"/>
    <limit effort="100" lower="-3.315" upper="3.315" velocity="9.60"/>
  </joint>
  <joint name="joint_5" type="revolute">
    <origin rpy="0 0 0" xyz="0.226 0 0"/>
    <parent link="link_4"/>
    <child link="link_5"/>
    <axis xyz="0 -1 0"/>
    <dynamics damping="1.0"/>
    <limit effort="100" lower="-2.18" upper="2.18" velocity="9.51"/>
  </joint>
  <joint name="joint_6" type="revolute">
    <origin rpy="0 0 0" xyz="0.070 0 0"/>
    <parent link="link_5"/>
    <child link="link_6"/>
    <axis xyz="-1 0 0"/>
    <dynamics damping="1.0"/>
    <limit effort="100" lower="-6.285" upper="6.285" velocity="17.45"/>
  </joint>
  <!-- WORLD LINK -->
  <link name="world"/>
  <joint name="world" type="fixed">
    <origin rpy="0 0 0" xyz="0 0 0"/>
    <parent link="world"/>
    <child link="base_link"/>
  </joint>
</robot>

Inspect the code above. The robot is composed of six links and attached to the world link by the world joint. Each link has visual, collision and inertial properties defined. While the visual properties are used for visualisation of the robot, the collision and inertial properties are required for motion planning and control execution. The visual and collision properties depend on geometry, which in this case is not a simple shape but a more complex shape that is defined in an .stl file. The .stl files for the links are located in another package, the fanuc_lrmate200id_support package, and are referenced in the filename argument of the mesh tag.

To visualise the Fanuc robot model in Rviz, create a launch file fanuc.launch. Hint: Use the code from simple_shape.launch and modify the neccessary part of the code.

The following is the code for the gripper:

<robot name="gripper">
    <link name="flange">
    <visual>
      <origin rpy="0 0 0" xyz="0 0 0"/>
      <geometry>
        <mesh filename="package://fanuc_lrmate200id_support/meshes/lrmate200id/visual/gripper.stl" scale="0.001 0.001 0.001"/>
      </geometry>
      <material name="">
        <color rgba="0.75 0.75 0.75 1.0"/>
      </material>
    </visual>
    <collision>
      <origin rpy="0 0 0" xyz="0 0 0"/>
      <geometry>
        <mesh filename="package://fanuc_lrmate200id_support/meshes/lrmate200id/collision/gripper.stl" scale="0.001 0.001 0.001"/>
      </geometry>
    </collision>
    <inertial>
      <mass value="0.1"/>
      <origin rpy="0 0 0" xyz="0 0 0"/>
      <inertia ixx="6e-06" ixy="0" ixz="0" iyy="6e-06" iyz="0" izz="6e-06"/>
    </inertial>
  </link>
  <link name="left_finger">
    <visual>
      <origin rpy="0 0 0" xyz="0 0 0"/>
      <geometry>
        <mesh filename="package://fanuc_lrmate200id_support/meshes/lrmate200id/visual/left_finger.stl" scale="0.001 0.001 0.001"/>
      </geometry>
      <material name="">
        <color rgba="0.75 0.75 0.75 1.0"/>
      </material>
    </visual>
    <collision>
      <origin rpy="0 0 0" xyz="0 0 0"/>
      <geometry>
        <mesh filename="package://fanuc_lrmate200id_support/meshes/lrmate200id/collision/left_finger.stl" scale="0.001 0.001 0.001"/>
      </geometry>
    </collision>
    <inertial>
      <mass value="0.01"/>
      <origin rpy="0 0 0" xyz="0 0 0"/>
      <inertia ixx="6e-06" ixy="0" ixz="0" iyy="6e-06" iyz="0" izz="6e-06"/>
    </inertial>
  </link>
  <link name="right_finger">
    <visual>
      <origin rpy="0 0 0" xyz="0 0 0"/>
      <geometry>
        <mesh filename="package://fanuc_lrmate200id_support/meshes/lrmate200id/visual/right_finger.stl" scale="0.001 0.001 0.001"/>
      </geometry>
      <material name="">
        <color rgba="0.75 0.75 0.75 1.0"/>
      </material>
    </visual>
    <collision>
      <origin rpy="0 0 0" xyz="0 0 0"/>
      <geometry>
        <mesh filename="package://fanuc_lrmate200id_support/meshes/lrmate200id/collision/right_finger.stl" scale="0.001 0.001 0.001"/>
      </geometry>
    </collision>
    <inertial>
      <mass value="0.01"/>
      <origin rpy="0 0 0" xyz="0 0 0"/>
      <inertia ixx="6e-06" ixy="0" ixz="0" iyy="6e-06" iyz="0" izz="6e-06"/>
    </inertial>
  </link>
  <joint name="finger_joint1" type="prismatic">
    <parent link="flange"/>
    <child link="left_finger"/>
    <origin rpy="0 0 0" xyz="0.088 0 0"/>
    <axis xyz="0 -1 0"/>
    <dynamics damping="1.0"/>
    <limit effort="10" lower="0.0" upper="0.015" velocity="0.2"/>
  </joint>
  <joint name="finger_joint2" type="prismatic">
    <parent link="flange"/>
    <child link="right_finger"/>
    <origin rpy="0 0 0" xyz="0.088 0 0"/>
    <axis xyz="0 1 0"/>
    <dynamics damping="1.0"/>
    <limit effort="10" lower="0.0" upper="0.015" velocity="0.2"/>
    <mimic joint="finger_joint1"/>
  </joint>
</robot>

Use the above code to update your fanuc.urdf. Connect the gripper to the Fanuc robot arm with a fixed joint named joint_6-flange.

Run the ROS system to visualise the updated robot model and move the joints around using the GUI.

Generating urdf from xacro

Xacro (XML Macros) Xacro is an XML macro language. With xacro, you can construct shorter and more readable XML files by using macros that expand to larger XML expressions.

Xacro is another way of defining a URDF. It allows more modularity and code re-use when defining a URDF model. It enables using variables in URDF, (called properties), math expressions, conditional blocks, and references to other packages using rospack commands (e.g. find).

A XACRO file is not used directly but is always converted to URDF first, either separately or while loading it from a launch file.

The conversion is done by running xacro the xacro package. Here is an example use for our Fanuc robot. (The xacro file is located in the urdf folder in the fanuc_lrmate200id_support package.)

cd ~/rosinljubljana/fanuc_ros/
source devel/setup.bash
rosrun xacro xacro ./src/fanuc_lrmate200id_support/urdf/fanuc_lrmate200id_include.xacro

The XACRO file is read, converted to URDF and printed to the terminal. To redirect this output to a file, a (shell) redirection oprator > can be used. To save the above URDF to the urdf_exercise package to a file called fanuc_lrmate200id.urdf run:

rosrun xacro xacro ./src/fanuc_lrmate200id_support/urdf/fanuc_lrmate200id_include.xacro > ./src/urdf_exercise/urdf/fanuc_lrmate200id.urdf

Atteching one robot model to another

In the urdf folder, create three files: base_link.urdf, attachment.xacro, and two_links.xacro.

Contents for base_link.urdf:

<?xml version="1.0"?>
<robot name="myfirst">
  <link name="base_link">
    <visual>
      <origin rpy="0 0 0" xyz="0 0 0.75" />
      <geometry>
        <box size="0.5 0.5 1.5"/>
      </geometry>
    </visual>
  </link>
</robot>

Contents for attachment.xacro:

<?xml version="1.0"?>
<robot  xmlns:xacro="http://ros.org/wiki/xacro" name="link_one">
  <xacro:macro name="attachment" params="connected_to">
  <link name="link_one">
    <visual>
      <origin rpy="0 0 0" xyz="0 0 0.75" />
      <geometry>
        <box size="0.5 0.5 1.5"/>
      </geometry>
      <material name="white"/>
    </visual>
  </link>
  <joint name="connection_joint" type="revolute">
    <parent link="${connected_to}"/>
    <child link="link_one"/>
    <origin xyz="0.0 0.0 1.5" />
    <limit lower="-1.0" upper="1.0" effort="1000.0" velocity="0.5"/>
  </joint>
  </xacro:macro>
</robot>

Contents for two_links.xacro:

<?xml version="1.0"?>
<robot xmlns:xacro="http://ros.org/wiki/xacro" name="two_links_robot">
  <!-- base_link -->
  <xacro:include filename="$(find urdf_exercise)/urdf/base_link.urdf" />
  <!-- attachment -->
  <xacro:include filename="$(find urdf_exercise)/urdf/attachment.xacro" />
  <xacro:attachment connected_to="base_link"/>
</robot>

In the terminal run:

rosrun xacro xacro ./src/urdf_exercise/urdf/two_links.xacro > ./src/urdf_exercise/urdf/two_links.urdf