Creating a URDF robot model from scratch for Cool1000 robotic manipulator


In this post i explain the process of creation of a URDF robot model for Cool1000 arm. At the end of this post you should be able to understand the concept of links, joints, types of joints, physical and collision properties to be added for simulation in Gazebo. A detailed tutorials for creation of URDF files can be found in the urdf_tutorials.

Joints are the moving positions in a robotic arm that can move in a rotational or translational motion. Hence, the joints could be specified in a URDF as one among the types fixed, revolute, prismatic or continuous. A revolute joint (usually for motors) has rotational motion with the joint limits specified, a prismatic joint has translational motion with the joint limits specified in meters, a continuous joint has rotational motion with no joint limits being specified.

Links refer to the rigid body that connects two joints.

Collision properties refer to the collision meshes to be added into the model so as to detect a collision between parts of robot in simulation environment.
Physical properties refer to the mass, inertia, friction, stiffness, dampening co-efficient for the links, static friction and dampening values for the joints.

You can find the URDF file that we will be using in this tutorial available here.
The entire cool1000_description package can be found in here.

Create a ROS workspace, download the cool1000_description package into the workspace and build the workspace using $ catkin_make command.

Create a new cool1000_test.urdf file in urdf folder of the cool1000_description package and feed the below lines into the file. In the lines below you can see that there is a fixed joint specified between two links. Every link is specified with the visual, collision and inertial parameters. Here, we have made use of the same mesh file for both the visual and collision parameters. The origin and rpy specified is with respect to the base_link's co-ordinate frame.

<?xml version="1.0"?>
<robot name="cool1000">

    <!-- World-Link -->
    <link name="world"/>
    <joint name="fixed" type="fixed">
        <parent link="world"/>
        <child link="base_link"/>
    </joint>

    <!--Base-Link -->  
    <link name="base_link">
        <visual>
            <origin xyz="-1.62 0.865 0" rpy="0 0 -1.57" />
            <geometry>
                <mesh filename="package://cool1000_description/meshes/cool1000_base.dae" scale=".001 .001 .001"/> 
            </geometry>
            <material name="grey"/>
        </visual>
        <collision>
            <origin xyz="-1.62 0.865 0" rpy="0 0 -1.57" />
            <geometry>
                <mesh filename="package://cool1000_description/meshes/cool1000_base.dae" scale=".001 .001 .001"/>
            </geometry>
        </collision>
        <inertial>
            <mass value="1.0"/>
            <inertia ixx="0.001" ixy="0.0" ixz="0.0" iyy="0.001" iyz="0.0" izz="0.001"/>
        </inertial>
    </link>
</robot>

If urdf_tutorial package is not there then you can install it using the command
$ sudo apt-get install ros-<dist>-urdf-tutorial

You can load the urdf file in RViz using command
$ cd /path/to/your/catkin_ws/src/cool1000_description/urdf
$ roslaunch urdf_tutorial display.launch model:=cool1000_test.urdf

The above command will launch RViz and loads the robot model into the scene.
You should be able to see the robot loaded as shown below. You can add the display type TF in RViz and then you should be able to see the frame for the base link. At present only the base_link is the robot model. In this model both the world and base_link co-ordinate frame are specified at the same location. It is important to add the world frame as a fixed frame else you might see that in Gazebo simulation environment the manipulator is sliding over the ground.


Now let's add the next joint and link1 into the file.
Add the following lines at place where the base_link ends.

Here we have specified that the joint1 is of revolute type, with its rotational limits specified in radians units. The <axis xyz="0 0 1" /> specifies the co-ordinate z-axis along which the joint rotation will take place. Here, the origin and rpy in the joint1 is specified wrt the base_link frame. Hence, when you load the new robot model you should be able to see the co-ordinate frame for the link1 at 0.06m above the base_link frame.

The origin, rpy specified in the Link1 are wrt the new co-ordinate frame for the Link1.

    <!-- joint 1 -->
       <joint name="joint1" type="revolute">
        <axis xyz="0 0 1" />
        <limit effort="3.0" velocity="3.0" lower="-2.617" upper="2.617"/>
        <origin xyz="0 0 0.06" rpy="0 0 0" />
           <parent link="base_link" />
          <child link="link1" />
            <dynamics damping="1000.0" friction="1.0"/>
    </joint>

<!-- Link1 -->
    <link name="link1">
        <visual>
            <origin xyz="-0.805 0.322 -0.058" rpy="0 0 -1.57" />
            <geometry>
                <mesh filename="package://cool1000_description/meshes/link1.dae"/> 
            </geometry>   
            <material name="grey"/>
        </visual>
        <collision>
            <origin xyz="-0.805 0.322 -0.058" rpy="0 0 -1.57" />
            <geometry>
                       <mesh filename="package://cool1000_description/meshes/link1.dae"/> 
            </geometry>
             </collision>
             <inertial>
                <mass value="0.5"/>
                <inertia ixx="0.001" ixy="0.0" ixz="0.0" iyy="0.001" iyz="0.0" izz="0.001"/>
              </inertial>
    </link>

When you load the robot model back into RViz using following command you should be able to see the image as shown below.
$ roslaunch urdf_tutorial display.launch model:=cool1000_test.urdf

You can see the new co-ordinate frame for the link1 that is placed 0.06m above the base_link co-ordinate frame. Since, the rpy in joint1 are all kept zero, there is no rotation changes from the base_link to the link_1.


Now you might be wondering how to specify the origin and rpy in the joints or links. A good way to start with is specifying 0.0 for both origin and rpy in the joint section. Now modify the origin and rpy values in the links section so as to match with the real robot. You could specify these values based on the dh-parameters for that particular link. Another approach is intuition based trail and error approach for matching the simulation robot model with the real robot.

As an example for the above specified approach for identifying the origin and rpy, lets try with the following lines for joint2 and link2 for the model. Add these lines after the end of Link1 in the urdf file

    <!-- joint 2 -->
    <joint name="joint2" type="revolute">
        <axis xyz="0 1 0" />
        <limit effort="3.0" velocity="3.0" lower="-1.91" upper="1.91"/>
        <origin xyz="0 0 0.0" rpy="0 0 0" />
           <parent link="link1" />
           <child link="link2" />
         <dynamics damping="100.0" friction="1.0"/>
    </joint>

    <!-- Link2 -->
      <link name="link2">
           <visual>
                <origin xyz="-0.805 0.315 -0.061" rpy="0 0 -1.57" />
                <geometry>
                     <mesh filename="package://cool1000_description/meshes/link2.dae"/> 
                </geometry>
                <material name="grey"/>
           </visual>
           <collision>
                <origin xyz="-0.805 0.315 -0.061" rpy="0 0 -1.57" />
                <geometry>
                     <mesh filename="package://cool1000_description/meshes/link2.dae"/> 
                </geometry>
           </collision>
           <inertial>
                <mass value="0.5"/>
                <inertia ixx="0.001" ixy="0.0" ixz="0.0" iyy="0.001" iyz="0.0" izz="0.001"/>
           </inertial>
    </link>

After loading the robot model onto the RViz you should be able to see the following image in the scene. As you can see that the Link2 has been placed at the required place similar to the real robot, but the link2 and link1 co-ordinate are merged together. Hence, we might not get a good reference point for the link2. For this we can shift the link2 co-ordinate frame upwards such that the new co-ordinate frame aligns with the link2 and becomes a part of the link2.


Lets's raise the frame for Link2 by 0.069m using the lines below and see what happens. Replace the lines for the joint2 and link2 with these lines in the cool1000_test.urdf file.

    <!-- joint 2 -->
    <joint name="joint2" type="revolute">
        <axis xyz="0 1 0" />
        <limit effort="3.0" velocity="3.0" lower="-1.91" upper="1.91"/>
        <origin xyz="0 0 0.069" rpy="0 0 0" />
           <parent link="link1" />
           <child link="link2" />
         <dynamics damping="100.0" friction="1.0"/>
    </joint>

    <!-- Link2 -->
      <link name="link2">
           <visual>
                <origin xyz="-0.805 0.315 -0.13" rpy="0 0 -1.57" />
                <geometry>
                     <mesh filename="package://cool1000_description/meshes/link2.dae"/> 
                </geometry>
                <material name="grey"/>
           </visual>
           <collision>
                <origin xyz="-0.805 0.315 -0.13" rpy="0 0 -1.57" />
                <geometry>
                     <mesh filename="package://cool1000_description/meshes/link2.dae"/> 
                </geometry>
           </collision>
           <inertial>
                <mass value="0.5"/>
                <inertia ixx="0.001" ixy="0.0" ixz="0.0" iyy="0.001" iyz="0.0" izz="0.001"/>
           </inertial>
    </link>

Now load the modified model for the Joint2 and Link2 onto the RViz.
You should be able to see the below image loaded onto the scene. Here, you can see that the link2 co-ordinate frame is shited above due to increse in the z-component in the origin parameter for the Joint2 section. But, still the link2 is at same place as we have reduced the z-component in origin parameter for the Link2 section.


You can specify the mass of the link in kgs in the mass parameter of the inertial section for the corresponding link.

Going ahead if you load the entire robot model into the RViz you should be able to see the following image in the scene along with a new pop-up window for the joint_state_publisher . The co-ordinate frames have been disabled so as to get a clear view of the robot. At the top of the robot you can see the fingers of the gripper for the manipulator. The left and right fingers of the gripper have been made up of prismatic type for the joint8 (gripper_left finger) and joint9 (gripper_right finger). You can move all the joints in the RViz using the scroll bar for each joints in the joint state publisher window.
$ roslaunch urdf_tutorial display.launch model:=cool1000.urdf gui:=true


Comments

Popular posts from this blog

Dex-Net installation procedure on system installed with Anaconda and ROS