Tesseract 0.28.4
Loading...
Searching...
No Matches
Universal Robot Description Format (URDF)

URDF describes robot kinematic, dynamic, and visual structure in a standardized XML format.

The Universal Robot Description Format (URDF) is the standard way to describe a robot in ROS. It defines:

  • Kinematic structure – Links (rigid bodies) and joints (connections) forming the robot's skeleton
  • Masses and inertias – Dynamics information for simulation and control
  • Geometry and appearance – Visual meshes (for display) and collision meshes (for planning and checking)
  • Coordinate frames – Links are connected in a tree that defines all reference frames
  • Joint limits – Position, velocity, and effort boundaries

Your URDF essentially answers: **"What does my robot physically consist of?"**

Once you have a valid URDF, tools like Tesseract can parse it, build internal representations, and use it for collision detection, motion planning, visualization, and simulation.

Getting Started? See Tesseract URDF Loading Example for a complete walkthrough of loading and using URDF files in code.

Key Concepts

What You Need to Know About URDF**

A URDF is a tree of links connected by joints:

  • A link is a rigid body (has geometry, mass, inertias)
  • A joint connects two links (position, velocity, effort limits)
  • One link is the root (the "world" or fixed base)
  • All other links hang from the root through their parent joints

    Example: 6-DOF Robot Arm**

  • Root link: "base" (fixed to ground)
  • Joint: "joint_1" (revolute, 1 DOF) connects "base" → "link_1"
  • Joint: "joint_2" (revolute, 1 DOF) connects "link_1" → "link_2"
  • ... continue for 6 joints total
  • Tip link: "tool_flange" (where the end-effector attaches)

    URDF vs SRDF**

Aspect URDF SRDF
Purpose Physical structure and kinematics Semantic meaning and planning configuration
Content Links, joints, masses, geometry, frames Planning groups, collision rules, poses, TCPs
Usage Load robot into planning/simulation tools Configure planners and collision handlers
Required Yes, always Often yes (strongly recommended with URDF)

See Semantic Robot Description Format (SRDF) for more details on semantic descriptions.

URDF Structure

A basic URDF contains:

Links** – Represent rigid bodies

<link name="link_name">
<inertial>
<mass value="1.0"/>
<inertia ixx="0.01" ixy="0.0" ixz="0.0" iyy="0.01" iyz="0.0" izz="0.01"/>
</inertial>
<visual>
<geometry>
<mesh filename="package://my_robot/meshes/link.dae"/>
</geometry>
</visual>
<collision>
<geometry>
<mesh filename="package://my_robot/meshes/link_collision.dae"/>
</geometry>
</collision>
</link>

Joints** – Connect links and define motion

<joint name="joint_name" type="revolute">
<parent link="link_1"/>
<child link="link_2"/>
<origin xyz="0 0 0" rpy="0 0 0"/>
<axis xyz="0 0 1"/>
<limit lower="-3.14" upper="3.14" effort="100" velocity="2.0"/>
</joint>

Joint Types:**

Type DOF Range Use Case
revolute 1 Limited rotation Arm joints, rotation axes
continuous 1 Unlimited rotation (-∞ to ∞) Wheels, continuous spindles
prismatic 1 Limited translation Linear actuators, slides
fixed 0 None (rigidly attached) Sensors, brackets, tools
floating 6 Unlimited Mobile bases, free-floating objects
planar 3 Planar motion (x, y, θ) Mobile bases on flat terrain

Best Practices for Tesseract Compatibility

Before loading your URDF into Tesseract, review these guidelines to ensure smooth integration.

Joint and Link Naming

Avoid these special characters in joint and link names:**

  • Hyphens: -
  • Brackets: [ ]
  • Parentheses: ( )

These characters cause parsing issues in Tesseract. Use underscores or CamelCase instead.

Good names:** joint_1, link_2_base, toolFlange Bad names:** joint-1, link[2], tool_flange(tcp)

Joint Limits and Safety Controllers

Many URDFs specify both hard limits and soft limits (safety limits).

Hard Limits** – Primary joint boundaries, set in the <limit> tag:

<limit lower="-1.57" upper="1.57" effort="150" velocity="2.0"/>

Soft Limits** – Conservative boundaries for safe operation, set in <safety_controller>:

<safety_controller k_position="100" k_velocity="1.5"
soft_lower_limit="-2.857" soft_upper_limit="2.857"/>

How Tesseract Handles This:**

  • Tesseract compares hard and soft limits
  • Uses the more conservative (tighter) limits for planning and checking
  • Protects your robot by restricting motion to safer ranges

    Important:** If soft limits are set to 0.0, that joint becomes immobilized. Verify your URDF is correct; Tesseract will not validate or warn you about this.

Collision Geometry Best Practices

Tesseract uses the collision meshes from your URDF for all collision detection and distance calculations.

Why Collision Meshes Matter:**

  • Determines what the planner "sees" as obstacles
  • Too detailed = slow collision checks, slow planning
  • Too coarse = poor safety, missed collisions, bad trajectories

    Optimization Guidelines:**

  • Use simple primitives (boxes, cylinders, spheres) when possible
    • Much faster than mesh collision checking
    • Easier to tune and debug
  • If using meshes:
    • Target total triangle count: A few thousand for the whole robot (not per link)
    • Decimate/simplify meshes aggressively
    • Keep visual meshes separate (can be detailed, slow isn't a problem for display)
  • Use convex decomposition or hulls for complex shapes

    Example Structure:**

    <link name="arm_segment">
    <visual>
    <!-- Detailed mesh for display, doesn't affect planning -->
    <geometry>
    <mesh filename="package://robot/meshes/arm_segment_detailed.dae"/>
    </geometry>
    </visual>
    <collision>
    <!-- Simplified mesh for planning, minimal triangles -->
    <geometry>
    <mesh filename="package://robot/meshes/arm_segment_simple.stl"/>
    </geometry>
    </collision>
    </link>

Validating Your URDF

Always test your URDF before deploying it to production.**

ROS provides the check_urdf tool to validate syntax:

check_urdf my_robot.urdf

This catches XML errors and basic structural issues.

But also** — load it into Tesseract and visualize the collision geometry (see Tesseract URDF Loading Example). Visual inspection catches issues that automated checks miss:

  • Collision meshes too coarse or too fine
  • Misaligned frames or reference links
  • Joint limits that are too restrictive
  • Self-collision pairs that shouldn't collide

Tesseract URDF Extensions

Tesseract extends the standard URDF with additional geometry types and options optimized for planning and collision checking.

All extensions are optional — use them only when you need specialized geometry types beyond standard primitives and meshes.

tesseract:capsule

A capsule is a cylinder with hemispherical endcaps. Efficient for collision checking and commonly used for robot arms.

When to use:**

  • Cylindrical links (arm segments, fingers)
  • Need collision accuracy without mesh complexity
  • Want faster collision checks than detailed meshes

    URDF Usage:**

<link name="segment">
<collision>
<geometry>
<tesseract:capsule length="0.5" radius="0.05"/>
</geometry>
</collision>
</link>

Attributes:**

  • length – Distance between hemisphere centers (in meters)
  • radius – Radius of the cylinder and hemispheres (in meters)

tesseract:cone

A cone for conical collision geometry.

When to use:**

  • Conical tools, nozzles, or end-effectors
  • Geometry approximation of tapered components

    URDF Usage:**

<geometry>
<tesseract:cone length="0.2" radius="0.1"/>
</geometry>

tesseract:octomap

An octree map for volumetric environment representation, populated from point cloud data or octree files.

When to use:**

  • Sensor data (LIDAR, RGB-D cameras) for dynamic obstacle representation
  • Environment mapping from point clouds
  • Object recognition and shape approximation

    Supported Sources:**

  • Octree files (*.octree)
  • Point cloud files (*.pcd)

    Attributes:**

  • shape_type="box" – Axis-aligned boxes for voxels
  • shape_type="sphere_inside" – Spheres inside voxels
  • shape_type="sphere_outside" – Spheres outside voxels

    Example with Point Cloud:**

<geometry>
<tesseract:octomap shape_type="box">
<tesseract:point_cloud filename="scan.pcd" resolution="0.05"/>
</tesseract:octomap>
</geometry>

tesseract:sdf_mesh

A signed distance field (SDF) mesh for precise collision geometry with precomputed distance information.

When to use:**

  • Complex, smooth geometry where collision precision matters
  • Precomputed SDFs for faster collision checks
  • Applications requiring exact distance queries

    URDF Usage:**

<geometry>
<tesseract:sdf_mesh filename="complex_part.sdf"/>
</geometry>

tesseract:make_convex

Automatically convert collision meshes into convex hulls for more efficient collision checking and motion planning.

Why Use Convex Hulls:**

  • Speed: Simple polygon collision checks (GJK algorithm) vs. complex mesh checks
  • Robustness: Deterministic, no numerical issues
  • Trade-off: Convex hulls overapproximate the original shape

    When to use:**

  • Meshes are too slow for real-time planning
  • Non-convex shapes can be acceptably approximated as convex
  • Need predictable, fast collision response

    Important:** Always visualize the generated convex hull to ensure it's conservative enough for your application.

    Global Setting (applies to all meshes):**

<robot ... tesseract:make_convex="true">
...
</robot>

Mesh-Level Override (can enable/disable per-mesh):**

<link name="gripper_finger">
<collision>
<geometry>
<mesh filename="finger.stl" tesseract:make_convex="true"/>
</geometry>
</collision>
</link>

The mesh-level setting overrides the global setting.

Checklist Before Using in Tesseract

  • [ ] URDF passes check_urdf without errors
  • [ ] Joint names contain no special characters (-, [, ], (, ))
  • [ ] Soft limits are sensible (not 0.0), or removed
  • [ ] Collision meshes are simplified (few thousand triangles total, not per mesh)
  • [ ] Load URDF into Tesseract and visualize collision geometry
  • [ ] Joint limits allow full expected range of motion
  • [ ] All file paths use package:// URIs (not absolute paths)
  • [ ] Verified that coordinate frames make sense (visual inspection)

Next Steps

After you have a working URDF:

  1. Load it into Tesseract — See Tesseract URDF Loading Example for code to parse and load your URDF
  2. Add semantic information — Create an SRDF to define planning groups and collision rules (see Semantic Robot Description Format (SRDF) and Tesseract SRDF Parsing Example)
  3. Visualize geometry — Use Tesseract's visualization tools to inspect collision meshes and frame alignments
  4. Plan and execute — Use the loaded URDF in motion planning (see tesseract_examples)

Additional Resources

URDF Reference and Tutorials**