Gazebo | Ignition | Community
Ask Your Question
0

Stack of two models unstable bouncing

asked 2018-04-17 12:22:15 -0500

raequin gravatar image

updated 2018-04-18 08:40:21 -0500

Greetings. When I stack two one-link models (each is just a hollow cylinder, like a roll of paper towels) they keep colliding and bouncing until the top one finally gets thrown off. The STL is available here. The sdf and world files are pasted below. The animated gif shows the behavior. At the end of the gif, Gazebo show the collision and inertial elements. The inertial element is a bit off-center; I don't see why that would cause this but thought I should mention it. Can you help me get a stable stack of these models?

This is in Gazebo 9. In model.sdf I changed the restitution_coefficient tag from 0 to 0.5 in a failed attempt to resolve the issue (even though 0 should be the less bouncy value).

image description

Model sdf:

<sdf version='1.6'>
  <model name='Neleski_Cone_full'>
<link name='Neleski_Cone_full'>
  <pose>0 0 0 0 0 0</pose>
  <inertial>
        <pose>0.15 -0.15 0.14605 0 0 0</pose>
        <mass>130.96</mass>
        <inertia>
          <ixx>1.61005</ixx>
          <ixy>5.1652e-33</ixy>
          <ixz>5.85205e-33</ixz>
          <iyy>1.61005</iyy>
          <iyz>5.04266e-17</iyz>
          <izz>1.35779</izz>
        </inertia>
  </inertial>
  <collision name='Neleski_Cone_full_collision'>
    <surface>
      <bounce>
    <restitution_coefficient>0.5</restitution_coefficient>
      </bounce>
    </surface>
        <pose>0 0 0 1.5708 0 0</pose>
        <geometry>
          <mesh>
    <scale>.001 .001 .001</scale>
    <uri>model://Full_Cone/meshes/Neleski_Cone_full.STL</uri>
          </mesh>
        </geometry>
  </collision>
  <visual name='Neleski_Cone_full_visual'>
        <pose>0 0 0 1.5708 0 0</pose>
        <geometry>
          <mesh>
    <scale>.001 .001 .001</scale>
    <uri>model://Full_Cone/meshes/Neleski_Cone_full.STL</uri>
          </mesh>
        </geometry>
  </visual>
</link>
  </model>
</sdf>

World:

<sdf version='1.5'>
  <world name='default'>
<!-- A global light source -->
<include>
  <uri>model://sun</uri>
</include>
<!-- A ground plane -->
<include>
  <uri>model://ground_plane</uri>
</include>

<model name='Neleski_Cone_full_1'>
  <include>
    <static>0</static>
    <uri>model://Full_Cone</uri>
    <pose>-1 0 0.1 0 0 0</pose>
  </include>
</model>

<model name='Neleski_Cone_full_2'>
  <include>
    <static>0</static>
    <uri>model://Full_Cone</uri>
    <pose>-1 0 0.5 0 0 0</pose>
  </include>
</model>
  </world>
</sdf>
edit retag flag offensive close merge delete

Comments

It would be helpful to have the STLs too. Well actually, is it important that the holes are empty? You could always use a filled cylinder as the collision.

chapulina gravatar imagechapulina ( 2018-04-17 17:59:24 -0500 )edit

Thanks. I added a link to the STL file. Regarding the use of a cylinder primitive, I'd already considered that and decided that yes the center hole is necessary since it gets hung on a peg :-/

raequin gravatar imageraequin ( 2018-04-18 08:33:43 -0500 )edit

1 Answer

Sort by ยป oldest newest most voted
1

answered 2018-04-18 12:50:22 -0500

updated 2018-04-19 08:08:29 -0500

Based on personal experience, there are a couple things you can try:


If that doesn't make a difference, you may also try decreasing the physics simulation step size to get a better solution as explained here. This will reduce numerical instability but also slow down your simulation.

edit flag offensive delete link more

Comments

1

Setting max_vel to 0 made no change but using 0.001 as the min_depth distance fixed the problem :)

raequin gravatar imageraequin ( 2018-04-19 08:46:50 -0500 )edit
Login/Signup to Answer

Question Tools

1 follower

Stats

Asked: 2018-04-17 12:22:15 -0500

Seen: 1,319 times

Last updated: Apr 19 '18