Skip to content

Design a robot arm in ROS

francescodelduchetto edited this page Feb 13, 2025 · 4 revisions

The standard way to define a robot within the ROS ecosystem is with URDF.

URDF main components

ℹ️ The Unified Robotics Description Format (URDF) is an XML specification to model multi-body systems, such as robotic manipulators and mobile robots. URDF is "unified" because allows to specify multiple properties:

  • kinematic chain structure
  • visual appearance (shape and colour)
  • collision zones
  • physical properties (dynamics, inertia, contact coefficients, etc)
  • other elements, such as controllers and plug-ins

ℹ️ The main elements (or tags) of interest are <robot>, <link> and <joint>, which are nested in a hierarchical structure. <link> and <joint> are children of the <robot> element, conversely <robot> is a parent of the other two elements.

<robot>
	<link>
		...
	</link>
	<link>
		...
	</link>
	<joint>
		...
	</joint>
</robot>

ℹ️ Each <link> represent one part of the robot structure, and defines its properties (colour, shape, mass, etc).

ℹ️ Each <joint> defines how links are connected to one another.

Define a simple robot with URDF

▶️ 🖥️ 1. In your editor, open the file simple_robot.urdf.xacro inside RBT1001/src/week3/description/urdf/. This is an empty file for now.

▶️ 🖥️ 2. Add two links and a joint pasting from the definition below:

<robot name="simple_robot" xmlns:xacro="http://www.ros.org/wiki/xacro">
  <link name="world"/>
  <link name="base_link"> <!-- Each link should have a name to distinguish and refer to them -->
    <visual>
      <geometry>
        <box size="0.2 0.2 0.2"/> <!-- This specifies the shape of the link -->
      </geometry>
      <material name="base_material"> <!-- You need to give a name to the material -->
        <color rgba="0.5 0.5 0.5 1"/> <!-- This specifies the color of the link -->
      </material>
    </visual>
  </link>

  <link name="link_1">
    <visual>
      <geometry>
        <cylinder length="0.6" radius="0.1"/> 
      </geometry>
      <material name="link1_material">
        <color rgba="0 1 0 1"/>
      </material>
    </visual>
  </link>

  <joint name="fixed" type="fixed"> <!-- it's a fixed frame because we do not want the base to move -->
    <parent link="world"/>    <!-- parent, because in the chain sequence comes before the child -->
    <child link="base_link"/> <!-- This is the child, connected by the joint to the parent -->
  </joint>

  <joint name="base_to_link_1" type="continuous"> <!-- Continuous, meaning it can rotate without upper/lower limits -->
    <parent link="base_link"/>
    <child link="link_1"/>
  </joint>
</robot>

▶️ 🖥️ 3. We can visualise the model by launching ros2 launch week3 view_robot.launch.py description_file:=simple_robot.urdf.xacro. We can also move the angle of the joint we defined by moving the slider in the joint_state_publisher_gui window.

image

▶️ 🔍 Let's analyse the URDF definition to understand better why our robot is in the way shown.

  1. We have a world link which is just a reference for where our robot should be anchored.
    <link name="world"/>
  1. We defined the base of the robot as base_link to be a gray box-shaped component:
    <link name="base_link">        <!-- Each link should have a name to distinguish and refer to them -->
        <visual>
            <geometry>
                <box size="0.2 0.2 0.2"/>  <!-- This specifies the shape of the link -->
            </geometry>
            <material name="base_material">                <!-- You need to give a name to the material -->
                <color rgba="0.5 0.5 0.5 1"/>              <!-- This specifies the color of the link -->
            </material>
        </visual>
    </link>
  1. We defined a part of the robot arm as link_1 to be a green cylinder:
    <link name="link_1">
        <visual>
            <geometry>
                <cylinder length="0.6" radius="0.1"/>
            </geometry>
            <material name="link1_material">
                <color rgba="0 1 0 1"/>
            </material>
        </visual>
    </link>
  1. ❗ Now, we have defined our joints. The first is fixing the robot base to the world (simply saying that our robot base does not move):
    <joint name="fixed" type="fixed">  <!-- it's a fixed frame because we do not want the base to move -->
        <parent link="world"/>  <!-- parent, because in the chain sequence comes before the child -->
        <child link="base_link"/>  <!-- This is the child, connected by the joint to the parent -->
    </joint>
  1. ❗ And, we define how the arm moves with respect to the base:
    <joint name="base_to_link_1" type="continuous">        <!-- Continuous, meaning it can rotate without upper/lower limits -->
        <parent link="base_link"/>
        <child link="link_1"/>
    </joint>

continuous here essentially means that it is a rotational joint.

▶️ 🧑‍💻 Which one is the axis of rotation for the joint?

Modify the URDF

▶️ Let's modify the URDF to have the following 1 DOF arm and set the rotation around $y_1$:

image

▶️ 🖥️ 1. First, we need to "correct" the visual geometry position as, by default most geometries have their origin in the centre of the shape (see the documentation for link above). We can modify the visual origin with:

  <link name="base_link">
    <visual>
      <origin xyz="0 0 0.1" rpy="0 0 0"/><!-- !! ADD THIS to offset the position of the box's centre-->
      <geometry>
        <box size="0.2 0.2 0.2"/> 
      </geometry>
     ...
  </link>
  <link name="link_1">
    <visual>
      <origin xyz="0 0 0.3" rpy="0 0 0"/> <!-- !! ADD THIS to offset the position of the cylinder's centre-->
      <geometry>
        <cylinder length="0.6" radius="0.1"/> 
      </geometry>
      ...
  </link>

▶️ 🧑‍💻 2. Save the file, close the view_robot node from the terminal (CTRL+C), and relaunch it to see what is the result!

▶️ 🖥️ 3. Now we need to act on the joint. This allows to specify the pose of the frame q1 and the axis of rotation for revolute joints.

  <joint name="base_to_link_1" type="continuous">
    <origin xyz="0 0 0.2" rpy="${pi/2} 0 0"/> <!-- !! ADD THIS to rotate and offset the link (not its geometry) -->
    <axis xyz="0 1 0"/> <!-- !! ADD THIS for setting the axis of rotation. By default rotation is on the x axis-->
    <parent link="base_link"/>
    <child link="link_1"/>
  </joint>

▶️ 🧑‍💻 4. Save the file, close the view_robot node from the terminal (CTRL+C), and relaunch it to see what is the result!

image

2024/2025

Syllabus

2023/2024

Syllabus

Clone this wiki locally