URDF File Format Explained: A Complete Guide with Examples
If you have ever wanted to simulate a robot, visualize its structure, or plan its motions, you have almost certainly encountered the URDF file format. It is the standard way to describe a robot's physical structure in the robotics ecosystem, and understanding it is a foundational skill for any robotics engineer.
This post walks through the URDF file format from the ground up. By the end, you will know how to read, write, and debug URDF files -- and you will have a complete working example you can load into any URDF-compatible tool.
What Is URDF?
URDF stands for Unified Robot Description Format. It is an XML-based file format that describes a robot's physical structure: its rigid bodies, how they connect, what they look like, and where they can collide.
Originally developed for ROS (Robot Operating System), URDF has become a de facto standard far beyond the ROS ecosystem. Gazebo, MoveIt, MuJoCo (via conversion), Isaac Sim, and dozens of other tools all consume URDF files. If you are working in robotics, you will encounter this format.
A URDF file answers three fundamental questions about a robot:
- What are the parts? (links -- the rigid bodies)
- How are they connected? (joints -- the connections between links)
- What do they look like and where can they collide? (visual and collision geometry)
The Two Building Blocks: Links and Joints
Every URDF file is built from just two element types: links and joints. That is it. Even a complex humanoid robot with 30 degrees of freedom is just a collection of links connected by joints.
Links
A link is a rigid body. It has a name and can optionally define three properties:
- Visual geometry -- what the link looks like when rendered
- Collision geometry -- a simplified shape used for collision detection
- Inertial properties -- mass and moment of inertia for physics simulation
Here is a simple link:
<link name="base_link">
<visual>
<geometry>
<box size="0.3 0.2 0.1"/>
</geometry>
<material name="blue">
<color rgba="0.0 0.0 0.8 1.0"/>
</material>
</visual>
<collision>
<geometry>
<box size="0.3 0.2 0.1"/>
</geometry>
</collision>
<inertial>
<mass value="2.0"/>
<inertia ixx="0.01" ixy="0.0" ixz="0.0"
iyy="0.02" iyz="0.0" izz="0.01"/>
</inertial>
</link>The visual and collision geometries do not have to match. In practice, collision geometry is often a simpler shape (a box or cylinder wrapping the real geometry) because physics engines run faster with fewer polygons. Visual geometry can use detailed meshes for realistic rendering.
Joints
A joint connects exactly two links: a parent and a child. It defines the type of motion allowed between them and where the connection point is.
URDF supports six joint types:
| Joint Type | Degrees of Freedom | Description |
|---|---|---|
revolute | 1 (rotation) | Rotates around an axis, with upper and lower limits |
continuous | 1 (rotation) | Rotates around an axis, no limits (like a wheel) |
prismatic | 1 (translation) | Slides along an axis, with upper and lower limits |
fixed | 0 | No motion -- rigidly attaches child to parent |
floating | 6 | Allows all motion (rarely used in practice) |
planar | 2 | Allows motion in a plane |
Here is a revolute joint connecting two links:
<joint name="shoulder_joint" type="revolute">
<parent link="base_link"/>
<child link="upper_arm"/>
<origin xyz="0.0 0.0 0.1" rpy="0 0 0"/>
<axis xyz="0 1 0"/>
<limit lower="-1.57" upper="1.57" effort="10.0" velocity="1.0"/>
</joint>Let us break this down:
parentandchild: The two links this joint connects. The child moves relative to the parent.origin: The position (xyz) and orientation (rpy-- roll, pitch, yaw in radians) of the joint frame relative to the parent link frame.axis: The axis of rotation (or translation for prismatic joints). Here, the joint rotates around the Y axis.limit: The allowed range of motion, maximum effort (force/torque), and maximum velocity. Required forrevoluteandprismaticjoints.
Visual Geometry and Materials
URDF supports four primitive geometry types for both visual and collision elements:
<!-- Box: width (x), depth (y), height (z) in meters -->
<geometry>
<box size="0.5 0.3 0.2"/>
</geometry>
<!-- Cylinder: radius and length in meters -->
<geometry>
<cylinder radius="0.05" length="0.4"/>
</geometry>
<!-- Sphere: radius in meters -->
<geometry>
<sphere radius="0.1"/>
</geometry>
<!-- Mesh: external 3D model file -->
<geometry>
<mesh filename="package://my_robot/meshes/arm.stl" scale="1.0 1.0 1.0"/>
</geometry>For materials, you can define colors inline or reference named materials:
<!-- Inline color definition -->
<material name="red">
<color rgba="0.8 0.0 0.0 1.0"/>
</material>
<!-- Texture from file -->
<material name="textured">
<texture filename="package://my_robot/textures/carbon_fiber.png"/>
</material>Materials defined on one link can be referenced by name on other links without redefining the color, which keeps your file clean.
Inertial Properties
For physics simulation, each link needs mass and inertia data. The inertia tensor is a 3x3 symmetric matrix, so URDF requires six values:
<inertial>
<origin xyz="0.0 0.0 0.05" rpy="0 0 0"/>
<mass value="1.5"/>
<inertia ixx="0.003" ixy="0.0" ixz="0.0"
iyy="0.003" iyz="0.0" izz="0.001"/>
</inertial>The origin inside <inertial> specifies the center of mass relative to the link's frame. Getting this right matters -- incorrect inertial properties are one of the most common reasons a robot behaves strangely in simulation.
If you are prototyping and do not have exact values, you can approximate. For a solid box of uniform density:
mass = density * width * depth * height
ixx = (1/12) * mass * (depth^2 + height^2)
iyy = (1/12) * mass * (width^2 + height^2)
izz = (1/12) * mass * (width^2 + depth^2)Transmissions
Transmissions describe the relationship between joints and actuators. They are required if you want to use the ros_control framework for hardware interfacing or simulation control:
<transmission name="shoulder_transmission">
<type>transmission_interface/SimpleTransmission</type>
<joint name="shoulder_joint">
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
</joint>
<actuator name="shoulder_motor">
<mechanicalReduction>50</mechanicalReduction>
</actuator>
</transmission>The mechanicalReduction value represents the gear ratio. A value of 50 means the motor turns 50 times for each revolution of the joint. Transmissions are not needed for visualization or basic simulation, but they become essential when you start controlling a real robot or using Gazebo with ros_control plugins.
A Complete Minimal Robot
Here is a complete URDF file for a simple two-link robot arm. You can save this as simple_arm.urdf and load it into any URDF viewer:
<?xml version="1.0"?>
<robot name="simple_arm">
<!-- Base link (fixed to the world) -->
<link name="base_link">
<visual>
<geometry>
<cylinder radius="0.08" length="0.05"/>
</geometry>
<material name="gray">
<color rgba="0.5 0.5 0.5 1.0"/>
</material>
</visual>
<collision>
<geometry>
<cylinder radius="0.08" length="0.05"/>
</geometry>
</collision>
<inertial>
<mass value="5.0"/>
<inertia ixx="0.008" ixy="0.0" ixz="0.0"
iyy="0.008" iyz="0.0" izz="0.016"/>
</inertial>
</link>
<!-- Upper arm -->
<link name="upper_arm">
<visual>
<origin xyz="0 0 0.15" rpy="0 0 0"/>
<geometry>
<cylinder radius="0.03" length="0.3"/>
</geometry>
<material name="blue">
<color rgba="0.0 0.2 0.8 1.0"/>
</material>
</visual>
<collision>
<origin xyz="0 0 0.15" rpy="0 0 0"/>
<geometry>
<cylinder radius="0.03" length="0.3"/>
</geometry>
</collision>
<inertial>
<origin xyz="0 0 0.15" rpy="0 0 0"/>
<mass value="1.0"/>
<inertia ixx="0.008" ixy="0.0" ixz="0.0"
iyy="0.008" iyz="0.0" izz="0.0005"/>
</inertial>
</link>
<!-- Forearm -->
<link name="forearm">
<visual>
<origin xyz="0 0 0.125" rpy="0 0 0"/>
<geometry>
<cylinder radius="0.025" length="0.25"/>
</geometry>
<material name="red">
<color rgba="0.8 0.0 0.0 1.0"/>
</material>
</visual>
<collision>
<origin xyz="0 0 0.125" rpy="0 0 0"/>
<geometry>
<cylinder radius="0.025" length="0.25"/>
</geometry>
</collision>
<inertial>
<origin xyz="0 0 0.125" rpy="0 0 0"/>
<mass value="0.5"/>
<inertia ixx="0.003" ixy="0.0" ixz="0.0"
iyy="0.003" iyz="0.0" izz="0.0002"/>
</inertial>
</link>
<!-- Shoulder joint -->
<joint name="shoulder_joint" type="revolute">
<parent link="base_link"/>
<child link="upper_arm"/>
<origin xyz="0 0 0.025" rpy="0 0 0"/>
<axis xyz="0 1 0"/>
<limit lower="-3.14" upper="3.14" effort="50.0" velocity="2.0"/>
</joint>
<!-- Elbow joint -->
<joint name="elbow_joint" type="revolute">
<parent link="upper_arm"/>
<child link="forearm"/>
<origin xyz="0 0 0.3" rpy="0 0 0"/>
<axis xyz="0 1 0"/>
<limit lower="-2.35" upper="2.35" effort="30.0" velocity="2.0"/>
</joint>
</robot>This gives you a base, an upper arm connected by a shoulder joint, and a forearm connected by an elbow joint. Both joints rotate around the Y axis, creating a planar arm that moves in the XZ plane.
The URDF Tree Structure
One important constraint to understand: URDF enforces a tree structure. Every link has exactly one parent joint (except the root link, which has none), and joints connect exactly one parent link to one child link. There are no loops.
This means you cannot directly represent a parallel mechanism (like a Stewart platform or a four-bar linkage) in URDF. For those cases, you would need SDF (Simulation Description Format), which supports closed kinematic chains, or you would need to approximate the mechanism with virtual joints.
In practice, this tree constraint is not a problem for the vast majority of robots: serial manipulators, mobile robots, legged robots, and most humanoids are all trees.
Loading and Validating URDF Files
Before loading a URDF into a simulator, it is good practice to validate it. ROS provides a tool for this:
$ check_urdf simple_arm.urdf
robot name is: simple_arm
---------- Successfully Parsed XML ---------------
root Link: base_link has 1 child(ren)
child(1): upper_arm
child(1): forearmYou can also visualize the link-joint tree:
$ urdf_to_graphviz simple_arm.urdf
Created file simple_arm.gv
Created file simple_arm.pdfIf you are working in Python and want to parse a URDF programmatically, the urdfpy or yourdfpy libraries make it straightforward:
from yourdfpy import URDF
robot = URDF.load("simple_arm.urdf")
# List all links
for link in robot.link_map:
print(f"Link: {link}")
# List all joints
for joint_name, joint in robot.joint_map.items():
print(f"Joint: {joint_name}, type: {joint.type}, "
f"parent: {joint.parent}, child: {joint.child}")
# Get joint limits
for joint_name, joint in robot.joint_map.items():
if joint.limit is not None:
print(f"{joint_name}: [{joint.limit.lower}, {joint.limit.upper}]")Common Mistakes and Debugging Tips
URDF files are deceptively simple, but there are several pitfalls that catch nearly everyone at least once.
Forgetting the root link. Every URDF must have exactly one root link -- a link that is not the child of any joint. If your robot appears at the wrong position in the simulator or falls through the ground, check that your root link is correct and that there is a fixed joint connecting it to the world frame if needed.
Getting the origin wrong. The <origin> tag on a joint specifies the transform from the parent link frame to the joint frame. A common mistake is to think it positions the child link in the world frame. It does not -- it positions the joint relative to the parent. Draw the frames on paper if you are confused.
Mismatched parent-child references. If a joint references a link name that does not exist, most parsers will silently fail or produce cryptic errors. Double-check your link and joint names for typos.
Missing inertial properties. If you are loading the URDF into a physics simulator and a link has no <inertial> element, the simulator may assign zero mass (making it immovable) or default values (making it behave unpredictably). Always define inertial properties for links that need to move.
Collision geometry too detailed. Using your high-resolution visual mesh as the collision mesh will slow down the physics engine dramatically. Use simplified convex hulls or primitive shapes for collision geometry. Save the detailed meshes for visual rendering only.
Units. URDF uses SI units: meters for length, kilograms for mass, radians for angles, and seconds for time. A common mistake when importing CAD models is having meshes scaled in millimeters instead of meters, which results in a robot that is 1000 times too large.
Axis direction. The <axis> element on a joint defaults to xyz="1 0 0" (X axis) if omitted. If your joint rotates around the wrong axis, check that you have explicitly set the axis direction.
Beyond URDF: Xacro
As robots grow more complex, URDF files become large and repetitive. If you have a robot with four identical legs, you would need to copy-paste the same link and joint definitions four times.
Xacro (XML Macros) solves this. It is a macro language that generates URDF. You define a leg once as a macro with parameters, then instantiate it four times with different names and positions:
<xacro:macro name="leg" params="prefix x_offset y_offset">
<link name="${prefix}_upper_leg">
<!-- ... -->
</link>
<link name="${prefix}_lower_leg">
<!-- ... -->
</link>
<joint name="${prefix}_hip_joint" type="revolute">
<parent link="body"/>
<child link="${prefix}_upper_leg"/>
<origin xyz="${x_offset} ${y_offset} 0" rpy="0 0 0"/>
<!-- ... -->
</joint>
<!-- ... -->
</xacro:macro>
<xacro:leg prefix="front_left" x_offset="0.15" y_offset="0.1"/>
<xacro:leg prefix="front_right" x_offset="0.15" y_offset="-0.1"/>
<xacro:leg prefix="rear_left" x_offset="-0.15" y_offset="0.1"/>
<xacro:leg prefix="rear_right" x_offset="-0.15" y_offset="-0.1"/>You then process the Xacro file to produce a standard URDF:
$ xacro quadruped.urdf.xacro > quadruped.urdfMost real-world robot descriptions use Xacro rather than raw URDF. Learning the URDF format first gives you the foundation; Xacro is the practical tool you will use daily.
Try It Yourself
Head to our URDF Viewer tool in the tools section. You can upload the simple_arm.urdf file from this tutorial (or any URDF file you have) and interactively inspect the kinematic chain, visualize joint axes, toggle collision geometry, and drag joint sliders to see the robot move.
Seeing the structure come alive in 3D is the fastest way to build intuition for how links, joints, and frames relate to each other. If something in this post was unclear, loading the example into the viewer will make it click.