Gazebo | Ignition | Community
Ask Your Question
0

URDF models inertia value seems so big !

asked 2018-01-25 15:45:07 -0500

Nurul Karim gravatar image

updated 2018-01-27 12:35:12 -0500

Dear altruists, I have a robot model and its main body is mentioned here. Body size is a hollow cover of (0.90.90.5) cubic meters. weight nearly 14 kilo, is inertia got from meshlab here is reasonable? and approximately how much effort is required for lifting five times this wight (1459.8 N)?

<link name="body">        
    <inertial>
        <origin xyz="0 0 0" rpy="0 0 0"/>
        <mass value="14.1"/>  
 <inertia ixx="-2685.745" ixy="47.8420869" ixz="-13.070708" iyy="4702.4455" iyz="864.4434" izz="1845.634138"/>
    </inertial>
    <visual>
        <material name="Yellow"/>
        <origin xyz="0 0 0" rpy="0 0 0"/>
        <geometry>
            <mesh filename="package://tt_tutorial/meshes/body.stl" scale="0.001 0.001 0.001"/>
        </geometry>
    </visual>
    <collision>
        <material name="Red"/>
        <origin xyz="0.0 0.0 0.0" rpy="0 0 0"/>
        <geometry>               
            <mesh filename="package://tt_tutorial/meshes/body.stl" scale="0.001 0.001 0.001"/>
        </geometry>
    </collision>
     <turnGravityOff>true</turnGravityOff>
  <gazebo reference="base_link">  
  </gazebo>
</link>
edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
0

answered 2018-01-30 00:49:30 -0500

Francisco gravatar image

Yes, those inertia values are huge. To give you a sense of magnitude, these are the inertia values of a cylinder with a radius=0.45 meters and height=0.5 meters and a mass=14.1 Kilograms.

<inertial>
  <origin xyz="0 0 0.25" rpy="0 0 0" />
  <mass value="14.1" />
  <inertia  ixx="1.0075625" ixy="0" ixz="0"
            iyy="1.0075625" iyz="0"
            izz="1.427625" />
</inertial>

From the visual and collision fields, it's clear that the units of your mesh (body.stl) are in millimeters, so, you may want to scale it to meters before computing the inertia with meshlab.

Another option is to approximate the body to a simpler geometry (I normally use a cylinder) for which computing the inertia is straight forward: https://en.wikipedia.org/wiki/List_of...

edit flag offensive delete link more

Comments

@Francisco Thanks for your reply, I later rescaled mesh and computed inertia, and then divided it with volume computed by Meshlab as it was suggested in forums. Is it correct way?

Nurul Karim gravatar imageNurul Karim ( 2018-01-31 16:18:05 -0500 )edit

Question Tools

1 follower

Stats

Asked: 2018-01-25 15:45:07 -0500

Seen: 1,205 times

Last updated: Jan 30 '18