Example 2: URDF
Introduction
Unified Robot Description Format (URDF) is an XML format used in ROS (Robot Operating System) for representing a robot model. This model includes the robot’s physical components (links) and the connections between them (joints). URDF is essential for robot simulation, visualization, and control, making it a fundamental tool in robotics.
Common Uses of URDF
- Simulation: URDF files are used in simulation environments like Gazebo.
- Visualization: Tools like RViz use URDF to render the robot model.
- Control: URDF is integral in defining the robot’s kinematics and dynamics for control algorithms.
- IKM: using moveit.
Types of Joints in URDF
revolute
: Rotational motion with limits. (Manipulator arm)continuous
: Rotational motion without limits. (Mobile robot wheel)prismatic
: Translational motion with limits. (3D Printer)fixed
: No motion. (Fixed sensor)floating
: Six degrees of freedom (not commonly used in simple robots). (Drone to ground)planar
: Constrains motion to a plane (two translational and one rotational DOF). (Mobile robot to ground)
URDF XML Syntax
<link>
The <link>
tag defines a physical component of the robot. It can include several sub-elements that describe its properties and characteristics.
It contains the following elements:
<inertial>
- Describes the mass and inertia of the link.
- Sub-elements:
<origin>
: Specifies the pose of the inertial reference frame relative to the link reference frame.<mass>
: Defines the mass of the link.<inertia>
: Specifies the 3x3 inertia matrix of the link.
<visual>
- Defines the visual representation of the link.
- Sub-elements:
<origin>
: Specifies the pose of the visual element relative to the link reference frame.<geometry>
: Defines the shape of the visual element. Can be one of the following:<box>
: Defines a box shape with size attribute.<cylinder>
: Defines a cylinder shape with radius and length attributes.<sphere>
: Defines a sphere shape with radius attribute.<mesh>
: Defines a mesh shape with filename attribute (and optionally scale).<material>
: Specifies the appearance of the visual element. Can be either:<color>
: Defines the RGBA color of the material.
<collision>
- Defines the collision properties of the link.
- Sub-elements:
<origin>
: Specifies the pose of the collision element relative to the link reference frame.<geometry>
: Defines the shape of the collision element. Uses the same sub-elements as the<geometry>
element in<visual>
.
<sensor>
Optional tag for simulation only
Defines sensors attached to the link.
- Sub-elements:
<origin>
: Specifies the pose of the sensor relative to the link reference frame.- Specific sensor type tags (e.g.,
<camera>
,<ray>
).
<transmission>
Optional tag for simulation only
Defines transmissions associated with the link.
- Sub-elements:
<type>
: Defines the type of transmission (e.g., SimpleTransmission).<joint>
: Specifies the joint connected to the transmission.<actuator>
: Defines the actuator associated with the transmission.<mechanicalReduction>
: Defines the reduction factor for the transmission.
Joints
The
- Sub-elements of
: <parent>
\&<child>
- Specifies the parent and child links of the joint with attribute
<link>
using its name.<origin>
- Specifies the pose of the joint reference frame relative to the parent link reference frame.
- Attributes:
<xyz>
: Translation vector (e.g.,xyz="0 0 0"
).<rpy>
: Rotation vector (Roll, Pitch, Yaw) (e.g.,rpy="0 0 0"
).<axis>
- Specifies the axis of rotation or translation for the joint.
- Attributes:
<xyz>
: Axis vector (e.g.,xyz="0 0 1"
).<limit>
- Specifies the joint limits (applicable for revolute and prismatic joints).
- Attributes:
<lower>
: Lower limit of the joint (e.g.,lower="-1.57"
).<upper>
: Upper limit of the joint (e.g.,upper="1.57"
).<effort>
: Maximum effort (force/torque) that can be applied (e.g.,effort="100"
).<velocity>
: Maximum velocity of the joint (e.g.,velocity="1.0"
).<dynamics>
- Specifies the physical properties of the joint’s movement.
- Attributes:
<damping>
: Damping coefficient (e.g.,damping="0.1"
).<friction>
: Friction coefficient (e.g.,friction="0.01"
).<safety_controller>
- Specifies the safety controller parameters for the joint.
- Attributes:
<soft_lower_limit>
: Soft lower limit (e.g.,soft_lower_limit="-1.57"
).<soft_upper_limit>
: Soft upper limit (e.g.,soft_upper_limit="1.57"
).<k_position>
: Position correction gain (e.g.,k_position="10"
).<k_velocity>
: Velocity correction gain (e.g.,k_velocity="10"
).<calibration>
- Specifies the calibration parameters for the joint.
- Attributes:
<rising>
: Position at which the calibration rising edge occurs.<falling>
: Position at which the calibration falling edge occurs.<mimic>
- Specifies that the joint mimics the motion of another joint.
- Attributes:
<joint>
: Name of the joint to mimic.<multiplier>
: Multiplier for the mimic motion (e.g.,multiplier="1.0"
).<offset>
: Offset for the mimic motion (e.g.,offset="0.0"
).
Exercise 1: Creating a 2R Robot Arm
Prerequesets
- ROS 1 Installed (preferrably Noetic)
- A ROS workspace
Step 1: Create a RobotDescription
Package
#in ros_workspace
cd src
catkin_create_pkg my_robot_description urdf rviz
cd ..
catkin_make
source devel/setup.bash
Add necessary folders to host config files
cd src/my_robot_description
mkdir urdf launch rviz
Step 2: Write a new URDF file
nano urdf/3r_robot.urdf
Inside the newly created urdf file, define a world
<?xml version="1.0"?>
<robot name="3r_robot">
<link name="world">
<!-- other robot content here -->
</robot>
You should be able to visualize what you are building using various URDF visualization tools. There is a VSCode extension and there are some online tools to try out. This is especially useful in our example here.
Step 2:
Add the links to the URDF file so we can link them later using appropriate joints:
link_0
<link name="link_0">
<visual>
<geometry>
<box size="1 .1 .1"/>
</geometry>
<origin rpy="0 0 0" xyz="0.5 0 0"/>
</visual>
</link>
link_1
<link name="link_1">
<visual>
<geometry>
<box size="1 .05 .05"/>
</geometry>
<origin rpy="0 0 0" xyz="0.5 0 0"/>
</visual>
</link>
tool0
<link name="tool0"/>
Step 3: Add joints to define relationship between joints
In the same urdf xml file, add the following joints:
world_joint
<joint name="world_joint" type="fixed">
<origin xyz="0.0 0.0 0.0" rpy="0.0 0.0 0.0"/>
<parent link="world"/>
<child link="base_link"/>
</joint>
joint_0
<joint name="joint0" type="revolute">
<axis rpy="0 0 0" xyz="0 0 1"/>
<parent link="base_link"/>
<child link="link_0"/>
<limit lower="0.0" upper="6.28" effort="300.0" velocity="1.0"/>
</joint>
joint_1
<joint name="joint1" type="revolute">
<axis rpy="0 0 0" xyz="0 0 1"/>
<parent link="link_0"/>
<child link="link_1"/>
<origin rpy="0 0 0" xyz="1 0 0"/>
<limit lower="0.0" upper="6.28" effort="300.0" velocity="1.0"/>
</joint>
joint_ef
<joint name="joint_ef" type="fixed">
<parent link="link_1"/>
<child link="tool0"/>
<origin rpy="0 0 0" xyz="1 0 0"/>
</joint>
Step 4: Build the node and then view the URDF using rviz
Launch File
Create a launch file and po;ulate it with the following content. This will help us launch several nodes at once instead of manually launching them one-by-one.
nano launch/display.launch
Add the following content to the file:
<launch>
<param name="robot_description" command="$(find xacro)/xacro $(find my_robot_description)/urdf/3r_robot.urdf"/>
<node name="joint_state_publisher" pkg="joint_state_publisher_gui" type="joint_state_publisher_gui"/>
<node name="robot_state_publisher" pkg="robot_state_publisher" type="robot_state_publisher"/>
<node name="rviz" pkg="rviz" type="rviz" args="-d $(find my_robot_description)/rviz/3r_robot.rviz"/>
</launch>
The last node to launch is the rviz
node. Note that we specified a path for a configuration file named 3r_robot.rviz
. This will be useful to store viewing configuration (view angle, setup, background and grid config, …). rviz
will prompt you upn exit to specify if you want to save the configuration or not.
So now we have to create this file so that rviz can write in it. We somply create an empty file:
nano rviz/3r_robot.rviz
Launching the visualization
# in workspace folder
source /opt/ros/noetic/setup.bash
catkin_make
source devel/setup.bash
roslaunch my_robot_description display.launch
Explore some more
Try adding some material properties to your URDF links to make them colorful. Also, explore with adding collision geometry, inertia, and other properties discussed above.
Try exploring some simple URDF files online for inspiration.
XACRO
XACRO (XML Macros) is a powerful tool in ROS (Robot Operating System) for simplifying the creation of URDF (Unified Robot Description Format) files. URDF files can become very large and complex when defining robots with many links and joints. XACRO helps manage this complexity by allowing the use of macros, parameters, and conditional logic within XML. This makes the robot description more modular, reusable, and easier to maintain.
Key features
- Macros: Define reusable blocks of XML code.
- Parameters: Use variables to avoid hardcoding values.
- Conditional Statements: Apply logic to include or exclude parts of the XML.
Exercise 2: Simple XACRO Macro example
Step 1: Install XACRO
sudo apt-get install ros-noetic-xacro
Step 2: Create XACRO file
Create a file named simple_robot.xacro
.
<!-- simple_robot.xacro -->
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="simple_robot">
<!-- Define a macro for a link -->
<xacro:macro name="simple_link" params="link_name box_width">
<link name="${link_name}">
<origin rpy="0 0 0" xyz="0.5 0 0"/>
<visual>
<geometry>
<box size="1 ${box_width} ${box_width}"/>
</geometry>
</visual>
</link>
</xacro:macro>
<!-- Define a macro for a joint -->
<xacro:macro name="simple_joint" params="joint_name parent_link child_link">
<joint name="${joint_name}" type="fixed">
<parent link="${parent_link}"/>
<child link="${child_link}"/>
<origin xyz="1 0 0" rpy="0 0 0"/>
<axis rpy="0 0 0" xyz="0 0 1"/>
<limit lower="0.0" upper="6.28" effort="300.0" velocity="1.0"/>
</joint>
</xacro:macro>
<!-- Use the macros to create links and joints -->
<xacro:simple_link link_name="link_1"/>
<xacro:simple_link link_name="link_2"/>
<xacro:simple_joint joint_name="joint_1" parent_link="link_1" child_link="link_2"/>
</robot>
Step 3: Generate the URDF.
rosrun xacro xacro simple_robot.xacro -o simple_robot.urdf
Step 4: Visualize
We can now use some of the tools we discussed above to visualize the URDF file.
Useful XACRO Syntax
Basic Syntax
- XACRO files are XML files with additional macros and parameterization capabilities.
- The typical file extension is
.xacro
.
Comments
-
Use XML comments to add notes or disable parts of the code:
<!-- This is a comment -->
XACRO XML Namespace
-
Always include the XACRO namespace in the root element:
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="robot_name">
Macros
-
Macros are defined using
<xacro:macro>
tags:<xacro:macro name="my_macro"> <!-- Macro content --> </xacro:macro>
Calling Macros
- Call a macro using the
<xacro:macro_name>
syntax:<xacro:my_macro/>
Parameters
- Define parameters within macros to make them reusable and configurable:
<xacro:macro name="box_link" params="link_name box_size"> <link name="${link_name}"> <visual> <geometry> <box size="${box_size}"/> </geometry> </visual> </link> </xacro:macro>
Properties
- Define properties to store values and use them throughout the document:
<xacro:property name="link_length" value="1.0"/> <xacro:property name="link_color" value="0 1 0 1"/>
Useing Properites
- Access properties using
${property_name}
syntax:<material> <color rgba="${link_color}"/> </material>
Conditionals
- Use
if
andunless
conditions to include or exclude parts of the document:<xacro:if value="${use_sphere}"> <geometry> <sphere radius="1.0"/> </geometry> </xacro:if> <xacro:unless value="${use_sphere}"> <geometry> <box size="1 1 1"/> </geometry> </xacro:unless>
Include
-
Reuse code by including other XACRO files:
<xacro:include filename="$(find package_name)/urdf/other_file.xacro"/>
Command-Line Arguments
- Pass arguments to XACRO from the command line:
rosrun xacro xacro --inorder my_robot.xacro my_arg:=value
Default Parameter Values
- Provide default values for parameters:
<xacro:macro name="example_macro" params="param1:=default1 param2:=default2"> <!-- Macro content --> </xacro:macro>
Math Expressions
- Perform mathematical operations directly in XACRO:
<xacro:property name="half_length" value="${length / 2.0}"/>
Debugging and Validation
-
Validate XACRO files by converting them to URDF and checking for errors:
rosrun xacro xacro --inorder my_robot.xacro -o my_robot.urdf check_urdf my_robot.urdf