URDF Processor API Reference
This page documents ManipulaPy.urdf_processor, the module for URDF (Unified Robot Description Format) processing and conversion to ManipulaPy objects.
Tip
For conceptual explanations, see URDF Processor User Guide.
URDFToSerialManipulator Class
Usage Examples
Basic URDF Loading:
from ManipulaPy.urdf_processor import URDFToSerialManipulator
# Load robot from URDF
processor = URDFToSerialManipulator("robot.urdf")
# Access created objects
robot = processor.serial_manipulator
dynamics = processor.dynamics
print(f"Robot has {len(robot.joint_limits)} joints")
Using Built-in Robot Models:
from ManipulaPy.ManipulaPy_data.xarm import urdf_file as xarm_urdf
# Load xArm robot
processor = URDFToSerialManipulator(xarm_urdf)
# Perform forward kinematics
joint_angles = [0.1, 0.2, 0.3, 0, 0, 0]
T = processor.serial_manipulator.forward_kinematics(joint_angles)
Joint Limits Configuration:
# Use PyBullet joint limits (default)
processor_pb = URDFToSerialManipulator("robot.urdf", use_pybullet_limits=True)
# Use default limits (-π, π)
processor_default = URDFToSerialManipulator("robot.urdf", use_pybullet_limits=False)
# Compare joint limits
print("PyBullet limits:", processor_pb.serial_manipulator.joint_limits)
print("Default limits:", processor_default.serial_manipulator.joint_limits)
Robot Visualization:
# Static robot visualization
processor.visualize_robot()
# Trajectory animation with numpy array
import numpy as np
# Create trajectory: 100 timesteps, smooth motion
n_steps = 100
n_joints = len(processor.serial_manipulator.joint_limits)
trajectory = np.zeros((n_steps, n_joints))
for i in range(n_joints):
trajectory[:, i] = np.linspace(0, np.pi/3, n_steps)
processor.visualize_trajectory(
cfg_trajectory=trajectory,
loop_time=5.0,
use_collision=True
)
Trajectory Animation with Dictionary:
# Get joint names
joint_info = processor.print_joint_info()
joint_names = joint_info["joint_names"]
# Create trajectory dictionary
trajectory_dict = {}
for joint_name in joint_names:
if "joint" in joint_name.lower(): # Filter actuated joints
trajectory_dict[joint_name] = [0, np.pi/4, np.pi/2, np.pi/4, 0]
processor.visualize_trajectory(trajectory_dict, loop_time=4.0)
Extracting Robot Parameters:
# Access raw URDF data
robot_data = processor.robot_data
print(f"Home configuration:\n{robot_data['M']}")
print(f"Number of DOF: {robot_data['actuated_joints_num']}")
print(f"Screw axes shape: {robot_data['Slist'].shape}")
# Access inertia matrices
for i, G in enumerate(robot_data['Glist']):
print(f"Link {i} inertia:\n{G}")
Integration with Kinematics and Dynamics:
# Complete workflow example
processor = URDFToSerialManipulator("robot.urdf")
# Kinematics
joint_angles = [0.5, -0.3, 0.8, 0.1, -0.2, 0.4]
T = processor.serial_manipulator.forward_kinematics(joint_angles)
J = processor.serial_manipulator.jacobian(joint_angles)
# Dynamics
joint_velocities = [0.1, 0.2, 0.0, 0.0, 0.0, 0.0]
joint_accelerations = [1.0, 0.5, 0.0, 0.0, 0.0, 0.0]
torques = processor.dynamics.inverse_dynamics(
joint_angles, joint_velocities, joint_accelerations,
g=[0, 0, -9.81], Ftip=[0, 0, 0, 0, 0, 0]
)
print(f"Required torques: {torques}")
Custom URDF Processing:
# Access raw urchin URDF object
urdf_obj = processor.robot
# Inspect URDF structure
print(f"Robot name: {urdf_obj.name}")
print(f"Links: {[link.name for link in urdf_obj.links]}")
print(f"Joints: {[joint.name for joint in urdf_obj.joints]}")
# Get link-wise forward kinematics
link_transforms = urdf_obj.link_fk()
for link_name, transform in link_transforms.items():
print(f"{link_name}: {transform[:3, 3]}") # Position only
Error Handling:
try:
processor = URDFToSerialManipulator("nonexistent.urdf")
except FileNotFoundError:
print("URDF file not found")
except Exception as e:
print(f"URDF processing error: {e}")
# Validate extracted parameters
if processor.robot_data["actuated_joints_num"] == 0:
print("Warning: No actuated joints found")
if len(processor.dynamics.Glist) != processor.robot_data["actuated_joints_num"]:
print("Warning: Inertia matrix count mismatch")
Key Features
Automatic parameter extraction from URDF files using urchin library
PyBullet integration for accurate joint limit retrieval
Dual object creation (SerialManipulator + ManipulatorDynamics)
Flexible visualization with static and animated display options
Robust trajectory handling supporting both array and dictionary formats
Complete inertia processing from URDF link properties
Screw theory conversion from joint parameters to screw axes
Error handling for malformed or missing URDF files
Dependencies
urchin – URDF loading and visualization
PyBullet – Joint limit extraction and simulation
NumPy – Numerical computations and array operations
ManipulaPy.kinematics – SerialManipulator class
ManipulaPy.dynamics – ManipulatorDynamics class
ManipulaPy.utils – Utility functions for transformations
See Also
Kinematics API Reference – SerialManipulator class created by this processor
Dynamics API Reference – ManipulatorDynamics class created by this processor
Simulation API Reference – Simulation module using URDF models
URDF Processor User Guide – Conceptual overview and URDF format details