gazebosim / gazebo-classic

Gazebo classic. For the latest version, see https://github.com/gazebosim/gz-sim
http://classic.gazebosim.org/
Other
1.17k stars 478 forks source link

Large models break the simulation #1154

Open osrf-migration opened 10 years ago

osrf-migration commented 10 years ago

Original report (archived issue) by Andrew Hundt (Bitbucket: ahundt).

The original report had attachments: animated_box.world


The attached version of animated_box.world creates a 7x7x7 box with some spheres on its surface. This model appears in the sky and jitters off into the distance. It is clearly triggering a severe bug, and I've been able to trigger it with numerous other models and configurations of similar size.

Enabling bullet physics reduces the severity of the problem, but it is still there. I've been able to make the attached spheres fly off when using bullet if I put the box into an animation that modifies pitch as well.

osrf-migration commented 10 years ago

Original comment by John Hsu (Bitbucket: hsu, GitHub: hsu).


Looks like a convergence issue. The long moment arm to the point masses must be making the system difficult to converge. Increasing the number of iterations will stabilize it. For example, modify the world file by adding a physics block as below should stabilize it:

<?xml version="1.0"?> 
<sdf version="1.4">
  <world name="animated_box_world">

    <physics type="ode">
      <gravity>0.000000 0.000000 -9.810000</gravity>
      <ode>
        <solver>
          <type>quick</type>
          <iters>1000</iters>
        </solver>
      </ode>
      <bullet>
        <solver>
          <type>sequential_impulse</type>
          <iters>1000</iters>
        </solver>
      </bullet>
      <real_time_update_rate>0.000000</real_time_update_rate>
      <max_step_size>0.001</max_step_size>
    </physics>

    <!-- Ground Plane -->
    <include>
      <uri>model://ground_plane</uri>
    </include>
    ...

Alternatively, you can specify inertia values that correspond to real world objects of comparable sizes to stabilize the system as well. For example,

<?xml version="1.0"?> 
<sdf version="1.4">
  <world name="animated_box_world">

    <!-- Ground Plane -->
    <include>
      <uri>model://ground_plane</uri>
    </include>

    <include>
      <uri>model://sun</uri>
    </include>
    <model name="box">
      <pose>0 0 5 0 0 0</pose>

      <link name="boxlink">

        <inertial>
          <mass>100.0</mass>
          <inertia>
            <ixx>1.0</ixx>
            <iyy>1.0</iyy>
            <izz>1.0</izz>
            <ixy>0</ixy>
            <ixz>0</ixz>
            <iyz>0</iyz>
          </inertia>
        </inertial>

        <collision name="collision">
          <geometry>
            <box>
              <size>7 7 7</size>
            </box>
          </geometry>
        </collision>

        <visual name="visual">
          <geometry>
            <box>
              <size>7 7 7</size>
            </box>
          </geometry>
        </visual>
      </link>

      <!-- Top Middle -->
      <link name="point.1">
        <gravity>true</gravity>
        <self_collide>true</self_collide>
        <pose>7 7 0 0 0 0</pose>

        <inertial>
          <mass>0.01</mass>
          <inertia>
            <ixx>0.0001</ixx>
            <iyy>0.0001</iyy>
            <izz>0.0001</izz>
            <ixy>0</ixy>
            <ixz>0</ixz>
            <iyz>0</iyz>
          </inertia>
        </inertial>

        <visual name="visual-point.1"><geometry><sphere><radius>0.1</radius></sphere></geometry></visual>
      </link>
      <joint name="cartlink-point.1" type="revolute">
        <axis><xyz>0 0 1</xyz><limit><lower>0</lower><upper>0</upper></limit><use_parent_model_frame>true</use_parent_model_frame></axis>
        <parent>boxlink</parent>
        <child>point.1</child>
      </joint>

      <!-- Middle Middle, on top of wheel -->
      <link name="point.2">
        <gravity>true</gravity>
        <self_collide>true</self_collide>
        <pose>7 7 0.5 0 0 0</pose>

        <inertial>
          <mass>0.01</mass>
          <inertia>
            <ixx>0.0001</ixx>
            <iyy>0.0001</iyy>
            <izz>0.0001</izz>
            <ixy>0</ixy>
            <ixz>0</ixz>
            <iyz>0</iyz>
          </inertia>
        </inertial>

        <visual name="visual-point.2"><geometry><sphere><radius>0.1</radius></sphere></geometry></visual>
      </link>
      <joint name="cartlink-point.2" type="revolute">
        <axis><xyz>0 0 1</xyz><limit><lower>0</lower><upper>0</upper></limit><use_parent_model_frame>true</use_parent_model_frame></axis>
        <parent>boxlink</parent>
        <child>point.2</child>
      </joint>

      <link name="point.3">
        <gravity>true</gravity>
        <self_collide>true</self_collide>
        <pose>7 7 1 0 0 0</pose>

        <inertial>
          <mass>0.01</mass>
          <inertia>
            <ixx>0.0001</ixx>
            <iyy>0.0001</iyy>
            <izz>0.0001</izz>
            <ixy>0</ixy>
            <ixz>0</ixz>
            <iyz>0</iyz>
          </inertia>
        </inertial>

        <visual name="visual-point.3"><geometry><sphere><radius>0.1</radius></sphere></geometry></visual>
      </link>
      <joint name="cartlink-point.3" type="revolute">
        <axis><xyz>0 0 1</xyz><limit><lower>0</lower><upper>0</upper></limit><use_parent_model_frame>true</use_parent_model_frame></axis>
        <parent>boxlink</parent>
        <child>point.3</child>
      </joint>

      <link name="point1">
        <gravity>true</gravity>
        <self_collide>true</self_collide>
        <pose>7 7 2 0 0 0</pose>

        <inertial>
          <mass>0.01</mass>
          <inertia>
            <ixx>0.0001</ixx>
            <iyy>0.0001</iyy>
            <izz>0.0001</izz>
            <ixy>0</ixy>
            <ixz>0</ixz>
            <iyz>0</iyz>
          </inertia>
        </inertial>

        <!-- 
        <collision name="collision">
          <geometry>
            <sphere>
              <radius>0.01</radius>
            </sphere>
          </geometry>
        </collision>
        <!-- -->
        <visual name="visual">
          <geometry>
            <sphere>
              <radius>0.1</radius>
            </sphere>
          </geometry>
        </visual>
      </link>
      <joint name="boxlink-point1" type="revolute">
        <axis>
           <xyz>0 0 1</xyz>
           <limit>
             <lower>0</lower>
             <upper>0</upper>
           </limit>
         </axis>
         <parent>boxlink</parent>
         <child>point1</child>
       </joint>
      <!--><plugin name="animated_box" filename="libanimated_box.so"/>

    </model>        
  </world>
</sdf>

If you are compiling from source, you can also test out engines such as simbody and dart. Simbody will reduce internal time step size to make sure contacts are stable, while DART uses direct solver to resolve contact constraints. Each engine deal with the dynamics problem differently and may have different resulting behaviors. Something fun to experiment with.

Issues like this one could probably have been resolved automatically if the GUI provided better feedback to let users understand what's happening under the hood of the engine used. For example, in this particular test world, if gzclient or gzserver raised a warning about the lack of constraint solver convergence in the dynamics solution, paused simulation and proposed alternative solutions such as raising the number of iterations or using a different solver, it might make it easier to produce better simulation results. Creating a feature request issue #1155.

osrf-migration commented 10 years ago

Original comment by Andrew Hundt (Bitbucket: ahundt).


Thanks if that works it will help.

In my particular case the physics of these points isn't very important. I really just need to see them and have them broadcast their pose. They are simulating locations on the robot, not actual physical entities. Therefore, an ideal solution for my use case would be for them to behave as non-actors in the world, but still exist otherwise so I can collect the relevant data, which is my real use case.

The other information you've provided plus the new issue you created are definitely useful in many situations other than this particular case as well, so I think the issue you brought up is a good and relevant one.