Edit on GitHub

Specification

Hardware Specification

Items Unit OpenMANIPULATOR-X
Actuator   DYNAMIXEL XM430-W350-T
Input Voltage V 12
DOF - 5 (4 DOF + 1 DOF Gripper)
Payload g 500
Repeatability mm < 0.2
Speed(Joint) RPM 46
Weight kg (lb) 0.70 (1.54)
Reach mm (in) 380 (14.9)
Gripper Stroke mm (in) 20~75 (0.79~2.95)
Communication - TTL Level Multidrop BUS
Software - ROS, DYNAMIXEL SDK, Arduino, Processing
Main Controller - PC, OpenCR

Dimension

Inertia

Total Mass : 711.37 gram

Joint 1

Joint 2

Joint 3

Joint 4

Understanding URDF

Understanding URDF (Universal Robot Description Format) with OpenManipulator-X

What is URDF?

URDF (Universal Robot Description Format) is an XML-based format used to describe a robot’s physical structure, kinematics, dynamics, and visualization properties. It is widely used in ROS (Robot Operating System) to define robot models for simulation, motion planning, and visualization.

URDF defines a robot using the following key elements:

For a more detailed understanding of URDF, we recommend referring to the URDF Tutorial on the ROS 2 Wiki. The best way to understand and learn URDF is to build a simple robot yourself.

Visualizing the OpenManipulator-X URDF Structure

Understanding the hierarchical structure of the OpenManipulator-X is crucial before diving into the URDF breakdown. The following URDF graph visually represents the parent-child relationships between links and joints.

Key Features of the URDF Graph

The following image shows the OpenManipulator-X URDF model as visualized in RViz. It includes the joint positions and link dimensions, providing a clear representation of the robot’s structure.

URDF with Xacro

The provided URDF uses Xacro (XML Macros) to simplify and modularize the robot description. Xacro allows reusing components and making the URDF more maintainable.
The following explanation is based on the Xacro file:

open_manipulator/open_manipulator_x_description/urdf/open_manipulator_x.urdf.xacro

At the beginning of the file, a macro is defined:

<xacro:macro name="open_manipulator_x" params="prefix=''">

This allows the reuse of the same structure with different prefixes, making it flexible for multi-robot environments.

A link represents a rigid body in the robot. Each link has visual, collision, and inertial properties.

Example of link1 in OpenManipulator-X:

<link name="${prefix}link1">
  <visual>
    <origin xyz="0 0 0" rpy="0 0 0"/>
    <geometry>
      <mesh filename="${meshes_file_direction}/link1.stl" scale="0.001 0.001 0.001"/>
    </geometry>
    <material name="grey"/>
  </visual>
  
  <collision>
    <origin xyz="0 0 0" rpy="0 0 0"/>
    <geometry>
      <mesh filename="${meshes_file_direction}/link1.stl" scale="0.001 0.001 0.001"/>
    </geometry>
  </collision>

  <inertial>
    <origin xyz="3.0876154e-04 0.0000000e+00 -1.2176461e-04" />
    <mass value="7.9119962e-02" />
    <inertia ixx="1.2505234e-05" ixy="0.0" ixz="-1.7855208e-07"
             iyy="2.1898364e-05" iyz="0.0"
             izz="1.9267361e-05" />
  </inertial>
</link>

Explanation

Defining a Joint

A joint connects two links and defines how they move relative to each other.

Example of joint1 in OpenManipulator-X:

<joint name="${prefix}joint1" type="revolute">
  <parent link="${prefix}link1"/>
  <child link="${prefix}link2"/>
  <origin xyz="0.012 0.0 0.017" rpy="0 0 0"/>
  <axis xyz="0 0 1"/>
  <limit velocity="4.8" effort="1" lower="${-pi}" upper="${pi}" />
  <dynamics damping="0.1"/>
</joint>

Explanation

Adding a Prismatic Joint

Prismatic joints allow linear motion rather than rotation.

Example from OpenManipulator-X gripper:

<joint name="${prefix}gripper_left_joint" type="prismatic">
  <parent link="${prefix}link5"/>
  <child link="${prefix}gripper_left_link"/>
  <origin xyz="0.0817 0.021 0.0" rpy="0 0 0"/>
  <axis xyz="0 1 0"/>
  <limit velocity="4.8" effort="1" lower="-0.010" upper="0.019" />
  <dynamics damping="0.1"/>
</joint>

Explanation

Using a Fixed Joint

Fixed joints are used when a link does not move relative to another.

Example:

<joint name="${prefix}end_effector_joint" type="fixed">
  <parent link="${prefix}link5"/>
  <child link="${prefix}end_effector_link"/>
  <origin xyz="0.126 0.0 0.0" rpy="0 0 0"/>
</joint>

Explanation