Unstable Simulation At Low max_step_size?
My entire world:
<?xml version='1.0' encoding='utf-8'?>
<sdf version="1.5">
<world name="bin-picking">
<physics type="ode">
<max_step_size>0.050</max_step_size>
<real_time_update_rate>0</real_time_update_rate>
</physics>
<include><uri>model://ground_plane</uri></include>
<include><uri>model://sun</uri></include>
<include><uri>model://triangle</uri><name>triangle_0</name><pose> 1.5 -0.705 1.075 0 0 1.134</pose></include>
</world>
</sdf>
Here is the triangle model:
<?xml version='1.0'?>
<sdf version='1.5'>
<model name='cylinder'>
<link name='link'>
<pose frame=''>0 0 0 0 -0 0</pose>
<visual name='visual'>
<geometry>
<cylinder>
<radius>.5</radius>
<length>1</length>
</cylinder>
</geometry>
</visual>
<collision name='collision'>
<geometry>
<cylinder>
<radius>.5</radius>
<length>1</length>
</cylinder>
</geometry>
</collision>
</link>
</model>
</sdf>
Running this: gazebo --verbose my_world.world
will produce an unstable simulation with jittery ground plane collision that never ends in Gazebo 6.5.1, like in this video.
This appears to be entirely a result of having a large max_step_size
. A value of 0.001, for example, will not cause this problem. The environment will appear stable. Is this instability at large step sizes expected? What explains it?
Our difficulty with using small step sizes is that it affects the camera's rendering rate and we'd like to have the camera rendering at a certain rate in relation to physics updates.
Modifying my .world file to use the "world" solver helped the stability of it:
<world name="bin-picking">
<physics type="ode">
<max_step_size>0.050</max_step_size>
<real_time_update_rate>20</real_time_update_rate>
<ode>
<solver>
<type>world</type>
</solver>
</ode>
</physics>
The above situation with a single triangle is now stable. However, slightly more complicated scenes, like a scene with 2 boxes, 2 cylinders, 2 triangles, and 2 hexagons will exhibit some of this collision instability simply from running the simulation without any interaction.