Wiki

Note: This tutorial assumes that you have completed the previous tutorials: Building a Visual Robot Model with URDF from Scratch, Building a Movable Robot Model with URDF.
(!) Please ask about problems and questions regarding this tutorial on answers.ros.org. Don't forget to include in your question the link to this page, the versions of your OS & ROS, and also add appropriate tags.

Adding Physical and Collision Properties to a URDF Model

Description: Learn how to add collision and inertial properties to links, and how to add joint dynamics to joints.

Keywords: URDF, Inertial, Dynamics, Collision

Tutorial Level: BEGINNER

Next Tutorial: Using Xacro to Clean Up a URDF File Using a URDF in Gazebo

In this tutorial, we’ll look at how to add some basic physical properties to your URDF model and how to specify its collision properties.

Collision

So far, we’ve only specified our links with a single sub-element, visual, which defines (not surprisingly) what the robot looks like. However, in order to get collision detection to work or to simulate the robot in something like Gazebo, we need to define a collision element as well. Here is the new urdf with collision and physical properties.

Here is the code for our new base link.

   1 <link name="base_link">
   2     <visual>
   3       <geometry>
   4         <cylinder length="0.6" radius="0.2"/>
   5       </geometry>
   6       <material name="blue">
   7         <color rgba="0 0 .8 1"/>
   8       </material>
   9     </visual>
  10     <collision>
  11       <geometry>
  12         <cylinder length="0.6" radius="0.2"/>
  13       </geometry>
  14     </collision>
  15   </link>

In many cases, you’ll want the collision geometry and origin to be exactly the same as the visual geometry and origin. However, there are two main cases where you wouldn’t.

Physical Properties

In order to get your model to simulate properly, you need to define several physical properties of your robot, i.e. the properties that a physics engine like Gazebo would need.

Inertia

Every link element being simulated needs an inertial tag. Here is a simple one.

   1   <link name="base_link">
   2     <visual>
   3       <geometry>
   4         <cylinder length="0.6" radius="0.2"/>
   5       </geometry>
   6       <material name="blue">
   7         <color rgba="0 0 .8 1"/>
   8       </material>
   9     </visual>
  10     <collision>
  11       <geometry>
  12         <cylinder length="0.6" radius="0.2"/>
  13       </geometry>
  14     </collision>
  15     <inertial>
  16       <mass value="10"/>
  17       <inertia ixx="0.4" ixy="0.0" ixz="0.0" iyy="0.4" iyz="0.0" izz="0.2"/>
  18     </inertial>
  19   </link>

ixx

ixy

ixz

ixy

iyy

iyz

ixz

iyz

izz

Contact Coefficients

You can also define how the links behave when they are in contact with one another. This is done with a subelement of the collision tag called contact_coefficients. There are three attributes to specify:

Joint Dynamics

How the joint moves is defined by the dynamics tag for the joint. There are two attributes here:

If not specified, these coefficients default to zero.

Other Tags

In the realm of pure URDF (i.e. excluding Gazebo-specific tags), there are two remaining tags to help define the joints: calibration and safety controller. Check out the spec, as they are not included in this tutorial.

Next Steps

Reduce the amount of code and annoying math you have to do by using xacro.

Wiki: urdf/Tutorials/Adding Physical and Collision Properties to a URDF Model (last edited 2021-10-07 18:40:17 by DavidLu)