/!\ 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 and URDF Part 2.

Understanding the PR2 Robot Description Extensions for Gazebo Simulator

Description: This tutorial explains URDF extensions used by Gazebo simulation.

Tutorial Level: ADVANCED

Next Tutorial: Addding Sensors to PR2 URDF

Gazebo URDF Extension Explained

A snapshot of the Gazebo URDF extension for the PR2 base is displayed here for dissection (original file in urdf/base_b0/base.gazebo.xacro in the pr2_description package):

   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 
   8   <xacro:macro name="pr2_wheel_gazebo_v0" params="suffix parent">
   9     <gazebo reference="${parent}_${suffix}_wheel_link">
  10       <mu1 value="100.0" />
  11       <mu2 value="100.0" />
  12       <kp  value="1000000.0" />
  13       <kd  value="1.0" />
  14       <material value="PR2/wheel_${suffix}" />
  15     </gazebo>
  16   </xacro:macro>
  17 
  18   <xacro:macro name="pr2_caster_gazebo_v0" params="suffix">
  19     <gazebo reference="${suffix}_caster_rotation_link">
  20       <material value="PR2/caster_texture" />
  21     </gazebo>
  22   </xacro:macro>
  23 
  24   <xacro:macro name="pr2_base_gazebo_v0" params="name">
  25     <gazebo reference="${name}_link">
  26       <selfCollide>true</selfCollide>
  27       <sensor:contact name="${name}_contact_sensor">
  28         <geom>${name}_link_geom</geom> <!--geomname = linkname + "_geom"-->
  29         <updateRate>100.0</updateRate>
  30         <controller:gazebo_ros_bumper name="${name}_gazebo_ros_bumper_controller" plugin="libgazebo_ros_bumper.so">
  31           <alwaysOn>true</alwaysOn>
  32           <updateRate>100.0</updateRate>
  33           <bumperTopicName>${name}_bumper</bumperTopicName>
  34           <interface:bumper name="${name}_bumper_iface" />
  35         </controller:gazebo_ros_bumper>
  36       </sensor:contact>
  37       <material value="PR2/Green" />
  38     </gazebo>
  39     <gazebo>
  40       <controller:gazebo_ros_p3d name="p3d_base_controller" plugin="libgazebo_ros_p3d.so">
  41         <alwaysOn>true</alwaysOn>
  42         <updateRate>100.0</updateRate>
  43         <bodyName>${name}_link</bodyName>
  44         <topicName>${name}_pose_ground_truth</topicName>
  45         <gaussianNoise>0.01</gaussianNoise>
  46         <frameName>map</frameName>
  47         <xyzOffsets>25.7 25.7 0</xyzOffsets> <!-- initialize odometry for fake localization-->
  48         <rpyOffsets>0 0 0</rpyOffsets>
  49         <interface:position name="p3d_base_position"/>
  50       </controller:gazebo_ros_p3d>
  51     </gazebo>
  52   </xacro:macro>
  53 
  54 
  55 
  56 
  57 
  58 </robot>

Let's begin the breakdown with the first Gazebo extension block,

   8   <xacro:macro name="pr2_wheel_gazebo_v0" params="suffix parent">
   9     <gazebo reference="${parent}_${suffix}_wheel_link">
  10       <mu1 value="100.0" />
  11       <mu2 value="100.0" />
  12       <kp  value="1000000.0" />
  13       <kd  value="1.0" />
  14       <material value="PR2/wheel_${suffix}" />
  15     </gazebo>
  16   </xacro:macro>

Gazebo extensions for simulating contact properties of the PR2 wheel. Defines friction coefficients $$\mu$$ for the two principle contact directions along the contact surface as defined by Open Dynamics Engine. Defines contact stiffness $$k_p$$ and contact damping $$k_d$$ for rigid body contacts as defined by Open Dynamics Engine. Here mu1 and mu2 are the friction coefficients of the wheels. In ODE, the two friction directions are decoupled. kp and kd are the equivalent stiffness and damping coefficients for contact joints (ODE uses cfm and erp, more detains can be found in the external documentation).

  18   <xacro:macro name="pr2_caster_gazebo_v0" params="suffix">
  19     <gazebo reference="${suffix}_caster_rotation_link">
  20       <material value="PR2/caster_texture" />
  21     </gazebo>
  22   </xacro:macro>

Custom visual material for PR2 caster. See pr2_common/pr2_description/urdf/materials.urdf.xacro for material definitions. This refers to the Ogre material for the caster. File Media/materials/scripts/pr2.material in the pr2_ogre package contains all the ogre texture definitions.

  26       <selfCollide>true</selfCollide>

This line indicates that the PR2 base will collide with EVERYTHING in the simulation world. Otherwise, simulation Models do not self-collide.

  27       <sensor:contact name="${name}_contact_sensor">
  28         <geom>${name}_link_geom</geom> <!--geomname = linkname + "_geom"-->
  29         <updateRate>100.0</updateRate>
  30         <controller:gazebo_ros_bumper name="${name}_gazebo_ros_bumper_controller" plugin="libgazebo_ros_bumper.so">
  31           <alwaysOn>true</alwaysOn>
  32           <updateRate>100.0</updateRate>
  33           <bumperTopicName>${name}_bumper</bumperTopicName>
  34           <interface:bumper name="${name}_bumper_iface" />
  35         </controller:gazebo_ros_bumper>
  36       </sensor:contact>

The sensor:contact XML element is used by Gazebo dynamic plugins to produce a ROS topic message containing contact information such as contact force and contact object name whenever the PR2 wheel makes contact with another collision object. To see the output, start up a PR2 simulator and try the following command.

rostopic echo /bl_caster_l_wheel_bumper/state

You should see contact informations for the left wheel of the back-left caster.

  40       <controller:gazebo_ros_p3d name="p3d_base_controller" plugin="libgazebo_ros_p3d.so">
  41         <alwaysOn>true</alwaysOn>
  42         <updateRate>100.0</updateRate>
  43         <bodyName>${name}_link</bodyName>
  44         <topicName>${name}_pose_ground_truth</topicName>
  45         <gaussianNoise>0.01</gaussianNoise>
  46         <frameName>map</frameName>
  47         <xyzOffsets>25.7 25.7 0</xyzOffsets> <!-- initialize odometry for fake localization-->
  48         <rpyOffsets>0 0 0</rpyOffsets>
  49         <interface:position name="p3d_base_position"/>
  50       </controller:gazebo_ros_p3d>

This controller:ros_p3d XML element is used by Gazebo dynamic plugins to produce a ROS topic message containing ground truth pose information of the referred body. In this case, xacro parameter ${name} is base, so the plugin will broadcast a ROS topic name base_pose_ground_truth containing the ground truth pose of the base_link. For example, start up a PR2 simulator, then type

rostopic echo base_pose_ground_truth

and you should see something that looks like:

---
header: 
  seq: 12870
  stamp: 207113000000
  frame_id: map
child_frame_id: 
pose: 
  pose: 
    position: 
      x: 25.7099377589
      y: 25.6999839894
      z: 0.0454674888869
    orientation: 
      x: 2.22136641447e-06
      y: -8.19793042301e-05
      z: -0.000179916136524
      w: 0.999999980452
  covariance: (0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0)
twist: 
  twist: 
    linear: 
      x: 0.0112686762226
      y: -0.00506217267736
      z: -0.0286738360376
    angular: 
      x: -0.00263516963208
      y: -0.00444738598567
      z: -0.0168913324218
  covariance: (0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0)

Next Tutorial: Addding Sensors to PR2 URDF

Wiki: urdf/Tutorials/UnderstandingPR2URDFGazeboExtension (last edited 2011-10-10 11:19:04 by TimAssman)