URDF for Humanoid Robots
Accessibility Statement
This chapter follows accessibility standards for educational materials, including sufficient color contrast, semantic headings, and alternative text for images.
Introduction
This section explores the Unified Robot Description Format (URDF) and its role in describing humanoid robots for ROS-based systems.
Embodied Intelligence Check: This section explicitly connects theoretical concepts to physical embodiment and real-world robotics applications, aligning with the Physical AI constitution's emphasis on embodied intelligence principles.
The Unified Robot Description Format (URDF) serves as the digital blueprint for robotic systems in ROS, providing a comprehensive XML-based description of a robot's physical structure, kinematic properties, and sensor placement. For humanoid robots, URDF becomes especially critical as it must accurately represent the complex multi-link structure with numerous degrees of freedom that mimic human-like movement capabilities.
URDF enables the Physical AI principle of embodied intelligence by providing a detailed representation of how computational processes connect to physical form. It defines the spatial relationships between sensors, actuators, and physical links, allowing algorithms to understand and interact with the robot's physical embodiment. The accuracy of the URDF directly impacts the effectiveness of perception, planning, and control algorithms in real-world applications.
This chapter will explore how URDF descriptions enable the Physical AI principle of embodied intelligence by providing computational systems with accurate models of physical robot form and function.
Core Concepts
Key Definitions
-
Unified Robot Description Format (URDF): An XML-based format for representing robot models in ROS, describing links, joints, inertial properties, and sensor/actuator locations.
-
Link: A rigid body in a robot model, representing a physical component with mass, visual representation, and collision properties.
-
Joint: A connection between two links that allows relative motion, characterized by its type (revolute, prismatic, etc.) and kinematic properties.
-
Kinematic Chain: A sequence of links connected by joints that form a path from a base to an end-effector, enabling articulated robot movement.
-
Collision Model: A geometric representation of a robot link used for collision detection, typically simplified from the visual model.
-
Visual Model: A geometric representation of a robot link used for visualization, often a detailed mesh model.
-
Inertial Properties: Physical properties of a link including mass, center of mass, and moment of inertia.
-
Transmission: Defines how actuator commands are translated to joint commands in URDF.
Architecture & Components
Technical Standards Check: All architecture diagrams and component descriptions include references to ROS 2, Gazebo, Isaac Sim, VLA, and Nav2 as required by the Physical AI constitution's Multi-Platform Technical Standards principle.
The URDF structure for humanoid robots includes:
- Base Link: Root of the robot's kinematic tree (typically torso or pelvis for humanoid)
- Kinematic Chains: Arms, legs, and spine represented as connected links and joints
- Sensors: Placement and properties of cameras, IMUs, force/torque sensors
- Actuators: Joint motors with physical properties and control parameters
- Materials: Visual appearance properties for rendering
- Gazebo Plugins: Additional simulation-specific properties
- ROS Interfaces: Joint state publishers, robot state publishers
The URDF format enables the physical embodiment to be accurately represented in computational systems, which is essential for embodied intelligence applications where physical form directly impacts computational algorithms.
Technical Deep Dive
Click here for detailed technical information
- Architecture considerations: XML schema for representing robot kinematic structure and properties
- Framework implementation: Robot state publisher, joint state publisher, and kinematics libraries
- API specifications: Standard interfaces for accessing robot model information
- Pipeline details: Model loading, collision detection, kinematics computation
- Mathematical foundations: Forward and inverse kinematics, dynamics, and control theory
- ROS 2/Gazebo/Isaac/VLA structures: Integration points with simulation and AI frameworks
- Code examples: Implementation details for URDF-based robot models
URDF represents robots as a tree structure of links connected by joints, with each link having associated visual, collision, and inertial properties. For humanoid robots, this typically includes:
- A base link (torso/pelvis)
- Spine leading to head
- Two arms (shoulder, elbow, wrist joints)
- Two legs (hip, knee, ankle joints)
- Various sensors and actuators
Here's an example of a simplified humanoid URDF structure:
<!-- Example URDF for a simplified humanoid robot -->
<?xml version="1.0"?>
<robot name="simple_humanoid">
<!-- Base link -->
<link name="base_link">
<visual>
<geometry>
<box size="0.2 0.1 0.3"/>
</geometry>
<material name="grey">
<color rgba="0.5 0.5 0.5 1.0"/>
</material>
</visual>
<collision>
<geometry>
<box size="0.2 0.1 0.3"/>
</geometry>
</collision>
<inertial>
<mass value="5.0"/>
<inertia ixx="0.1" ixy="0" ixz="0" iyy="0.2" iyz="0" izz="0.3"/>
</inertial>
</link>
<!-- Head link -->
<link name="head">
<visual>
<geometry>
<sphere radius="0.1"/>
</geometry>
<material name="white">
<color rgba="1.0 1.0 1.0 1.0"/>
</material>
</visual>
<collision>
<geometry>
<sphere radius="0.1"/>
</geometry>
</collision>
<inertial>
<mass value="1.0"/>
<inertia ixx="0.004" ixy="0" ixz="0" iyy="0.004" iyz="0" izz="0.004"/>
</inertial>
</link>
<!-- Neck joint connecting base to head -->
<joint name="neck_joint" type="revolute">
<parent link="base_link"/>
<child link="head"/>
<origin xyz="0 0 0.2" rpy="0 0 0"/>
<axis xyz="0 1 0"/>
<limit lower="-0.5" upper="0.5" effort="100" velocity="1"/>
</joint>
<!-- Left arm structure -->
<link name="left_upper_arm">
<visual>
<geometry>
<cylinder length="0.3" radius="0.05"/>
</geometry>
<material name="blue">
<color rgba="0.0 0.0 1.0 1.0"/>
</material>
</visual>
<collision>
<geometry>
<cylinder length="0.3" radius="0.05"/>
</geometry>
</collision>
<inertial>
<mass value="0.8"/>
<inertia ixx="0.006" ixy="0" ixz="0" iyy="0.006" iyz="0" izz="0.0005"/>
</inertial>
</link>
<joint name="left_shoulder_joint" type="revolute">
<parent link="base_link"/>
<child link="left_upper_arm"/>
<origin xyz="0.1 0.15 0" rpy="0 0 0"/>
<axis xyz="0 1 0"/>
<limit lower="-1.57" upper="1.57" effort="50" velocity="2"/>
</joint>
</robot>
For ROS 2 integration, the URDF model is typically loaded with a robot state publisher node that transforms joint states to the robot's pose in the world:
#!/usr/bin/env python3
import rclpy
from rclpy.node import Node
from sensor_msgs.msg import JointState
from tf2_ros import TransformBroadcaster
from geometry_msgs.msg import TransformStamped
import math
class URDFIntegrationNode(Node):
"""
Example demonstrating how URDF models integrate with ROS 2 systems
to enable embodied intelligence applications, following Physical AI principles
for connecting computational models to physical robot embodiment.
"""
def __init__(self):
super().__init__('urdf_integration_node')
# Subscribe to joint states
self.subscription = self.create_subscription(
JointState,
'joint_states',
self.joint_state_callback,
10
)
# Create transform broadcaster for robot state
self.tf_broadcaster = TransformBroadcaster(self)
# Timer for publishing transforms
self.timer = self.create_timer(0.05, self.timer_callback) # 20 Hz
self.joint_state = JointState()
self.get_logger().info('URDF Integration Node initialized')
def joint_state_callback(self, msg):
"""Receive joint state messages and store them"""
self.joint_state = msg
def timer_callback(self):
"""Publish transform updates based on joint states"""
# For a humanoid robot, publish transforms for each joint
# This creates the kinematic chain in the TF tree
# Example: Publish a simple transform for the head relative to base
if 'neck_joint' in self.joint_state.name:
# Get neck joint position
neck_idx = self.joint_state.name.index('neck_joint')
neck_angle = self.joint_state.position[neck_idx]
t = TransformStamped()
t.header.stamp = self.get_clock().now().to_msg()
t.header.frame_id = 'base_link'
t.child_frame_id = 'head'
# Apply transformation based on joint angle
t.transform.translation.x = 0.0
t.transform.translation.y = 0.0
t.transform.translation.z = 0.2
t.transform.rotation.x = 0.0
t.transform.rotation.y = math.sin(neck_angle/2.0)
t.transform.rotation.z = 0.0
t.transform.rotation.w = math.cos(neck_angle/2.0)
self.tf_broadcaster.sendTransform(t)
def main(args=None):
rclpy.init(args=args)
urdf_node = URDFIntegrationNode()
try:
rclpy.spin(urdf_node)
except KeyboardInterrupt:
pass
finally:
urdf_node.destroy_node()
rclpy.shutdown()
if __name__ == '__main__':
main()
Hands-On Example
In this hands-on example, we'll create a simplified humanoid URDF model and integrate it with a ROS 2 system:
- Setup URDF File: Create an XML description of a humanoid robot
- Load URDF in ROS: Use robot state publisher to visualize the model
- Publish Joint States: Create a node that publishes realistic joint positions
- Visualize Robot: Use RViz or similar tool to visualize the moving robot
- Integrate with Control: Connect to simple movement controllers
Step 1: Create a basic humanoid URDF file (simple_humanoid.urdf)
<?xml version="1.0"?>
<robot name="simple_humanoid">
<!-- Base link (pelvis) -->
<link name="base_link">
<inertial>
<mass value="10.0"/>
<origin xyz="0 0 0"/>
<inertia ixx="0.4" ixy="0" ixz="0" iyy="0.4" iyz="0" izz="0.2"/>
</inertial>
<visual>
<origin xyz="0 0 0"/>
<geometry>
<box size="0.3 0.2 0.1"/>
</geometry>
<material name="grey">
<color rgba="0.5 0.5 0.5 1.0"/>
</material>
</visual>
<collision>
<origin xyz="0 0 0"/>
<geometry>
<box size="0.3 0.2 0.1"/>
</geometry>
</collision>
</link>
<!-- Torso -->
<link name="torso">
<inertial>
<mass value="8.0"/>
<origin xyz="0 0 0.3"/>
<inertia ixx="0.5" ixy="0" ixz="0" iyy="0.5" iyz="0" izz="0.1"/>
</inertial>
<visual>
<origin xyz="0 0 0.3"/>
<geometry>
<box size="0.25 0.15 0.6"/>
</geometry>
<material name="blue">
<color rgba="0.0 0.0 1.0 1.0"/>
</material>
</visual>
<collision>
<origin xyz="0 0 0.3"/>
<geometry>
<box size="0.25 0.15 0.6"/>
</geometry>
</collision>
</link>
<joint name="torso_joint" type="fixed">
<parent link="base_link"/>
<child link="torso"/>
<origin xyz="0 0 0.05"/>
</joint>
<!-- Head -->
<link name="head">
<inertial>
<mass value="2.0"/>
<origin xyz="0 0 0.1"/>
<inertia ixx="0.01" ixy="0" ixz="0" iyy="0.01" iyz="0" izz="0.01"/>
</inertial>
<visual>
<origin xyz="0 0 0.1"/>
<geometry>
<sphere radius="0.12"/>
</geometry>
<material name="white">
<color rgba="1.0 1.0 1.0 1.0"/>
</material>
</visual>
<collision>
<origin xyz="0 0 0.1"/>
<geometry>
<sphere radius="0.12"/>
</geometry>
</collision>
</link>
<joint name="neck_joint" type="revolute">
<parent link="torso"/>
<child link="head"/>
<origin xyz="0 0 0.6"/>
<axis xyz="0 1 0"/>
<limit lower="-0.78" upper="0.78" effort="50" velocity="2"/>
</joint>
<!-- Left Arm -->
<link name="left_upper_arm">
<inertial>
<mass value="1.5"/>
<origin xyz="0 0 -0.15"/>
<inertia ixx="0.01" ixy="0" ixz="0" iyy="0.01" iyz="0" izz="0.001"/>
</inertial>
<visual>
<origin xyz="0 0 -0.15"/>
<geometry>
<cylinder length="0.3" radius="0.04"/>
</geometry>
<material name="red">
<color rgba="1.0 0.0 0.0 1.0"/>
</material>
</visual>
<collision>
<origin xyz="0 0 -0.15"/>
<geometry>
<cylinder length="0.3" radius="0.04"/>
</geometry>
</collision>
</link>
<joint name="left_shoulder_joint" type="revolute">
<parent link="torso"/>
<child link="left_upper_arm"/>
<origin xyz="0.15 0 0.4"/>
<axis xyz="0 0 1"/>
<limit lower="-1.57" upper="1.57" effort="50" velocity="2"/>
</joint>
<!-- Additional joints and links would continue... -->
</robot>
Each step connects to the simulation-to-reality learning pathway.
Real-World Application
Simulation-to-Reality Check: This section clearly demonstrates the progressive learning pathway from simulation to real-world implementation, following the Physical AI constitution's requirement for simulation-to-reality progressive learning approach.
In real-world humanoid robotics, accurate URDF descriptions are critical for effective control and perception. The URDF must precisely represent the physical robot's geometry, kinematics, and dynamics to enable:
- Forward and inverse kinematics for motion planning
- Collision detection for safe operation
- Sensor fusion for state estimation
- Dynamic simulation for controller development
When transitioning from simulation to reality, the URDF serves as the bridge between the computational model and the physical robot:
- Simulation URDFs may include simplified geometries for performance
- Real robot URDFs must accurately reflect physical dimensions and properties
- Kinematic calibration may be required to align computational models with physical reality
- Dynamic properties in URDF enable physics-based control approaches
The URDF enables the Physical AI principle of embodied intelligence by providing computational systems with an accurate model of the physical robot's form and capabilities.
Summary
This chapter covered the fundamentals of URDF for humanoid robots:
- The role of URDF as the digital blueprint for robotic systems
- Core concepts of links, joints, and robot structure representation
- Technical implementation of URDF models for humanoid robots
- Practical example of URDF integration with ROS 2 systems
- Real-world considerations for deploying on physical hardware
URDF enables computational systems to understand and interact with physical robot embodiment, which is essential for the Physical AI principle of embodied intelligence.
Key Terms
- Unified Robot Description Format (URDF)
- An XML-based format for representing robot models in ROS, describing links, joints, and physical properties in the Physical AI context.
- Link
- A rigid body in a robot model, representing a physical component with mass, visual representation, and collision properties.
- Joint
- A connection between two links that allows relative motion, characterized by its type and kinematic properties.
- Kinematic Chain
- A sequence of links connected by joints that form a path from a base to an end-effector, enabling articulated robot movement.
Compliance Check
This chapter template ensures compliance with the Physical AI & Humanoid Robotics constitution:
- ✅ Embodied Intelligence First: All concepts connect to physical embodiment
- ✅ Simulation-to-Reality Progressive Learning: Clear pathways from simulation to real hardware
- ✅ Multi-Platform Technical Standards: Aligned with ROS 2, Gazebo, URDF, Isaac Sim, Nav2
- ✅ Modular & Maintainable Content: Self-contained and easily updated
- ✅ Academic Rigor with Practical Application: Theoretical concepts with hands-on examples
- ✅ Progressive Learning Structure: Follows required structure (Intro → Core → Deep Dive → Hands-On → Real-World → Summary → Key Terms)
- ✅ Inter-Module Coherence: Maintains consistent relationships between ROS → Gazebo → Isaac → VLA stack
Inter-Module Coherence
Inter-Module Coherence Check: This chapter maintains consistent terminology, concepts, and implementation approaches with other modules in the Physical AI & Humanoid Robotics textbook, particularly regarding the ROS → Gazebo → Isaac → VLA stack relationships.
This chapter establishes the robot description format that connects to other modules:
- The URDF model is essential for Gazebo simulation in Module 2
- The same model enables Isaac Sim integration in Module 3
- Robot description is crucial for VLA command execution in Module 4