ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question
1

Calculating inertial matrix for Gazebo

asked 2016-06-18 04:24:53 -0500

ipa-hsd gravatar image

updated 2016-06-22 05:06:35 -0500

I am having issues following the tutorial to calculate the inertial matrix for my gripper. This is the behaviour I see. I am able to successfully create a config package with PR2 gripper, so I am pretty sure it is because of the inertial matrix.

In Meshlab, following are the values I get at no-scale:

Mesh Bounding Box Size 0.164416 0.063248 0.077500
Mesh Bounding Box Diag 0.192456 
Mesh Volume is 0.000214
Mesh Surface is 0.089074
Thin shell barycenter -0.040913 -0.000254 0.039031
Center of Mass is -0.041006 -0.000043 0.037458
Inertia Tensor is :
| 0.000000 -0.000000 0.000000 |
| -0.000000 0.000001 0.000000 |
| 0.000000 0.000000 0.000000 |
Principal axes are :
| 0.938629 0.011849 0.344725 |
| 0.004914 0.998849 -0.047710 |
| -0.344893 0.046476 0.937491 |
axis momenta are :
| 0.000000 0.000001 0.000001 |

For a scale of 100, following are the values I get :

Mesh Bounding Box Size 16.441637 6.324847 7.750000
Mesh Bounding Box Diag 19.245613 
Mesh Volume is 214.333633
Mesh Surface is 890.744385
Thin shell barycenter -4.091284 -0.025389 3.903062
Center of Mass is -4.100575 -0.004325 3.745764
Inertia Tensor is :
| 1597.194946 -17.950985 1307.758423 |
| -17.950985 5213.373047 9.511752 |
| 1307.758423 9.511752 4675.780273 |
Principal axes are :
| 0.938629 0.011848 0.344725 |
| 0.004914 0.998849 -0.047710 |
| -0.344893 0.046475 0.937491 |
axis momenta are :
| 1116.573364 5213.602539 5156.172363 |

How do I use these values? I didn't quite understand the scaling part of the tutorial. Also, ideally, shouldn't the simulation work when I consider the gripper to be almost weightless?

<inertial>
  <mass value="0.001" />
  <inertia ixx="0.001" ixy="0"  ixz="0"
           iyy="0.001" iyz="0"
           izz="0.001" />
</inertial>

A unity matrix or the above value as well gives the same behaviour as in the video.

Edit 1:

I have tested the macro mentioned by @Stefan Kohlbrecher. Also, I divided the inertia matrix given by Meshlab by volume which gives me :

<inertial>
    <mass value="1.0" />
    <origin xyz="-0.041006 -0.000043 0.037458" />
    <inertia ixx="0.000746353" ixy="0"  ixz="0"
               iyy="0.002436156" iyz="0"
               izz="0.002184945" />
</inertial>

Still I observe the same behaviour. Does Gazebo need the inertia matrix wrt origin or wrt center of mass?

Edit 2:

@MarioSelvaggio 's solution seems to work perfectly fine. The arm is stable and I am also able to plan and execute trajectories. But the solution only works when in my final urdf file I translate the gripper :

<joint name="gripper_joint" type="fixed">
    <parent link="ur5_arm_ee_link" />
    <child link = "gripper" />
    <origin xyz="0.04100575 0.00004325 -0.03745764" rpy="0.0 4.71 3.14" />
</joint>

Observe that the sign of origin xyz has been inverted. Here's how it looks: http://i.imgur.com/7hE8OdD.png For rest of the cases, the simulation remains unstable ... (more)

edit retag flag offensive close merge delete

3 Answers

Sort by ยป oldest newest most voted
3

answered 2016-06-21 09:04:17 -0500

mrslvgg gravatar image

When your model is too small, inertia matrix can usually assume very small values. When you scale your model by s (scale factor) in Meshlab in order to increase the precision, you're actually scaling the dimensions of your object. This means that the center of mass is changed according to s, volume, and thus mass, is changed according to s^3, moment of inertia, being mass*length^2, is changed according to s^5.

According to the values you posted (s=100) after scaling back I expect to see something like:

<inertial>
    <mass value="0.000214" />
    <origin xyz="-0.04100575 -0.00004325 0.03745764" />
    <inertia ixx="1.597e-7" ixy="-1.795e-9"  ixz="1.307e-7"
             iyy="5.213e-7" iyz="9.5117e-10"
             izz="4.675e-7"/>
</inertial>

Note that the mass value is the same as the computed volume, this means that a default value of density rho=1 has been used. The density of the material of your gripper expressed in kg/m^3 has to be multiplied by the volume in order to get the mass. Example density is rho = 7850 Kg/m^3 (steel).

You can have a useful feedback in Gazebo regarding your computed values by visualizing masses and inertia. Go to the Gazebo menu and select View->Inertia. If you still have troubles post here.

edit flag offensive delete link more

Comments

Your solution works! But there seems to be a problem with pose of the gripper wrt the end-effector. Please check Edit 2.

ipa-hsd gravatar image ipa-hsd  ( 2016-06-21 10:27:59 -0500 )edit

It is not possible to judge what is happening from just these information. It could be self-collision or other strange things. My suggestion is try to visualize collision meshes, centre of masses and inertia from the menu View in order to get more information. Otherwise you can post your URDF here.

mrslvgg gravatar image mrslvgg  ( 2016-06-21 11:08:53 -0500 )edit
2

answered 2016-06-18 17:52:21 -0500

Making values very small (i.e. making bodies weightless) can actually hurt, as the numerical stability of solvers can be worse when there are large differences between inertial properties of different bodies. I often base inertia tensors on the formulas for the inertia tensors of simple geometric shapes (see list of moments of inertia. These can be put into xacro macros and then it is fairly easy to use and modify them.

See https://github.com/tu-darmstadt-ros-p... and https://github.com/tu-darmstadt-ros-p...

edit flag offensive delete link more

Comments

But if I have to use the values generated by Meshlab, how do I do that? And if I HAVE to simplify, I probably have to use cuboid?

ipa-hsd gravatar image ipa-hsd  ( 2016-06-18 18:10:43 -0500 )edit

Does Gazebo need the inertia matrix wrt origin or wrt center of mass?

ipa-hsd gravatar image ipa-hsd  ( 2016-06-21 06:46:11 -0500 )edit
1

answered 2022-06-28 05:22:00 -0500

vonunwerth gravatar image

I implemented a python script reading an 3D file like stl or dae and outputting the full URDF XML inertial tag based on the gazebosim tutorial. and pymeshlab.

At first the script calculates the center of mass of the object. After that it scales the mesh by a factor of 100 to increase the numerical accuracy. You could manually change that, if you need to scale it more up. Now the convex hull of your object will be calculated. For the hull the geometric properties will be calculated, scaled back down and outputted as URDF XML inertial tag like that (the precision could also be changed in the script)

<inertial>
  <origin xyz="0.00000002 -0.00000001 0.00000000"/>
  <mass value="5.00000000"/>
  <inertia ixx="7.90866056" ixy="0.00000006" ixz="0.00000000" iyy="7.90866060" iyz="0.00000000" izz="2.48398783"/>
</inertial>

Check it out here: https://github.com/vonunwerth/MeshLab...

edit flag offensive delete link more

Comments

Thanks for the script! Do you mind adding a LICENSE file to the repo?

ipa-hsd gravatar image ipa-hsd  ( 2022-06-28 07:50:20 -0500 )edit

I updated the repo regarding that.

vonunwerth gravatar image vonunwerth  ( 2022-06-28 08:46:52 -0500 )edit

Question Tools

2 followers

Stats

Asked: 2016-06-18 04:24:53 -0500

Seen: 9,042 times

Last updated: Jun 28 '22