Understanding URDF for 6-Axis Robotic Manipulators
- Karan Bhakuni
- Sep 29, 2024
- 7 min read
Updated: Mar 7
1. Introduction
What is URDF?
The Unified Robot Description Format (URDF) is an XML format used in the Robot Operating System (ROS) to describe a robot's physical configuration. It includes information about the robot's joints, links, dimensions, kinematics, and dynamics.
Importance of URDF in Robotics
URDF is vital for simulating robots in ROS environments, running control algorithms, and visualizing robots in tools like RViz and Gazebo.
2. General URDF Structure
Basic Elements of URDF
Robot Tag (<robot>): The <robot> tag is the root element that encompasses the entire robot model.
Link Tag (<link>): Represents a rigid body in the robot and includes the <inertial>, <visual>, and <collision> tags.
Joint Tag (<joint>): Defines how two links are connected, including revolute, prismatic, and fixed types.
Transmission Tag (<transmission>): Links actuators to joints for proper movement.
Example of a Simple URDF File:
<robot name="simple_robot">
<link name="base_link" />
<joint name="joint1" type="revolute">
<parent link="base_link"/>
<child link="link1"/>
</joint>
</robot>
3. URDF for 6-Axis Robotic Manipulator
Introduction to 6-Axis Robots
A 6-axis robot, with six degrees of freedom (DOF), is widely used in industrial automation for tasks such as welding, material handling, and assembly.
Components of a 6-Axis Robot
Key components of a 6-axis robot include the base, shoulder, elbow, wrist, and more.
Modeling the Links
Each link of the robot is modeled from the base to the end effector, ensuring accurate dimensions, orientations, and masses.
Defining Joints
Define the six revolute joints of the robot, with appropriate limits for motion, velocity, and effort.
Adding Inertia and Dynamics
Incorporate the inertia properties for each link to achieve realistic simulation behavior.
Incorporating Visual and Collision Elements
Add visual and collision elements to ensure accurate physics simulation in Gazebo.
Example URDF for a 6-Axis Robot:
<robot name="six_axis_robot">
<link name="base_link" />
<joint name="joint1" type="revolute">
<parent link="base_link"/>
<child link="link1"/>
</joint>
<joint name="joint2" type="revolute">
<parent link="link1"/>
<child link="link2"/>
</joint>
</robot>
Explanation of Key Tags in URDF
<robot name="six_axis_robot">
This tag defines the start of the robot model in URDF. The name="six_axis_robot" attribute assigns a unique name to the robot, which is useful in simulation and ROS applications. The robot's structure, including links and joints, is enclosed within this tag.
<joint name="joint1" type="revolute">
This introduces a revolute joint named joint1. Revolute joints allow rotational motion, similar to a robotic arm's elbow.
<parent link="base_link"/>
Specifies that the joint is attached to the parent link base_link, helping to build the kinematic chain of the robot.
<child link="link1"/>
The child link link1 is attached to the parent via the joint, forming a hierarchical structure.
<joint name="joint2" type="revolute">
A second revolute joint, joint2, connects link1 to link2, adding another axis of rotation and increasing the robot's flexibility.
5. Learning Joint Transformations in URDF
5.1 In the below figure we can see that to go from joint 1 to dummy joint only translation is required along z-axis with respect to joint 1.
<joint name = "j_dummy_1_2" type = "fixed">
<origin xyz = "0.0 0.0 0.2" rpy="0.0 0.0 0.0"/>
<parent link ="l1"/>
<child link="l2"/>
</joint>
<joint name = "j_dummy_1_2" type = "fixed">
<origin xyz = "0.0 0.0 0.2" rpy="0.0 0.0 0.0"/>
<parent link ="l1"/>
<child link="l2"/>
<axis xyz = "0.0 0.0 1.0">
</joint> | ![]() |
We can clearly see that in orgin xyz tag that the distance is mentioned.
5.2 In the below figure the translation is along z axis wrt dummy joint.
<joint name = "j2" type = "revolute">
<origin xyz = "0.25 0.0 0.0" rpy="0.0 ${pi/2} 0.0"/>
<parent link ="l2"/>
<child link="l3"/>
<axis xyz = "0.0 0.0 1.0"/>
</joint> | ![]() |
5.3 Similarly for below joints there is only tranlations in below directions.
<joint name = "j2" type = "revolute">
<origin xyz = "0.30 0.0 0.0" rpy="0.0 0.0 0.0"/>
<parent link ="l3"/>
<child link="l4"/>
<axis xyz = "0.0 0.0 1.0"/>
</joint> | ![]() |
<joint name = "j2" type = "revolute">
<origin xyz = "0.32 0.0 0.0" rpy="0.0 0.0 0.0"/>
<parent link ="l5"/>
<child link="l6"/>
<axis xyz = "0.0 0.0 1.0"/>
</joint> | ![]() |
<joint name = "j2" type = "fixed">
<origin xyz = "0.0 0.0 -0.24" rpy="0.0 0.0 0.0"/>
<parent link ="l4"/>
<child link="l5"/>
</joint> | ![]() |
5.4 Now for below 2 joint we have rotations and translations both that can be seen in the attached figures.
<joint name = "j5" type = "revolute">
<origin xyz = "0.0 0.0 0.25" rpy="0.0 ${-pi/2} 0.0"/>
<parent link ="l6"/>
<child link="le"/>
<axis xyz = "0.0 0.0 1.0"/>
</joint> | ![]() |
<joint name = "j6" type = "revolute">
<origin xyz = "0.32 0.0 0.0" rpy="0.0 ${pi/2} 0.0"/>
<parent link ="le"/>
<child link="le_1"/>
<axis xyz = "0.0 0.0 1.0"/>
</joint> | ![]() |
6. Advanced URDF Features
6.1 Using Xacro for Modular URDFs
Xacro (XML Macro) simplifies URDF creation by allowing the use of macros and parameters.
6.1.1. Modularity and Reusability
You can create a reusable macro for a robotic arm link. Instead of writing out the same XML code multiple times for identical parts, you define it once and reuse it.In this case, a single macro for the robot_arm_link is reused for multiple links of the robot.
<xacro:macro name="robot_arm_link" params="name length radius">
<link name="${name}">
<visual>
<geometry>
<cylinder length="${length}" radius="${radius}" />
</geometry>
<material name="silver" />
</visual>
<collision>
<geometry>
<cylinder length="${length}" radius="${radius}" />
</geometry>
</collision>
</link>
</xacro:macro>
<!-- Reuse the same link for multiple parts of the robot -->
<xacro:robot_arm_link name="link1" length="0.5" radius="0.05" />
<xacro:robot_arm_link name="link2" length="0.4" radius="0.05" />
<xacro:robot_arm_link name="link3" length="0.3" radius="0.05" />
6.1.2 Parameterization
Xacro allows the definition of parameters that can be dynamically passed into macros to adjust the properties of the robot model. This is useful for varying robot designs or configurations.Here, base_length and arm_radius are parameterized values that can be changed in one place, and the changes will propagate throughout the robot description.
<xacro:property name="base_length" value="0.6" />
<xacro:property name="arm_radius" value="0.05" />
<!-- Use the parameters in a macro -->
<xacro:macro name="robot_base" params="length radius">
<link name="base">
<visual>
<geometry>
<cylinder length="${length}" radius="${radius}" />
</geometry>
</visual>
</link>
</xacro:macro>
<xacro:robot_base length="${base_length}" radius="${arm_radius}" />
6.1.3 Simplifies Complex Models
Xacro simplifies large and complex URDF models by breaking them into manageable chunks. A full robotic arm with many joints and links can be split into smaller macros, making it easier to handle.
<xacro:macro name="robot_arm" params="link_length joint_name">
<link name="link_${joint_name}">
<visual>
<geometry>
<box size="${link_length} 0.1 0.1" />
</geometry>
</visual>
</link>
<joint name="joint_${joint_name}" type="revolute">
<parent link="link_${joint_name}" />
<child link="link_${joint_name}_child" />
<origin xyz="0 0 ${link_length}" rpy="0 0 0" />
<axis xyz="0 0 1" />
</joint>
</xacro:macro>
<!-- Call the macro to generate complex robot structure -->
<xacro:robot_arm link_length="0.5" joint_name="1" />
<xacro:robot_arm link_length="0.6" joint_name="2" />
6.1.4 Maintainability
Instead of changing multiple parts of a URDF file when you need to modify a value (e.g., change the mass of a component), you can define properties and parameters in a Xacro file to maintain the robot model more efficiently.If you decide to change the mass from 2.0 to 3.0, you only need to modify the link_mass property in one place, and it will update across all parts of the robot model.
<xacro:property name="link_mass" value="2.0" />
<xacro:macro name="robot_link" params="name mass">
<link name="${name}">
<inertial>
<mass value="${mass}" />
<origin xyz="0 0 0" rpy="0 0 0" />
</inertial>
</link>
</xacro:macro>
<xacro:robot_link name="link1" mass="${link_mass}" />
6.1.5 Conditional Logic
Xacro allows conditional statements like if or unless to enable or disable parts of the robot model based on parameters. This is useful for creating different robot configurations with the same file.In this example, the sensor_mount link will only be added if the with_sensor parameter is set to true. This flexibility allows you to modify robot configurations without duplicating files.
<xacro:property name="with_sensor" value="true" />
<link name="robot_body">
<visual>
<geometry>
<box size="0.5 0.2 0.2" />
</geometry>
</visual>
</link>
<!-- Add sensor only if 'with_sensor' is true -->
<xacro:if value="${with_sensor}">
<link name="sensor_mount">
<visual>
<geometry>
<box size="0.1 0.1 0.05" />
</geometry>
</visual>
</link>
</xacro:if>
6.2 Visualizing with RViz
Visualize the URDF model in RViz and troubleshoot common issues.
Below is the struucture of how the robot is able to visualized in Rviz.
6.2.1. robot_state_publisher
Purpose:
The robot_state_publisher is responsible for publishing the transforms (position and orientation) between the various links of a robot. It uses the robot's URDF model to compute these transformations based on the robot's joint states.
Functionality:
The robot_state_publisher listens to the joint states (positions, velocities, and efforts) coming from the /joint_states topic (typically published by a joint state publisher or a robot's controller).
Using the joint positions and the URDF description of the robot, it calculates the relative transforms between each of the robot's links.
It publishes these transforms as TF frames, which other nodes can subscribe to for tasks like localization, navigation, or visualization in tools like RViz.
6.2.2. joint_state_publisher
Purpose:
The joint_state_publisher is responsible for publishing the joint states (i.e., the current positions, velocities, and efforts of the joints) to the /joint_states topic.
Functionality:
For real robots: The joint state data typically comes from the robot's sensors or controllers, and the joint_state_publisher publishes this information.
For simulations: The joint states can be set manually, or the publisher can read these states from a file or a configuration, simulating the joint movements.
For visualization: It is often used alongside the robot_state_publisher in simulated environments to manually or automatically control joint angles.
6.2.3. joint_state_publisher_gui
The joint_state_publisher_gui is a graphical interface provided by the joint_state_publisher package. It allows you to manually adjust the joint positions of your robot in simulation or for testing purposes. This is especially useful when visualizing a robot model in tools like RViz, as it lets you interactively change the robot's joint angles and observe the effects in real-time.
6.2.4. Below is the graph of how the communication is happening between ROS Nodes.

6.2.5. Below is the robot model in Rviz.
![]() | ![]() |
Front View | Side View |
7. Common Issues and Troubleshooting
Correctly Handling Position and Orientation
Remember that in URDF files, all positions and orientations are relative to the last joint mentioned. When defining a new link or joint, the position values are always in the local coordinate system of the previous link or joint.
Joint Rotation and Link Alignment
Always aim to rotate joints rather than links and align joint rotations around the z-axis. This approach simplifies managing the URDF and aligns with Denavit-Hartenberg (DH) conventions, making the robot's kinematics easier to model and simulate.
Incorrect Link Orientations
Incorrect orientations are often caused by errors in axis definitions. Double-check these to ensure proper link alignment.
Joint Limit Errors
Define joint limits correctly to avoid exceeding the range of motion. This is essential when transitioning from simulation to real hardware. Accurate joint limits also improve inverse kinematics and cartesian planning.
Missing Visual or Collision Elements
Ensure that all file paths for visual and collision elements are correct, and the corresponding tags are properly configured.
8. Conclusion
Summary of Key Points
URDF is essential in robotics for modeling and simulating robots, especially 6-axis manipulators, and plays a crucial role in both research and industrial applications.
Encouragement to Experiment
Experimenting with URDF files is a great way to understand the behavior of robots in simulations and improve your robotics knowledge.
Comments