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

Spawning a cube in gazebo

asked 2016-06-06 08:03:43 -0500

ipa-hsd gravatar image

updated 2016-06-06 08:04:58 -0500

I tried to spawn a cube in gazebo with the following URDF.

<robot name="simple_box">
  <link name="my_box">
    <inertial>
      <origin xyz="2 0 0" />
      <mass value="1.0" />
      <inertia  ixx="1.0" ixy="0.0"  ixz="0.0"  iyy="100.0"  iyz="0.0"  izz="1.0" />
    </inertial>
    <visual>
      <origin xyz="0.7 0 0.56"/>
      <geometry>
        <box size="0.02 0.02 0.02" />
      </geometry>
    </visual>
    <collision>
      <origin xyz="0.7 0 0.56"/>
      <geometry>
        <box size="0.02 0.02 0.02" />
      </geometry>
    </collision>
  </link>
  <gazebo reference="my_box">
    <material>Gazebo/Blue</material>
  </gazebo>
</robot>

with the following entry in my launch file :

<!-- spawn a cube for pick and place -->
<node name="spawn_cube" pkg="gazebo_ros" type="spawn_model" args="-file $(find ur5_pnp)/urdf/object.urdf -urdf -model cube" />

But I see some strange behavior of the cube as it never stops moving. https://youtu.be/HPc2xJXtPhc

I am guessing it has something to do with inertia / mass?

edit retag flag offensive close merge delete

Comments

Should your mass origin and visual/collision origin not be the same? I'm not an expert with URDF, I always solve this by try and error. But this movement looks like your mass center is wrong.

JohnDoe2991 gravatar image JohnDoe2991  ( 2016-06-06 08:45:16 -0500 )edit

Perfect! Works fine

ipa-hsd gravatar image ipa-hsd  ( 2016-06-06 08:49:41 -0500 )edit

@JohnDoe2991 not always. But for the cube, you're right.

longforgotten gravatar image longforgotten  ( 2016-06-06 08:53:49 -0500 )edit

@intelharsh, your inertia tensor is miles away from a real tensor, given that your cube mass is 1 kg.

You can use this xacro to compute a viable inertia tensor to the cube.

longforgotten gravatar image longforgotten  ( 2016-06-06 08:59:35 -0500 )edit

@emersonfs can I find a documentation somewhere regarding this?

ipa-hsd gravatar image ipa-hsd  ( 2016-06-07 03:27:17 -0500 )edit

@emersonfs I used the macro you mentioned and it seems to work fine, though I'll need to read about it to understand what's happening.

ipa-hsd gravatar image ipa-hsd  ( 2016-06-07 08:51:03 -0500 )edit

This xacro file implements some known moment of inertia tensors for certain shapes. To understand why inertia tensors are so importants to physics, you can read the chapter 6 "Manipulator dynamics", section 3 "Mass distribution", from Craig's book, "Introduction to Robotics".

longforgotten gravatar image longforgotten  ( 2016-06-07 18:17:32 -0500 )edit

@emersonfs thanks! Will go through it

ipa-hsd gravatar image ipa-hsd  ( 2016-06-08 04:15:57 -0500 )edit

1 Answer

Sort by ยป oldest newest most voted
1

answered 2016-06-06 09:41:28 -0500

Laurens Verhulst gravatar image

updated 2016-06-06 09:42:00 -0500

I can confirm from a lot of tests that the ratio between mass and inertia is crucial in the Gazebo physics. I had a problem with my robot collapsing, it also ended up being caused by inertia issues. The answer here covers a lot of solutions.

edit flag offensive delete link more

Question Tools

Stats

Asked: 2016-06-06 08:03:43 -0500

Seen: 2,319 times

Last updated: Jun 06 '16