[ROS Projects] – My Robotic Manipulator – #Part 3 – URDF Inertia

My-Robotic-Manipulator---Part-3---URDF-Inertia

Written by Marco Arruda

25/05/2018

In this video we are going to insert inertia property to each link of our robotic manipulator. At the end of the video we’ll be able to simulate this robot using Gazebo, due to having complete physic properties defined to the robot.

Step1. Create Project

Let’s start with creating a new project in ROS development studio.

Notice: If you haven’t had an account yet. You can register one here for free.

Open a shell and clone the package from bitbucket repo(https://goo.gl/1Kbt5v). You’ll have to register a bitbucket account to do that.

Since the repo is a simulation, we’ll clone it into the ~/simulation_ws/src folder.

Then the source tree should look similar like this.

Then we type the following command to compile the package.

cd ~/simulation_ws
catkin_make
source devel/setup.bash

Step2. Add physical properties in the URDF

Open the links_joints.xacro file under the urdf folder of the package and add the following tag in the link tag under the m_link_cylinder tag.

      <inertial>
        <mass value="${mass}" />
        <origin rpy="${origin_rpy}" xyz="${origin_xyz}" />
        <inertia ixx="${ixx}" ixy="${ixy}" ixz="${ixz}" iyy="${iyy}" iyz="${iyz}" izz="${izz}" />
      </inertial>

By adding this part, the link can have a more realistic physical behavior in the simulation, you also have to add the parameters for the inertia(ixx ixy ixz iyy iyz izz) in the pramas part.

  <xacro:macro name="m_link_cylinder" params="name origin_xyz origin_rpy radius length mass ixx ixy ixz iyy iyz izz">

We also need a collision tag to define the collision behavior when the robot collides with something in the simulation. We define the collision shape same as the visual shape here.

      <collision>
        <origin rpy="${origin_rpy}" xyz="${origin_xyz}" />
        <geometry>
          <cylinder radius="${radius}" length="${length}" />
        </geometry>
      </collision>

We also add these properties in the m_link_box.

Step3. Set parameter values

Now we have to define all the values for the parameters in the mrm.xacro file under the urdf folder. You can copy and replace the following code into it.

<?xml version="1.0" ?>

<robot name="mrm" xmlns:xacro="http://www.ros.org/wiki/xacro">
  
  <!-- BGN - Include -->
  <xacro:include filename="$(find mrm_description)/urdf/robot_parameters.xacro" />
  <xacro:include filename="$(find mrm_description)/urdf/links_joints.xacro" />
  <!-- END - Include -->
  
  <!-- BGN - Robot description -->
  <m_link_box name="${link_00_name}"
              origin_rpy="0 0 0" origin_xyz="0 0 0"
              mass="1024"
              ixx="170.667" ixy="0" ixz="0"
              iyy="170.667" iyz="0"
              izz="170.667"
              size="1 1 1" />
              
  <m_joint name="${link_00_name}__${link_01_name}" type="revolute"
           axis_xyz="0 0 1"
           origin_rpy="0 0 0" origin_xyz="0 0 0.5"
           parent="base_link" child="link_01" />
           
  <m_link_cylinder name="${link_01_name}"
              origin_rpy="0 0 0" origin_xyz="0 0 0.2"
              mass="157.633"
              ixx="13.235" ixy="0" ixz="0"
              iyy="13.235" iyz="0"
              izz="9.655"
              length="0.4" radius="0.35" />
              
  <m_joint name="${link_01_name}__${link_02_name}" type="revolute"
           axis_xyz="0 1 0"
           origin_rpy="0 0 0" origin_xyz="0 0 0.4"
           parent="link_01" child="link_02" />
           
  <m_link_cylinder name="${link_02_name}"
              origin_rpy="0 0 0" origin_xyz="0 0 0.4"
              mass="57.906"
              ixx="12.679" ixy="0" ixz="0"
              iyy="12.679" iyz="0"
              izz="0.651"
              radius="0.15" length="0.8" />
              
  <m_joint name="${link_02_name}__${link_03_name}" type="revolute"
           axis_xyz="0 1 0"
           origin_rpy="0 0 0" origin_xyz="0 0 0.8"
           parent="link_02" child="link_03" />
           
  <m_link_cylinder name="${link_03_name}"
              origin_rpy="0 0 0" origin_xyz="0 0 0.4"
              mass="57.906"
              ixx="12.679" ixy="0" ixz="0"
              iyy="12.679" iyz="0"
              izz="0.651"
              radius="0.15" length="0.8" />
              
  <m_joint name="${link_03_name}__${link_04_name}" type="revolute"
           axis_xyz="0 1 0"
           origin_rpy="0 0 0" origin_xyz="0 0 0.8"
           parent="link_03" child="link_04" />
           
  <m_link_cylinder name="${link_04_name}"
              origin_rpy="0 0 0" origin_xyz="0 0 0.4"
              mass="57.906"
              ixx="12.679" ixy="0" ixz="0"
              iyy="12.679" iyz="0"
              izz="0.651"
              radius="0.15" length="0.8" />
              
  <m_joint name="${link_04_name}__${link_05_name}" type="revolute"
           axis_xyz="0 0 1"
           origin_rpy="0 0 0" origin_xyz="0 0 0.8"
           parent="link_04" child="link_05" />
           
  <m_link_cylinder name="${link_05_name}"
              origin_rpy="0 0 0" origin_xyz="0 0 0.125"
              mass="18.056"
              ixx="0.479" ixy="0" ixz="0"
              iyy="0.479" iyz="0"
              izz="0.204"
              radius="0.15" length="0.25" />
  <!-- END - Robot description -->
  
</robot>

Step4. Launch the Simulation

Now, let’s open a graphical tool in the tools tab and launch the rviz with the following command.

$ roslaunch mrm_description rviz.launch

Then we start an empty simulation from the simulation tab. Then we create a spawn.launch file under the launch folder with following code.

<?xml version="1.0" encoding="UTF-8"?>
<launch>
    <param name="robot_description" command="$(find xacro)/xacro --inorder '$(find mrm_description)/urdf/mrm.xacro'" />
    
    <arg name="x" default="0"/>
    <arg name="y" default="0"/>
    <arg name="z" default="0.5"/>
    
    <node name="mybot_spawn" pkg="gazebo_ros" type="spawn_model" output="screen"
          args="-urdf -param robot_description -model mrm -x $(arg x) -y $(arg y) -z $(arg z)" />
          
</launch>

To spawn our robot in the simulation world, type the following command

$ roslaunch mrm_description spawn.launch

Now you’ll see the robot is falling down like this(at least in some physically correct way) since we haven’t applied any control yet.

Takeaway Today:

You can define the inertia properties with URDF to have a more realistic simulation behavior.

 

# Links or resources mentioned in the video: 

  • ROS Development Studio: https://goo.gl/zQQohY
  • Material for the video : https://bitbucket.org/theconstructcore/my-robotic-manipulator/src
  • Robot Ignite Academy : https://goo.gl/Qq4b5E
Masterclass 2023 batch2 blog banner

Check Out These Related Posts

0 Comments

Submit a Comment

Your email address will not be published.

This site uses Akismet to reduce spam. Learn how your comment data is processed.

Pin It on Pinterest

Share This