Skip to main content

Overview

URDF (Unified Robot Description Format) is an XML-based format for describing a robot’s physical structure. It defines links (rigid bodies), joints (connections), and properties like mass, inertia, and visual geometry.
Why URDF? ROS2 needs to know your robot’s physical structure for:
  • Coordinate frame transforms (TF)
  • Visualization in RViz
  • Simulation in Gazebo
  • Collision detection
  • Motion planning

URDF Purpose in ROS2

Visualization

RViz displays your robot’s 3D model exactly as defined in URDF, showing sensor positions and orientations.

Coordinate Transforms

TF2 system uses URDF joint definitions to compute transforms between robot parts (e.g., base_link → wheel_link).

Simulation

Gazebo uses URDF for physics simulation, including masses, inertias, and collision geometries.

Motion Planning

Nav2 and MoveIt use URDF to understand robot dimensions for collision-free path planning.

URDF Concepts

Links are rigid bodies (physical parts of robot):
  • Robot base
  • Wheels
  • Sensor mounts
  • Camera/LiDAR bodies

Joints

Joints connect links and define motion constraints:
  • Fixed: No movement (e.g., sensor rigidly mounted to base)
  • Revolute: Rotation around axis (e.g., steering wheel)
  • Continuous: Unlimited rotation (e.g., drive wheels)
  • Prismatic: Linear sliding (e.g., elevator)

Coordinate Frames

Each link has a coordinate frame (origin + orientation):
  • X-axis: Forward (red in RViz)
  • Y-axis: Left (green in RViz)
  • Z-axis: Up (blue in RViz)
ROS Convention (REP-103):
  • X: forward
  • Y: left
  • Z: up
  • Rotation: right-hand rule

Basic URDF Structure

<?xml version="1.0"?>
<robot name="my_robot">

  <!-- Base link (root of robot tree) -->
  <link name="base_link">
    <visual>
      <!-- How it looks -->
    </visual>
    <collision>
      <!-- Collision geometry -->
    </collision>
    <inertial>
      <!-- Mass and inertia -->
    </inertial>
  </link>

  <!-- Child link (e.g., wheel) -->
  <link name="wheel_link">
    <!-- ... -->
  </link>

  <!-- Joint connecting links -->
  <joint name="base_to_wheel" type="continuous">
    <parent link="base_link"/>
    <child link="wheel_link"/>
    <origin xyz="0.1 0.15 0" rpy="0 0 0"/>
    <axis xyz="0 1 0"/>  <!-- Rotation axis -->
  </joint>

</robot>

Minimal URDF Example

Simple Box Robot

<?xml version="1.0"?>
<robot name="simple_box">

  <!-- Base link: a 1x1x0.5m box -->
  <link name="base_link">
    <visual>
      <geometry>
        <box size="1.0 1.0 0.5"/>
      </geometry>
      <material name="blue">
        <color rgba="0 0 1 1"/>  <!-- RGB + Alpha -->
      </material>
    </visual>
  </link>

</robot>
Save as: simple_box.urdf

Visualize in RViz

# Install tools
sudo apt install ros-jazzy-urdf-tutorial ros-jazzy-joint-state-publisher-gui

# Launch visualization
ros2 launch urdf_tutorial display.launch.py model:=simple_box.urdf
Result: RViz opens showing blue box.

Visual (Appearance)

<visual>
  <origin xyz="0 0 0" rpy="0 0 0"/>  <!-- Position relative to link frame -->
  <geometry>
    <box size="0.5 0.3 0.2"/>  <!-- Length Width Height -->
    <!-- OR -->
    <cylinder radius="0.05" length="0.1"/>
    <!-- OR -->
    <sphere radius="0.05"/>
    <!-- OR -->
    <mesh filename="package://my_robot/meshes/base.stl" scale="0.001 0.001 0.001"/>
  </geometry>
  <material name="red">
    <color rgba="1 0 0 1"/>
  </material>
</visual>

Collision (Physics)

<collision>
  <origin xyz="0 0 0" rpy="0 0 0"/>
  <geometry>
    <box size="0.5 0.3 0.2"/>  <!-- Simplified geometry for collision checking -->
  </geometry>
</collision>
Simplify collision geometry: Use basic shapes (box, cylinder) even if visual is complex mesh. Faster collision checking!

Inertial (Dynamics)

<inertial>
  <origin xyz="0 0 0" rpy="0 0 0"/>  <!-- Center of mass -->
  <mass value="2.5"/>  <!-- kg -->
  <inertia
    ixx="0.01" ixy="0.0" ixz="0.0"
    iyy="0.01" iyz="0.0"
    izz="0.01"/>
</inertial>
Inertia tensor for common shapes:
  • Box
  • Cylinder
  • Sphere
# Box: width (w), depth (d), height (h), mass (m)
ixx = (1/12) * m * (h^2 + d^2)
iyy = (1/12) * m * (w^2 + h^2)
izz = (1/12) * m * (w^2 + d^2)
ixy = iyz = ixz = 0

Joint Types

Fixed Joint

No motion allowed:
<joint name="base_to_sensor" type="fixed">
  <parent link="base_link"/>
  <child link="lidar_link"/>
  <origin xyz="0 0 0.3" rpy="0 0 0"/>
  <!-- Sensor 0.3m above base -->
</joint>
Use for: Sensors, static mounts

Continuous Joint

Unlimited rotation:
<joint name="base_to_wheel" type="continuous">
  <parent link="base_link"/>
  <child link="wheel_link"/>
  <origin xyz="0.15 0.2 0" rpy="0 0 0"/>
  <axis xyz="0 1 0"/>  <!-- Rotates around Y-axis -->
</joint>
Use for: Drive wheels, continuously rotating parts

Revolute Joint

Limited rotation:
<joint name="base_to_arm" type="revolute">
  <parent link="base_link"/>
  <child link="arm_link"/>
  <origin xyz="0 0 0.1" rpy="0 0 0"/>
  <axis xyz="0 0 1"/>
  <limit lower="-1.57" upper="1.57" effort="10" velocity="1.0"/>
  <!-- -90° to +90° -->
</joint>
Use for: Robot arms, steering joints

Prismatic Joint

Linear motion:
<joint name="base_to_slider" type="prismatic">
  <parent link="base_link"/>
  <child link="slider_link"/>
  <origin xyz="0 0 0" rpy="0 0 0"/>
  <axis xyz="0 0 1"/>  <!-- Slides along Z -->
  <limit lower="0" upper="0.5" effort="100" velocity="0.1"/>
</joint>
Use for: Linear actuators, elevators

Origin: Position and Orientation

Position (xyz)

<origin xyz="0.15 0.2 0" rpy="0 0 0"/>
<!--        X    Y   Z -->
  • X: forward/backward (m)
  • Y: left/right (m)
  • Z: up/down (m)

Orientation (rpy)

Roll-Pitch-Yaw in radians:
<origin xyz="0 0 0" rpy="0 0 1.57"/>
<!--                   R  P  Y    -->
  • Roll (R): Rotation around X-axis
  • Pitch (P): Rotation around Y-axis
  • Yaw (Y): Rotation around Z-axis
Common angles:
  • 90° = 1.5708 rad (π/2)
  • 180° = 3.1416 rad (π)
  • 270° = 4.7124 rad (3π/2)
Python helper:
import math
angle_rad = math.radians(90)  # Convert degrees to radians

URDF Best Practices

Problem: URDF is verbose and repetitive (4 wheels = lots of copy-paste).Solution: Use Xacro (XML Macros):
  • Define reusable macros (e.g., wheel macro)
  • Use variables for dimensions
  • Include external files
Example:
<!-- wheel_macro.xacro -->
<xacro:macro name="wheel" params="prefix reflect">
  <link name="${prefix}_wheel">
    <!-- Wheel definition -->
  </link>
</xacro:macro>

<!-- Use macro -->
<xacro:wheel prefix="front_left" reflect="1"/>
<xacro:wheel prefix="front_right" reflect="-1"/>
We’ll use Xacro extensively for Mecanum robot!
  1. Step 1: Base link only (box)
  2. Step 2: Add wheels (cylinders)
  3. Step 3: Add sensors (simple shapes)
  4. Step 4: Replace with detailed meshes
  5. Step 5: Add inertia and collision
Don’t start with complex meshes - hard to debug!
After each change:
ros2 launch urdf_tutorial display.launch.py model:=robot.urdf
Check:
  • Links appear at correct positions
  • Joints rotate correctly (use GUI sliders)
  • Coordinate frames (TF) are logical
Links:
  • base_link (root, always)
  • base_footprint (projection on ground)
  • wheel_FL, wheel_FR, wheel_RL, wheel_RR
  • lidar_link, imu_link, camera_link
Joints:
  • base_to_wheel_FL
  • base_to_lidar
Consistent naming helps debugging!
# Check URDF syntax
check_urdf robot.urdf

# Expected output:
# robot name is: mecanum_robot
# ---------- Successfully Parsed XML ---------------
Common errors:
  • Unclosed tags
  • Invalid joint parent/child references
  • Duplicate link names

URDF to Robot State Publisher

Once URDF is created, robot_state_publisher node publishes TF transforms:
# Launch robot state publisher
ros2 run robot_state_publisher robot_state_publisher --ros-args -p robot_description:="$(cat robot.urdf)"
What it does:
  • Reads URDF from robot_description parameter
  • Publishes static transforms for fixed joints
  • Subscribes to /joint_states for movable joints
  • Publishes complete TF tree
TF Tree Example:
base_link
├── wheel_FL
├── wheel_FR
├── wheel_RL
├── wheel_RR
├── lidar_link
└── imu_link

Visualization Tools

RViz

# Launch with URDF display
ros2 launch urdf_tutorial display.launch.py model:=robot.urdf
Features:
  • 3D visualization
  • TF frame axes (RGB = XYZ)
  • Joint state sliders (for revolute/continuous joints)

View Frames

# Generate TF tree diagram
ros2 run tf2_tools view_frames

# Output: frames.pdf (TF tree visualization)
evince frames.pdf

URDF to Graphviz

# Generate link-joint diagram
urdf_to_graphiz robot.urdf

# Output: robot.pdf
evince robot.pdf

Common URDF Mistakes

MistakeSymptomFix
Missing base_linkTF errors, no rootAlways have base_link as root
Wrong originParts floating/misalignedDouble-check xyz values
Wrong axisJoint rotates wrong wayVerify axis direction (X/Y/Z)
Missing inertiaGazebo crashesAdd <inertial> to all links
Negative massPhysics explosionUse positive mass values
Collision = VisualSlow simulationSimplify collision geometry
Large mesh scaleGiant robot in RVizAdjust scale in mesh

URDF Resources

File Locations (ROS2 Package)

mecanum_description/
├── urdf/
│   ├── mecanum_robot.urdf.xacro  (Main file)
│   ├── wheel.xacro               (Wheel macro)
│   └── sensors.xacro             (Sensor definitions)
├── meshes/
│   ├── base.stl
│   ├── wheel.stl
│   └── lidar.dae
├── launch/
│   └── display.launch.py
├── rviz/
│   └── config.rviz
└── package.xml

Typical Launch File

from launch import LaunchDescription
from launch_ros.actions import Node
from launch.actions import DeclareLaunchArgument
from launch.substitutions import Command, LaunchConfiguration
import os
from ament_index_python.packages import get_package_share_directory

def generate_launch_description():
    # Get URDF file path
    pkg_share = get_package_share_directory('mecanum_description')
    urdf_file = os.path.join(pkg_share, 'urdf', 'mecanum_robot.urdf.xacro')

    # Process xacro to URDF
    robot_description = Command(['xacro ', urdf_file])

    return LaunchDescription([
        # Robot state publisher
        Node(
            package='robot_state_publisher',
            executable='robot_state_publisher',
            parameters=[{'robot_description': robot_description}]
        ),

        # Joint state publisher GUI (for testing)
        Node(
            package='joint_state_publisher_gui',
            executable='joint_state_publisher_gui'
        ),

        # RViz
        Node(
            package='rviz2',
            executable='rviz2',
            arguments=['-d', os.path.join(pkg_share, 'rviz', 'config.rviz')]
        ),
    ])

Next Steps

References

[1] URDF Specification: http://wiki.ros.org/urdf/XML [2] URDF Tutorials: https://docs.ros.org/en/jazzy/Tutorials/Intermediate/URDF/URDF-Main.html [3] Xacro Documentation: http://wiki.ros.org/xacro