Note: This tutorial assumes that you have completed the previous tutorials: Setting up urdf, differential_drive PID setup.
(!) 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.

URDF setup for differential_drive

Description: Setting up the differential_drive package URDF and transforms

Tutorial Level: BEGINNER

Introduction

The URDF file is used to describe the robot shape and the position of the various components for the RVIZ visualization program. The URDF tutorials give a good overview.

Create your first URDF

At a minimum, the robot URDF requires a base_link. The origin of this link should be the center of the axle of the robot, and this will serve as the reference point for the odometry. The minimal urdf file looks like this:

   1 <robot name="test_robot">
   2 
   3   <link name="base_link">
   4     <visual>
   5       <geometry>
   6         <box size="0.16 0.16 0.12"/>
   7       </geometry>
   8       <origin rpy="0 0 0" xyz="0 0 0.085"/>
   9       <material name="white">
  10         <color rgba="1 1 1 1"/>
  11       </material>
  12     </visual>
  13   </link>
  14 
  15 </robot>

Next, edit your launch file to include these two lines:

  <param name="robot_description" textfile="$(find my_robot)/my_robot.urdf" />
  <node pkg="rviz" type="rviz" name="rviz" output="screen"/>
  <node pkg="differential_drive" type="diff_tf.py" name="diff_tf">
     <rosparam param="rate">8.0</rosparam>
     <rosparam param="base_width">0.245</rosparam>
  </node>
  <node name="robot_state_publisher" pkg="robot_state_publisher" type="state_publisher" /> 

(URDF and robot_state_publisher are part of the robot_model stack. Does that need to be installed, or is it part of core ROS installation? Does it need to be a dependancy?) Launch this launch file, and you should be able to drive the robot and have RVIZ track its location.

Update the URDF

The next step is to update the URDF file to look more like your robot. Add wheels and other components. The URDF tutorials are the best place to look for more information. Here is how my robot's URDF file ended up:

   1 <robot name="test_robot">
   2 
   3   <link name="base_link">
   4     <visual>
   5       <geometry>
   6         <box size="0.16 0.16 0.12"/>
   7       </geometry>
   8       <origin rpy="0 0 0" xyz="0 0 0.085"/>
   9       <material name="white">
  10         <color rgba="1 1 1 1"/>
  11       </material>
  12     </visual>
  13   </link>
  14   
  15   <link name="lwheel">
  16     <visual>
  17       <geometry>
  18         <cylinder length="0.008" radius="0.046"/>
  19       </geometry>
  20       <origin rpy="0 0 0" xyz="0 0 0"/>
  21       <material name="black">
  22         <color rgba="0 0 0 1"/>
  23       </material>
  24     </visual>
  25   </link>
  26   
  27   <joint name="base_to_lwheel" type="fixed">
  28     <parent link="base_link"/>
  29     <child link="lwheel"/>
  30     <origin xyz="0 0.115 0.046" rpy="1.5708 0 0"/>
  31   </joint>
  32   
  33   <link name="rwheel">
  34     <visual>
  35       <geometry>
  36         <cylinder length="0.008" radius="0.046"/>
  37       </geometry>
  38       <origin rpy="0 0 0" xyz="0 0 0"/>
  39       <material name="black">
  40         <color rgba="0 0 0 1"/>
  41       </material>
  42     </visual>
  43   </link>
  44   
  45   <joint name="base_to_rwheel" type="fixed">
  46     <parent link="base_link"/>
  47     <child link="rwheel"/>
  48     <origin xyz="0 -0.115 0.046" rpy="-1.5708 0 0"/>
  49   </joint>
  50   
  51   <link name="fwheel_attach">
  52     <visual>
  53       <geometry>
  54         <cylinder length="0.060" radius="0.023"/>
  55       </geometry>
  56       <origin rpy="0 0 0" xyz="0.13 0 0.08"/>
  57       <material name="white">
  58         <color rgba="1 1 1 1"/>
  59       </material>
  60     </visual>
  61   </link>
  62   
  63   <joint name="base_to_fattach" type="fixed">
  64     <parent link="base_link"/>
  65     <child link="fwheel_attach"/>
  66     <origin xyz="0 0 0" rpy="0 0 0"/>
  67   </joint>
  68   
  69   <link name="fwheel">
  70     <visual>
  71       <geometry>
  72         <cylinder length="0.005" radius="0.020"/>
  73       </geometry>
  74       <origin rpy="1.578 0 0" xyz="0 0 0"/>
  75       <material name="black">
  76         <color rgba="0 0 0 1"/>
  77       </material>
  78     </visual>
  79   </link>
  80   
  81   <joint name="base_to_fwheel" type="fixed">
  82     <parent link="base_link"/>
  83     <child link="fwheel"/>
  84     <origin xyz="0.13 0 0.02" rpy="0 0 0"/>
  85   </joint>
  86   
  87   <link name="scanner">
  88     <visual>
  89       <geometry>
  90         <box size="0.015 0.045 0.015"/>
  91       </geometry>
  92       <origin rpy="0 0 0" xyz="0.022 0 0.015"/>
  93       <material name="black">
  94         <color rgba="0 0 0 1"/>
  95       </material>
  96     </visual>
  97   </link>
  98   
  99   <joint name="base_to_scanner" type="fixed">
 100     <parent link="base_link"/>
 101     <child link="scanner"/>
 102     <origin xyz="0.105 0 0.22" rpy="0 0 0"/>
 103   </joint>
 104   
 105 </robot>

Wiki: differential_drive/tutorials/setup_urdf (last edited 2021-11-16 16:56:28 by BarisYazici)