URDF¶
Introduction¶
This tutorial explains how one can describe the links and joints of a robot using URDF (http://wiki.ros.org/urdf). The description may then be used to visualize and simulate the robot, it’s sensors and their properties. Use the Desktop P.C. for this Tutorial.
Lines beginning with $ are terminal commands.
To open a new terminal → use the shortcut
Ctrl + Alt + T
.To open a new tab inside an existing terminal → use the shortcut
Ctrl + Shift +T
.To kill a process in a terminal → use the shortcut
Ctrl + C
.
Lines beginning with # indicate the syntax of the commands.
Code is separated in boxes.
Code is case sensitive.
Requirements¶
We will need the additional package joint_state_publisher, which is not yet available as binary in ROS2 Foxy. So we will compile it from source:
$ cd ~/robot_ws/src
$ git clone -b ros2 https://github.com/ros/joint_state_publisher
$ cd ..
$ colcon build
$ source ~/robot_ws/install/setup.bash
Also the package xacro is missing, which is necessary:
$ sudo apt install ros-foxy-xacro
Create the Turtlebot3 model¶
The Unified Robot Description Format is an XML based file format used in ROS to describe the robot’s mechanical configuration and physical properties. URDF can be used in RViz and Gazebo to visualize and simulate robots.
Create a new package tb3_description in your robot_ws workspace. inside the package create a folder meshes and download the following CAD files in this folder:
tb3_waffle_base
left_tire
right_tire
webcam
laser
These files will be used for the geometrical description of our robot model to visualize the specific parts.
Create another folder urdf in this package and place here the
turtlebot3_waffle_base.urdf.xacro
and common_properties.xacro
files.
The turtlebot3_waffle_base.urdf.xacro is the main file wherein we will be building the turtlebot3 model.
All definitions for the joints, links, plugins, etc. should be defined within the outermost <robot> tags. Currently, the base or the chassis of the turtlebot3 includes a base_link and it’s projection on the ground, referred to as base_footprint.
Xacros(XML Macros) are commonly used to organize URDF files and include among other things, constant values, macros and other xacro files. This file demonstrates the use of one such xacro to include another file containing common constants.
The link tags may include the visual, collision and inertial properties of robot links. The joint tags specify joint properties between various links. The gazebo tags are used to specify additional details and features that are used for gazebo simulations.
Hint
Make sure that the path to all mesh files matches your actual setup/packages.
You can use this setup.py
file.
Create a file wheel.urdf.xacro in the urdf folder to describe the front wheels for the model:
<?xml version="1.0"?>
<robot xmlns:xacro="http://ros.org/wiki/xacro" name="turtlebot3_wheel">
<xacro:macro name="turtlebot3_wheel" params="alignment *origin">
<link name="wheel_${alignment}_link">
<visual>
<origin xyz="0 0 0" rpy="${M_PI*0.5} 0 0"/>
<geometry>
<mesh filename="package://tb3_description/meshes/${alignment}_tire.stl" scale="0.001 0.001 0.001"/>
</geometry>
<material name="orange"/>
</visual>
<inertial>
<origin xyz="0 0 0" />
<mass value="0.01" />
<inertia ixx="0.0000029925" ixy="0.0" ixz="0.0" iyy="0.0000029925" iyz="0.0" izz="0.000005445" />
</inertial>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<cylinder length="0.018" radius="0.033"/>
</geometry>
</collision>
</link>
<joint name="wheel_${alignment}_joint" type="continuous">
<parent link="base_link"/>
<child link="wheel_${alignment}_link"/>
<xacro:insert_block name="origin"/>
<axis xyz="0 0 1"/>
</joint>
<gazebo reference="wheel_${alignment}_link">
<mu1 value="10.0"/>
<mu2 value="10.0"/>
<kp value="500000.0" />
<kd value="10.0" />
<minDepth>0.001</minDepth>
<maxVel>0.1</maxVel>
<fdir1>1 0 0</fdir1>
<material>Gazebo/Orange</material>
</gazebo>
</xacro:macro>
</robot>
Now in order to include this file into the robot description, add the following line as shown to turtlebot3_waffle_base.urdf.xacro.
<!-- Turtlebot3 platform include files -->
<xacro:include filename="$(find tb3_description)/urdf/wheel.urdf.xacro"/>
Finally we use macros to replicate the code for each wheel with alignment and origin values as the variables:
<!-- Turtlebot3 wheel macros -->
<xacro:turtlebot3_wheel alignment="left">
<origin xyz="0.0 0.144 0.023" rpy="${-M_PI*0.5} 0 0"/>
</xacro:turtlebot3_wheel>
<xacro:turtlebot3_wheel alignment="right">
<origin xyz="0.0 -0.144 0.023" rpy="${-M_PI*0.5} 0 0"/>
</xacro:turtlebot3_wheel>
As you would have already noticed, the collision geometry of a link is generally a simplified version of the visual element in order to reduce the computation load.
Similarly, add the casters to support the rear of the turtlebot via a caster.urdf.xacro:
<?xml version="1.0"?>
<robot xmlns:xacro="http://ros.org/wiki/xacro" name="turtlebot3_caster">
<xacro:macro name="turtlebot3_caster" params="alignment *origin">
<link name="caster_back_${alignment}_link">
<inertial>
<origin xyz="0 0 0" />
<mass value="0.01" />
<inertia ixx="0.00000001" ixy="0.0" ixz="0.0" iyy="0.00000001" iyz="0.0" izz="0.00000001" />
</inertial>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<sphere radius="0.005"/>
</geometry>
</collision>
</link>
<joint name="caster_back_${alignment}_joint" type="fixed">
<parent link="base_link"/>
<child link="caster_back_${alignment}_link"/>
<xacro:insert_block name="origin"/>
</joint>
<gazebo reference="caster_back_${alignment}_link">
<mu1 value="0.0"/>
<mu2 value="0.0"/>
<kp value="500000.0" />
<kd value="10.0" />
<minDepth>0.001</minDepth>
<maxVel>0.1</maxVel>
</gazebo>
</xacro:macro>
</robot>
The corresponding include xacro:
<!-- Turtlebot3 platform include files -->
<xacro:include filename="$(find tb3_description)/urdf/caster.urdf.xacro"/>
The macros for each caster with alignment and origin values as the variables:
<!-- Turtlebot3 caster macros -->
<xacro:turtlebot3_caster alignment="left">
<origin xyz="-0.21 0.064 -0.004" rpy="0 0 0"/>
</xacro:turtlebot3_caster>
<xacro:turtlebot3_caster alignment="right">
<origin xyz="-0.21 -0.064 -0.004" rpy="0 0 0"/>
</xacro:turtlebot3_caster>
Using URDF to publish links¶
The robot_state_publisher package allows you to read the robot’s links and fixed joints from the URDF and publishes the links as transforms. Additionally the the joint_state_publisher subscribes to the topic /robot_description for all non fixed joint types. This topic is published by the robot_state_publisher. This can then be used to visualize the robot in RViz as described in the urdf file.
Exercise¶
Create a launch file in the package tb3_description called tb3_description.launch.py.
#!/usr/bin/env python3
import os
from ament_index_python.packages import get_package_share_directory
from launch import LaunchDescription
from launch_ros.actions import Node
import xacro
def generate_launch_description():
xacro_file_name = 'turtlebot3_waffle_base.urdf.xacro'
urdf_file_name = 'turtlebot3_waffle_base.urdf'
urdf_file = os.path.join(
get_package_share_directory('tb3_description'),
'urdf',
urdf_file_name)
xacro_file = os.path.join(
get_package_share_directory('tb3_description'),
'urdf',
xacro_file_name)
doc = xacro.process_file(xacro_file)
robot_desc = doc.toprettyxml(indent=' ')
f = open(urdf_file, 'w+')
f.write(robot_desc)
f.close()
return LaunchDescription([
Node(
package='robot_state_publisher',
node_executable='robot_state_publisher',
node_name='robot_state_publisher',
output='screen',
arguments=[urdf_file],
),
Node(
package='joint_state_publisher',
node_executable='joint_state_publisher',
node_name='joint_state_publisher',
output='screen',
),
])
Now launch the file and run RViz and add a RobotModel and TF. Switch the FixedFrame to base_footprint to visualize the Turtlebot3.
Hint
Set the description topic to /robot_description and the QoS policies to System default
Instead of separately creating the static transforms as described in Tutorial1: ROS2 TF2 (simplistic), you may utilize the already described urdf to display the robot.
Adding sensors to the platform¶
Now let us extend the robot model by adding the following:
Camera: Create a camera.urdf.xacro file in the urdf folder of tb3_description.
<?xml version="1.0"?>
<robot>
<link name="camera_link">
<visual>
<origin xyz="0 0 0" rpy="1.57 0 1.57"/>
<geometry>
<mesh filename="package://tb3_description/meshes/webcam.stl" scale="0.0001 0.0001 0.0001"/>
</geometry>
<material name="silver"/>
</visual>
<inertial>
<origin xyz="0 0 0" />
<mass value="0.001" />
<inertia ixx="0.001" ixy="0.0" ixz="0.0" iyy="0.001" iyz="0.0" izz="0.001" />
</inertial>
</link>
<joint name="camera_base_joint" type="fixed">
<parent link="base_link"/>
<child link="camera_link"/>
<origin xyz="-0.075 0.1 0.032" rpy="0 0 0"/>
</joint>
<link name="camera_lens_link"/>
<joint name="camera_lens_joint" type="fixed">
<parent link="camera_link"/>
<child link="camera_lens_link"/>
<origin xyz="0.09 -0.0087 0.0625" rpy="0 0 0"/>
</joint>
</robot>
IMU: Create a imu.urdf.xacro file in the urdf folder of tb3_description.
<?xml version="1.0"?>
<robot>
<link name="imu_link"/>
<joint name="imu_joint" type="fixed">
<parent link="base_link"/>
<child link="imu_link"/>
<origin xyz="0.0 0 0.068" rpy="0 0 0"/>
</joint>
</robot>
LASER Scanner: Create a laser.urdf.xacro file in the urdf folder of tb3_description.
<?xml version="1.0"?>
<robot>
<link name="laser_link">
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="package://tb3_description/meshes/hokuyo.dae"/>
</geometry>
</visual>
<inertial>
<origin xyz="0 0 0" />
<mass value="0.2" />
<inertia ixx="0.001" ixy="0.0" ixz="0.0" iyy="0.001" iyz="0.0" izz="0.001" />
</inertial>
<collision>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<box size="0.05 0.06 0.085"/>
</geometry>
</collision>
</link>
<joint name="laser_joint" type="fixed">
<parent link="base_link"/>
<child link="laser_link"/>
<origin xyz="-0.09 0 0.114" rpy="0 0 0"/>
</joint>
</robot>
The include xacro for the sensors:
<!-- sensors -->
<xacro:include filename="$(find tb3_description)/urdf/camera.urdf.xacro"/>
<xacro:include filename="$(find tb3_description)/urdf/imu.urdf.xacro"/>
<xacro:include filename="$(find tb3_description)/urdf/laser.urdf.xacro"/>
Restart tb3_description.launch.py to view the newly added frames and meshes in RViz.