Introduction to Universal Robot Description Format (URDF)
Last updated: October 28, 2024
It is XML format which can be used to define robots strucure. Both physical and mechanical properties and interactions of each physical component with each other and constrains.
This means you can define define everything in your physical robot in a form of a code file. This is very powerful and useful and simple.
NOTE: This lesson contains a lot of different stuff. You dont need to remember it all, this is intro to what is possible with URDF. We will be introducing each of these components when we need them and why we need them. It is important to mention them here so that you are aware that they exist.
Why use URDF?
Visualisations: You can visualize it in rviz and gazebo for better debugging and understanding.
Simulation: You can load your robot into a Simulation (will be covered later) and experiment with various hardware and try out different algorithms.
Modularity and Resuability: Create URDFs in modules and reuse them in various ways and places.
Kinematics and Dynamics: You can define kinematics and dinemics of your robots in the URDF then use them with various ROS packages and achieve complex things like manupulationa arms with MoveIt. Handle complex motion and force calculations automatically.
Standardisation: It is a widely accepted ROS standard and you can benefit from it and use many packages with it directly.
URDF Components
Robots can be described using URDF as a tree of links and joints. The node of the tree is a link and the edges are joints. Like in other tree like strcutures, each node can have a parent and or a child.
URDF Components Overview
- Robot
- Root element of the URDF
- Attributes: name
- Link
- Represents a rigid body
- Sub-elements:
- visual (appearance)
- collision (for collision checking)
- inertial (mass properties)
- Joint
- Connects two links
- Types: revolute, continuous, prismatic, fixed, floating, planar
- Sub-elements:
- origin
- parent
- child
- axis
- calibration
- dynamics
- limit
- mimic
- safety_controller
- Transmission
- Describes the relationship between an actuator and a joint
- Sub-elements:
- type
- joint
- actuator
- Material
- Defines colors and textures for visual elements
- Can be referenced by visual elements
- Gazebo
- Used for simulation-specific properties in Gazebo
- Can be applied to links, joints, or the entire robot
- Sensor
- Describes sensors attached to the robot (often used with Gazebo plugin)
- Plugin
- Extends functionality, often used with Gazebo
- XML Namespaces
- Used for extending URDF with custom elements (e.g., for specific simulators or tools)
1. URDF general structure
<?xml version="1.0"?>
<robot name="robot_name">
<!-- Materials (for visual elements) -->
<material name="material_name">
<color rgba="r g b a"/>
</material>
<!-- Links -->
<link name="base_link">
<visual>
<!-- Visual properties -->
</visual>
<collision>
<!-- Collision properties -->
</collision>
<inertial>
<!-- Inertial properties -->
</inertial>
</link>
<link name="another_link">
<!-- ... -->
</link>
<!-- Joints -->
<joint name="joint_name" type="joint_type">
<parent link="parent_link_name"/>
<child link="child_link_name"/>
<origin xyz="x y z" rpy="r p y"/>
<axis xyz="x y z"/>
<limit lower="lower_limit" upper="upper_limit" effort="max_effort" velocity="max_velocity"/>
<!-- Other joint properties (calibration, dynamics, mimic, safety_controller) -->
</joint>
<!-- Transmissions -->
<transmission name="transmission_name">
<type>transmission_interface/SimpleTransmission</type>
<joint name="joint_name">
<!-- Joint specifics -->
</joint>
<actuator name="actuator_name">
<!-- Actuator specifics -->
</actuator>
</transmission>
<!-- Sensors, plugins, etc. can be added here -->
</robot>
2. Link
Links represent the physical component of a robot (like body, wheel, camera)
<link name="link_name">
<inertial>
<origin xyz="0 0 0" rpy="0 0 0"/>
<mass value="1.0"/>
<inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/>
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<box size="1 1 1"/>
</geometry>
<material name="material_name">
<color rgba="1 1 1 1"/>
</material>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<box size="1 1 1"/>
</geometry>
</collision>
</link>
Here's a brief explanation of each element in the URDF link:
name
: Specifies the unique name of the link.inertial
: Defines the inertial properties of the link.origin
: Sets the position and orientation of the inertial reference frame.mass
: Specifies the mass of the link.inertia
: Defines the 3x3 rotational inertia matrix.
visual
: Describes the visual properties of the link.origin
: Sets the position and orientation of the visual element.geometry
: Specifies the shape of the visual element (e.g., box, cylinder, sphere, mesh).material
: Defines the material properties (color, texture) of the visual element.
collision
: Describes the collision properties of the link.origin
: Sets the position and orientation of the collision element.geometry
: Specifies the shape used for collision checking.
The visual
and collision
elements can have different geometries. Often, a simplified geometry is used for collision to improve performance in physics simulations.
3. Joint
joint represents how it interacts wrt to other components.
<joint name="joint_name" type="joint_type">
<origin xyz="0 0 0" rpy="0 0 0"/>
<parent link="parent_link_name"/>
<child link="child_link_name"/>
<axis xyz="1 0 0"/>
<calibration rising="0.0" falling="0.0"/>
<dynamics damping="0.0" friction="0.0"/>
<limit lower="0.0" upper="0.0" effort="0.0" velocity="0.0"/>
<mimic joint="mimic_joint_name" multiplier="1.0" offset="0.0"/>
<safety_controller soft_lower_limit="0.0" soft_upper_limit="0.0" k_position="0.0" k_velocity="0.0"/>
</joint>
Here's a brief explanation of each element in the URDF joint:
name
: Specifies the unique name of the joint.type
: Defines the joint type (e.g., revolute, prismatic, fixed).origin
: Sets the transform from the parent link to the joint frame.xyz
: Specifies the x, y, z offset.rpy
: Specifies the roll, pitch, yaw rotation.
parent
: Specifies the name of the parent link.child
: Specifies the name of the child link.axis
: Defines the joint axis in the joint frame.calibration
: Used for calibrating the joint's position.dynamics
: Specifies physical properties of the joint.limit
: Sets the limits on the joint's motion.mimic
: Makes this joint mimic another joint's motion.safety_controller
: Defines a safety controller for the joint.
URDF Joint Types
- Revolute - A hinge joint that rotates along the axis with limited range.
- Example: Robot arm joint
- URDF:
<joint type="revolute" ... >
- Continuous - A hinge joint that rotates around the axis without limits.
- Example: Wheel rotation
- URDF:
<joint type="continuous" ... >
- Prismatic - A sliding joint that moves along the axis with limited range.
- Example: 3D printer axis movement
- URDF:
<joint type="prismatic" ... >
- Fixed - Not a movable joint; all degrees of freedom are locked.
- Example: Robot arm base
- URDF:
<joint type="fixed" ... >
- Floating - Allows motion in all 6 degrees of freedom.
- Example: Free-floating object in space
- URDF:
<joint type="floating" ... >
- Planar - Allows motion in a plane perpendicular to the axis.
- Example: Puck on an air hockey table
- URDF:
<joint type="planar" ... >
Note: Fixed joints don't require <axis>
, <calibration>
, <dynamics>
, <limits>
, or <safety_controller>
elements.
4. Transmission
<transmission name="transmission_name">
<type>transmission_interface/SimpleTransmission</type>
<joint name="joint_name">
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
</joint>
<actuator name="actuator_name">
<mechanicalReduction>1</mechanicalReduction>
<hardwareInterface>hardware_interface/PositionActuatorInterface</hardwareInterface>
</actuator>
</transmission>
Here's a brief explanation of each element in the URDF transmission:
name
: Specifies the unique name of the transmission.type
: Defines the type of transmission. In this example, it's set to "transmission_interface/SimpleTransmission", which is a common type for a simple 1:1 transmission.joint
: Specifies the joint that this transmission is connected to.name
: The name of the joint (should match a joint defined elsewhere in the URDF).hardwareInterface
: Specifies the hardware interface type for the joint. This example uses a position interface, but other types like velocity or effort interfaces are also possible.
actuator
: Describes the actuator that drives this transmission.name
: A unique name for the actuator.mechanicalReduction
: The gear reduction ratio between the actuator and the joint. A value of 1 means no reduction.hardwareInterface
: Specifies the hardware interface type for the actuator. This should be compatible with the joint's interface.
The transmission element is used to describe how joint movement in the URDF model is transmitted to the actuators in the real robot (or vice versa). It's particularly useful for robots where there isn't a simple 1:1 relationship between actuators and joints, such as when there are gears or other mechanical transmissions involved.
Conclusion
This lesson intrducted URDF an dvarious components. In the next lesson we will use some of these compoenents and build a robot and visualize it.