/!\ XML verbatim blocks are broken, all special charaters are not displayed.

Note: This tutorial assumes that you have completed the previous tutorials: URDF Part 1.

Understanding the PR2 URDF description, Part 2

Description: Describes one of the low-level components of the PR2 definition in full detail.

Tutorial Level: ADVANCED

Next Tutorial: Understanding Gazebo extensions

PR2 Base URDF Explained

A snapshot of the URDF xacro macro (see pr2_description/urdf/base_v0/base.urdf.xacro in the pr2_description package) for the PR2 base is displayed here for dissection:

   1 <?xml version="1.0"?>
   2 <robot xmlns:sensor="http://playerstage.sourceforge.net/gazebo/xmlschema/#sensor"
   3        xmlns:controller="http://playerstage.sourceforge.net/gazebo/xmlschema/#controller"
   4        xmlns:interface="http://playerstage.sourceforge.net/gazebo/xmlschema/#interface"
   5        xmlns:xacro="http://ros.org/wiki/xacro">
   6 
   7   <include filename="$(find pr2_description)/urdf/base_v0/base.gazebo.xacro" />
   8   <include filename="$(find pr2_description)/urdf/base_v0/base.transmission.xacro" />
   9 
  10   <!-- DATA SOURCES -->
  11   <!-- all link offsets, CG, limits are obtained from Function Engineering spreadsheet 090224_link_data.xls unless stated otherwise -->
  12   <!-- all link geometry sizes are obtained from Function provided CAD model unless stated otherwise -->
  13   <!-- all simplified collision geometry are hand approximated from CAD model, sometimes from respective bounding boxes -->
  14 
  15   <property name="M_PI" value="3.1415926535897931" />
  16 
  17   <property name="caster_offset_x" value="0.2225" />
  18   <property name="caster_offset_y" value="0.2225" />
  19   <property name="caster_offset_z" value="0.0282" />
  20 
  21   <property name="caster_wheel_offset_y" value="0.049" />
  22   <property name="wheel_length" value="0.034" />
  23   <property name="wheel_radius" value="0.074792" />   <!-- This is the 'effective' wheel radius. Wheel radius for uncompressed wheel is 0.079.  mp 20080801 -->
  24 
  25   <property name="base_cg_x" value="-0.061" />
  26   <property name="base_cg_y" value="0.0" />
  27   <property name="base_cg_z" value="0.293" />
  28   <property name="base_mass" value="116.0" />
  29 
  30   <!-- simplified box collision geometry for base -->
  31   <property name="base_size_x" value="0.65" />
  32   <property name="base_size_y" value="0.65" />
  33   <property name="base_size_z" value="0.23" />
  34   <property name="base_collision_size_z" value="0.04" />
  35 
  36   <!-- simplified box collision geometry for hokuyo laser -->
  37   <property name="base_laser_x" value="0.275" />
  38   <property name="base_laser_y" value="0.0" />
  39   <property name="base_laser_z" value="0.252" />
  40   <property name="base_laser_size_x" value="0.06" />
  41   <property name="base_laser_size_y" value="0.06" />
  42   <property name="base_laser_size_z" value="0.03" />
  43   <property name="base_laser_collision_offset_z" value="0.023" />
  44 
  45   <!--                                                      -->
  46   <!--           wheel                                      -->
  47   <!--                                                      -->
  48   <xacro:macro name="pr2_wheel_v0" params="suffix parent reflect">
  49 
  50     <joint name="${parent}_${suffix}_wheel_joint" type="continuous">
  51       <axis xyz="0 1 0" />
  52       <limit effort="100" velocity="100"/>
  53       <safety_controller  k_velocity="10" />
  54       <dynamics damping="0.0" friction="0.0" />
  55       <origin xyz="0 ${reflect*caster_wheel_offset_y} 0" rpy="0 0 0" />
  56       <parent link="${parent}_rotation_link"/>
  57       <child link="${parent}_${suffix}_wheel_link"/>
  58     </joint>
  59     <link name="${parent}_${suffix}_wheel_link">
  60       <inertial>
  61         <mass value="0.44036" />
  62         <origin xyz="0 0 0" />
  63         <inertia  ixx="0.012411765597" ixy="-0.000711733678" ixz="0.00050272983"
  64                   iyy="0.015218160428" iyz="-0.000004273467" izz="0.011763977943" />
  65       </inertial>
  66       <visual>
  67         <origin xyz="0 0 0" rpy="0 0 0" />
  68         <geometry>
  69           <mesh filename="package://pr2_description/meshes/base_v0/pr2_wheel.stl" />
  70         </geometry>
  71         
  72         <material name="Wheel_${suffix}" />
  73       </visual>
  74       <collision>
  75         <origin xyz="0 0 0" rpy="${M_PI/2} 0 0" /> <!-- rotation because cyl. geom primitive has symmetry axis in +x direction -->
  76         <geometry>
  77           <cylinder radius="${wheel_radius}" length="${wheel_length}" />
  78         </geometry>
  79       </collision>
  80     </link>
  81 
  82     <!-- extensions -->
  83     <xacro:pr2_wheel_gazebo_v0 parent="${parent}" suffix="${suffix}" />
  84     <xacro:pr2_wheel_transmission_v0 parent="${parent}" suffix="${suffix}" reflect="${reflect}" />
  85 
  86   </xacro:macro>
  87 
  88   <!-- Macro for PR2 Caster hub only -->
  89   <xacro:macro name="pr2_caster_hub_v0" params="suffix parent *origin ref_position" >
  90     <joint name="${suffix}_rotation_joint" type="continuous">
  91       <axis xyz="0 0 1" />
  92       <limit effort="100" velocity="100"/>
  93       <safety_controller  k_velocity="10" />
  94       <calibration reference_position="${ref_position}" />
  95       <dynamics damping="0.0" friction="0.0" />
  96       <insert_block name="origin" />
  97       <parent link="${parent}"/>
  98       <child link="${suffix}_rotation_link" />
  99     </joint>
 100     <link name="${suffix}_rotation_link">
 101 
 102       <inertial>
 103         <mass value="3.473082"/>
 104         <origin xyz="0 0 0.07" />
 105         <inertia  ixx="0.012411765597" ixy="-0.000711733678" ixz="0.00050272983"
 106                   iyy="0.015218160428" iyz="-0.000004273467" izz="0.011763977943" />
 107       </inertial>
 108 
 109       <visual>
 110         <origin xyz="0 0 0" rpy="0 0 0" />
 111         <geometry>
 112           <mesh filename="package://pr2_description/meshes/base_v0/caster.stl" />
 113         </geometry>
 114         
 115         <material name="Green" />
 116       </visual>
 117 
 118       <collision>
 119         <origin xyz="0 0 0.07" rpy="0.0 0.0 0.0" />
 120         <geometry>
 121           <box size="0.192 0.164 0.013" />
 122         </geometry>
 123       </collision>
 124     </link>
 125 
 126     <!-- extensions -->
 127     <xacro:pr2_caster_transmission_v0 suffix="${suffix}" />
 128   </xacro:macro>
 129 
 130   <xacro:macro name="pr2_caster_v0" params="suffix parent *origin ref_position">
 131 
 132     <xacro:pr2_caster_hub_v0 parent="${parent}" suffix="${suffix}_caster"
 133                              ref_position="${ref_position}" >
 134       <insert_block name="origin" />
 135     </xacro:pr2_caster_hub_v0>
 136 
 137     <!-- wheel macros -->
 138     <xacro:pr2_wheel_v0 parent="${suffix}_caster" suffix="l" reflect="1" />
 139     <xacro:pr2_wheel_v0 parent="${suffix}_caster" suffix="r" reflect="-1" />
 140 
 141     <!-- extensions -->
 142     <xacro:pr2_caster_gazebo_v0 suffix="${suffix}" />
 143   </xacro:macro>
 144 
 145 
 146   <!-- The xacro macro xacro:pr2_base contains: base, casters and wheels -->
 147   <xacro:macro name="pr2_base_v0" params="name *origin">
 148     <joint name="${name}_joint" type="planar">
 149       <insert_block name="origin" />
 150       <parent link="world"/>
 151       <child link="${name}_link" />
 152     </joint>
 153     <link name="${name}_link">
 154 
 155       <inertial>
 156         <mass value="${base_mass}" />
 157         <origin xyz="${base_cg_x} ${base_cg_y} ${base_cg_z}" />
 158         <inertia ixx="5.652232699207" ixy="-0.009719934438" ixz="1.293988226423"
 159                  iyy="5.669473158652" iyz="-0.007379583694" izz="3.683196351726" />
 160       </inertial>
 161 
 162       <visual>
 163         <origin xyz="0 0 0" rpy="0 0 0" />
 164         <geometry>
 165           <mesh filename="package://pr2_description/meshes/base_v0/base.stl" />
 166         </geometry>
 167         
 168         <material name="Green" />
 169       </visual>
 170 
 171       <collision>
 172         <!-- represent base collision with a simple rectangular model, positioned by base_size_z s.t. top
 173              surface of the collision box matches the top surface of the PR2 base -->
 174         <origin xyz="0 0 ${base_size_z-base_collision_size_z/2}" rpy="0 0 0" />
 175         <geometry>
 176           <box size="${base_size_x} ${base_size_y} ${base_collision_size_z}" />
 177         </geometry>
 178       </collision>
 179     </link>
 180 
 181 
 182     <!-- base laser -->
 183     <xacro:hokuyo_lx30_laser_v0 name="${name}_laser" parent="${name}" ros_topic="base_scan" update_rate="20" >
 184       <origin xyz="${base_laser_x} ${base_laser_y} ${base_laser_z}" rpy="0 0 0" />
 185     </xacro:hokuyo_lx30_laser_v0>
 186 
 187     <!-- all four caster macros -->
 188     <xacro:pr2_caster_v0 suffix="fl" parent="${name}_link" ref_position="${cal_caster_fl}" >
 189       <origin xyz="${caster_offset_x} ${caster_offset_y} ${caster_offset_z}" rpy="0 0 0" />
 190     </xacro:pr2_caster_v0>
 191     <xacro:pr2_caster_v0 suffix="fr" parent="${name}_link" ref_position="${cal_caster_fr}" >
 192       <origin xyz="${caster_offset_x} ${-caster_offset_y} ${caster_offset_z}" rpy="0 0 0" />
 193     </xacro:pr2_caster_v0>
 194     <xacro:pr2_caster_v0 suffix="bl" parent="${name}_link" ref_position="${cal_caster_bl}" >
 195       <origin xyz="${-caster_offset_x} ${caster_offset_y} ${caster_offset_z}" rpy="0 0 0" />
 196     </xacro:pr2_caster_v0>
 197     <xacro:pr2_caster_v0 suffix="br" parent="${name}_link" ref_position="${cal_caster_br}"  >
 198       <origin xyz="${-caster_offset_x} ${-caster_offset_y} ${caster_offset_z}" rpy="0 0 0" />
 199     </xacro:pr2_caster_v0>
 200 
 201     <!-- gazebo extensions -->
 202     <xacro:pr2_base_gazebo_v0 name="${name}" />
 203 
 204   </xacro:macro>
 205 
 206 
 207 
 208 
 209 
 210 </robot>

Now let's breakdown the entire macro piece by piece.

   2 <robot xmlns:sensor="http://playerstage.sourceforge.net/gazebo/xmlschema/#sensor"
   3        xmlns:controller="http://playerstage.sourceforge.net/gazebo/xmlschema/#controller"
   4        xmlns:interface="http://playerstage.sourceforge.net/gazebo/xmlschema/#interface"
   5        xmlns:xacro="http://ros.org/wiki/xacro">

The base XML element must be <robot>. Here we also specify the XML name spaces used in this URDF.

   7   <include filename="$(find pr2_description)/urdf/base_v0/base.gazebo.xacro" />

This file includes Gazebo simulator extensions. For more details, please see Gazebo URDF Extensions.

   8   <include filename="$(find pr2_description)/urdf/base_v0/base.transmission.xacro" />

This file includes transmission values used by PR2 Mechanism Model package.

  10   <!-- DATA SOURCES -->
  11   <!-- all link offsets, CG, limits are obtained from Function Engineering spreadsheet 090224_link_data.xls unless stated otherwise -->
  12   <!-- all link geometry sizes are obtained from Function provided CAD model unless stated otherwise -->
  13   <!-- all simplified collision geometry are hand approximated from CAD model, sometimes from respective bounding boxes -->
  14 
  15   <property name="M_PI" value="3.1415926535897931" />
  16 
  17   <property name="caster_offset_x" value="0.2225" />
  18   <property name="caster_offset_y" value="0.2225" />
  19   <property name="caster_offset_z" value="0.0282" />
  20 
  21   <property name="caster_wheel_offset_y" value="0.049" />
  22   <property name="wheel_length" value="0.034" />
  23   <property name="wheel_radius" value="0.074792" />   <!-- This is the 'effective' wheel radius. Wheel radius for uncompressed wheel is 0.079.  mp 20080801 -->
  24 
  25   <property name="base_cg_x" value="-0.061" />
  26   <property name="base_cg_y" value="0.0" />
  27   <property name="base_cg_z" value="0.293" />
  28   <property name="base_mass" value="116.0" />
  29 
  30   <!-- simplified box collision geometry for base -->
  31   <property name="base_size_x" value="0.65" />
  32   <property name="base_size_y" value="0.65" />
  33   <property name="base_size_z" value="0.23" />
  34   <property name="base_collision_size_z" value="0.04" />
  35 
  36   <!-- simplified box collision geometry for hokuyo laser -->
  37   <property name="base_laser_x" value="0.275" />
  38   <property name="base_laser_y" value="0.0" />
  39   <property name="base_laser_z" value="0.252" />
  40   <property name="base_laser_size_x" value="0.06" />
  41   <property name="base_laser_size_y" value="0.06" />
  42   <property name="base_laser_size_z" value="0.03" />
  43   <property name="base_laser_collision_offset_z" value="0.023" />

Defines a series of xacro parameters used by PR2 base URDF.

  45   <!--                                                      -->
  46   <!--           wheel                                      -->
  47   <!--                                                      -->
  48   <xacro:macro name="pr2_wheel_v0" params="suffix parent reflect">

Start of the xacro:pr2_wheel_v0 macro.

  50     <joint name="${parent}_${suffix}_wheel_joint" type="continuous">
  51       <axis xyz="0 1 0" />
  52       <limit effort="100" velocity="100"/>
  53       <safety_controller  k_velocity="10" />
  54       <dynamics damping="0.0" friction="0.0" />
  55       <origin xyz="0 ${reflect*caster_wheel_offset_y} 0" rpy="0 0 0" />
  56       <parent link="${parent}_rotation_link"/>
  57       <child link="${parent}_${suffix}_wheel_link"/>
  58     </joint>

This block defines a hinge joint attaching the wheel to the caster.

  59     <link name="${parent}_${suffix}_wheel_link">
  60       <inertial>
  61         <mass value="0.44036" />
  62         <origin xyz="0 0 0" />
  63         <inertia  ixx="0.012411765597" ixy="-0.000711733678" ixz="0.00050272983"
  64                   iyy="0.015218160428" iyz="-0.000004273467" izz="0.011763977943" />
  65       </inertial>
  66       <visual>
  67         <origin xyz="0 0 0" rpy="0 0 0" />
  68         <geometry>
  69           <mesh filename="package://pr2_description/meshes/base_v0/pr2_wheel.stl" />
  70         </geometry>
  71         
  72         <material name="Wheel_${suffix}" />
  73       </visual>
  74       <collision>
  75         <origin xyz="0 0 0" rpy="${M_PI/2} 0 0" /> <!-- rotation because cyl. geom primitive has symmetry axis in +x direction -->
  76         <geometry>
  77           <cylinder radius="${wheel_radius}" length="${wheel_length}" />
  78         </geometry>
  79       </collision>
  80     </link>

This block defines a rigid body link describing inertial/visual/collision properties of the wheel.

  83     <xacro:pr2_wheel_gazebo_v0 parent="${parent}" suffix="${suffix}" />

Invokes another xacro macro (contained in pr2_description/urdf/base_v0/base.gazebo.xacro) to expend Gazebo extensions for this PR2 wheel.

  84     <xacro:pr2_wheel_transmission_v0 parent="${parent}" suffix="${suffix}" reflect="${reflect}" />

Invokes another xacro macro (contained in pr2_description/urdf/base_v0/base.transmission.xacro) to expend PR2 transmission extensions for this PR2 wheel / caster hinge joint. That completes the definition of xacro:pr2_wheel_v0. XML elements with this name will now expand to the above elements.

  88   <!-- Macro for PR2 Caster hub only -->
  89   <xacro:macro name="pr2_caster_hub_v0" params="suffix parent *origin ref_position" >
  90     <joint name="${suffix}_rotation_joint" type="continuous">
  91       <axis xyz="0 0 1" />
  92       <limit effort="100" velocity="100"/>
  93       <safety_controller  k_velocity="10" />
  94       <calibration reference_position="${ref_position}" />
  95       <dynamics damping="0.0" friction="0.0" />
  96       <insert_block name="origin" />
  97       <parent link="${parent}"/>
  98       <child link="${suffix}_rotation_link" />
  99     </joint>
 100     <link name="${suffix}_rotation_link">
 101 
 102       <inertial>
 103         <mass value="3.473082"/>
 104         <origin xyz="0 0 0.07" />
 105         <inertia  ixx="0.012411765597" ixy="-0.000711733678" ixz="0.00050272983"
 106                   iyy="0.015218160428" iyz="-0.000004273467" izz="0.011763977943" />
 107       </inertial>
 108 
 109       <visual>
 110         <origin xyz="0 0 0" rpy="0 0 0" />
 111         <geometry>
 112           <mesh filename="package://pr2_description/meshes/base_v0/caster.stl" />
 113         </geometry>
 114         
 115         <material name="Green" />
 116       </visual>
 117 
 118       <collision>
 119         <origin xyz="0 0 0.07" rpy="0.0 0.0 0.0" />
 120         <geometry>
 121           <box size="0.192 0.164 0.013" />
 122         </geometry>
 123       </collision>
 124     </link>
 125 
 126     <!-- extensions -->
 127     <xacro:pr2_caster_transmission_v0 suffix="${suffix}" />
 128   </xacro:macro>

The above block defines a xacro:pr2_caster_hub_v0 macro, which defines physical properties of a single PR2 caster.

 139     <xacro:pr2_wheel_v0 parent="${suffix}_caster" suffix="r" reflect="-1" />
 140 
 141     <!-- extensions -->
 142     <xacro:pr2_caster_gazebo_v0 suffix="${suffix}" />
 143   </xacro:macro>

This block defines a complete PR2 caster (xacro:pr2_caster_v0) which includes a xacro:pr2_caster_hub_v0 and two xacro:pr2_wheel_v0 macros for the left and right wheels. Note the trick we use to differentiate between the two: xacro:pr2_wheel_v0 has a parameter reflect which equals 1 or -1, and this is used as a multiplier to get the right numerical parameters within the definition.

 146   <!-- The xacro macro xacro:pr2_base contains: base, casters and wheels -->
 147   <xacro:macro name="pr2_base_v0" params="name *origin">

Beginning of the xacro:pr2_base_v0 macro.

 148     <joint name="${name}_joint" type="planar">
 149       <insert_block name="origin" />
 150       <parent link="world"/>
 151       <child link="${name}_link" />
 152     </joint>

Defines a PLANAR joint between the PR2 base link and the world. Here the world-link is interpreted as a special case to be a reference frame attached to the absolute inertial frame.

 153     <link name="${name}_link">
 154 
 155       <inertial>
 156         <mass value="${base_mass}" />
 157         <origin xyz="${base_cg_x} ${base_cg_y} ${base_cg_z}" />
 158         <inertia ixx="5.652232699207" ixy="-0.009719934438" ixz="1.293988226423"
 159                  iyy="5.669473158652" iyz="-0.007379583694" izz="3.683196351726" />
 160       </inertial>
 161 
 162       <visual>
 163         <origin xyz="0 0 0" rpy="0 0 0" />
 164         <geometry>
 165           <mesh filename="package://pr2_description/meshes/base_v0/base.stl" />
 166         </geometry>
 167         
 168         <material name="Green" />
 169       </visual>
 170 
 171       <collision>
 172         <!-- represent base collision with a simple rectangular model, positioned by base_size_z s.t. top
 173              surface of the collision box matches the top surface of the PR2 base -->
 174         <origin xyz="0 0 ${base_size_z-base_collision_size_z/2}" rpy="0 0 0" />
 175         <geometry>
 176           <box size="${base_size_x} ${base_size_y} ${base_collision_size_z}" />
 177         </geometry>
 178       </collision>
 179     </link>

This block defines the PR2 base link.

 182     <!-- base laser -->
 183     <xacro:hokuyo_lx30_laser_v0 name="${name}_laser" parent="${name}" ros_topic="base_scan" update_rate="20" >
 184       <origin xyz="${base_laser_x} ${base_laser_y} ${base_laser_z}" rpy="0 0 0" />
 185     </xacro:hokuyo_lx30_laser_v0>

This block defines a laser scanner xacro:hokuyo_lx30_laser_v0, where the reference frame of base_laser defines the origin of range scans produced by the Hokuyo laser range scanner. In simulation, the Gazebo extensions tutorial explains how to define a laser sensor that produces the same ROS topic message as a real Hokuyo laser scanner.

 187     <!-- all four caster macros -->
 188     <xacro:pr2_caster_v0 suffix="fl" parent="${name}_link" ref_position="${cal_caster_fl}" >
 189       <origin xyz="${caster_offset_x} ${caster_offset_y} ${caster_offset_z}" rpy="0 0 0" />
 190     </xacro:pr2_caster_v0>
 191     <xacro:pr2_caster_v0 suffix="fr" parent="${name}_link" ref_position="${cal_caster_fr}" >
 192       <origin xyz="${caster_offset_x} ${-caster_offset_y} ${caster_offset_z}" rpy="0 0 0" />
 193     </xacro:pr2_caster_v0>
 194     <xacro:pr2_caster_v0 suffix="bl" parent="${name}_link" ref_position="${cal_caster_bl}" >
 195       <origin xyz="${-caster_offset_x} ${caster_offset_y} ${caster_offset_z}" rpy="0 0 0" />
 196     </xacro:pr2_caster_v0>
 197     <xacro:pr2_caster_v0 suffix="br" parent="${name}_link" ref_position="${cal_caster_br}"  >
 198       <origin xyz="${-caster_offset_x} ${-caster_offset_y} ${caster_offset_z}" rpy="0 0 0" />
 199     </xacro:pr2_caster_v0>

Invokes pr2_caster xacro macros, pulls in 4 casters and 8 wheels in total to the PR2 base.

 201     <!-- gazebo extensions -->
 202     <xacro:pr2_base_gazebo_v0 name="${name}" />

More Gazebo extensions for the PR2 base.

Next Tutorial: PR2 URDF Gazebo Extensions.

Wiki: urdf/Tutorials/UnderstandingPR2URDFAdvanced (last edited 2009-11-18 20:34:38 by hsu)