Gazebo | Ignition | Community
Ask Your Question
0

Still runaway simulations in gazebo

asked 2018-11-13 06:52:23 -0500

Sietse gravatar image

updated 2019-05-01 03:29:12 -0500

Hello List,

UPDATED YET AGAIN: See 3rd update below!

I am having difficulties in getting stable behaviour with my simulated rowing boat. The model can be found on my github page in the boot3_description/urdf directory.

A simplified version can be found in the testing directory Please see crash.mp4 for how the simulation (and simulator) blows up.

Sometimes there is an error message like:

gzclient: /build/ogre-1.9-B6QkmW/ogre-1.9-1.9.0+dfsg1/OgreMain/include/OgreAxisAlignedBox.h:252: void Ogre::AxisAlignedBox::setExtents(const Ogre::Vector3&, const Ogre::Vector3&): Assertion `(min.x <= max.x && min.y <= max.y && min.z <= max.z) && "The minimum corner of the box must be less than or equal to maximum corner"' failed.

The model is crash_boot.xacro and for testing I use the (normally) generated crash_boot.sdf. The model now contains only 3 revolute joints. Playing around with friction and damping does not help.

What does help is reducing the max step size by a factor of 10. But it then becomes impractically slow, especially when using the full blown model with almost 40 joints.

Hopefully someone can help, as I am really stuck here.

UPDATE: Enforcing more limits as in

   <limit>
          <lower>-1.5</lower>
          <upper>0.5</upper>
          <effort>1</effort>
          <velocity>0.01</velocity>
        </limit>

seems to be completely ignored the model and gazebo crashes just the same!

2nd UPDATE: Getting a bit despondent here.

I can get it a bit better by increasing iterations in the solver, e.g. to 200 or 500. The testing model now works fine, but the complete (boot3) model now most of the time will be stable for some time (sometimes several minutes). But adding a few controllers to the joints makes it unstable again. But not by the controller itself, I am using very low values for pid.

The instability maybe comes from two or more joints connected directly together as in an elbow or shoulder using e.g.

 <link name="left_shoulder_psi_link">
    <inertial>
      <mass value="0.01"/>
      <origin rpy="0 0 0" xyz="0 0.0 0.0"/>
      <inertia ixx="0.000000167" ixy="0" ixz="0" iyy="0.000000167" iyz="0" izz="0.000000167"/>
    </inertial>
    <visual>
      <origin rpy="0 0 0" xyz="0.0 0.0 0.0"/>
      <geometry>
        <box size="0.01 0.01 0.01"/>
      </geometry>
    </visual>
  </link>

So with no change in the origin.

If you pull the Rowing repository and then do

roslaunch boot3_gazebo control_boot_world.launch

you will see the simulated rower in gazebo. Starting the simulation (and the control via ros_control) will show the crashing fairly quickly.

The following shows that a simplified model does work ok.

roslaunch testboot_gazebo control_boot_world.launch

3rd UPDATE

After some help from gazebo/issues I now have a better simple example that still crashes! Please see this folder on my github page.

The video shows the usual form of crashing. Sometimes gazebo crashes entirely with the error mentioned above.

Simplifying it further makes is stable most of the time. For example removing the fixed_joint ... (more)

edit retag flag offensive close merge delete

2 Answers

Sort by ยป oldest newest most voted
2

answered 2019-05-07 10:03:56 -0500

azeey gravatar image

Another thing to consider is your joint damping. Some of the values in your example (test2) have a joint damping of 0.5. Unfortunately, with the default settings, ODE becomes unstable for large damping values like that. The easiest thing to do is to add the following snippet in each of your joints:

<physics>
    <ode>
        <implicit_spring_damper>1</implicit_spring_damper>
    </ode>
</physics>

Here's an answer that also shows how to do it in URDF: http://answers.gazebosim.org/question...

Alternatively, you can look into using DART as the physics engine. In my testing, it was able to run your example without any modifications.

edit flag offensive delete link more

Comments

Thanks! Installing the DART engine did the trick. I get some warnings, but it works perfectly for me.

I first tried lowering the joint damping, it clearly helped, but more complicated models still become unstable and the intended model also crashes the simulator as before. I used the high damping values in an attempt to battle the instabilities. It is very non-intuitive that setting the damping higher makes the model unstable.

Thanks again, Sietse

Sietse gravatar imageSietse ( 2019-05-10 04:19:17 -0500 )edit
1

Have you tried setting higher damping values with implicit_spring_damper set to 1?

azeey gravatar imageazeey ( 2019-05-11 19:15:54 -0500 )edit
0

answered 2018-11-13 09:46:49 -0500

nkoenig gravatar image

That type of behavior can come from a couple places. Have you double checked your inertia values? Look at this tutorial.

Are your joints configure properly? Take a look at axis and limits.

Look at the effort you apply to the joints. Very large forces can be unrealistic and in turn cause incorrect behavior.

Out of curiosity, are you trying to row on a flat ground plane? If you want to row in water then you should look at this repository.

edit flag offensive delete link more

Comments

Thanks, see my edit above. And also thanks for the links! I want to do experiments with rigging of race-shells, in order to make better discussions among rowing coaches possible. This is only the very first start. Later I will add a rower in the form of a "robot" with all his joints. And then be hopefully able to optimize the rigger setting for that rower, optimizing it for maximum speed given a power output of the rower.

Sietse gravatar imageSietse ( 2018-11-13 10:23:24 -0500 )edit

The inertia and mass values look okay. You could start debugging your problem by inspecting the forces you are applying to the joints. If you haven't done so, you could also reduce the friction coefficients on the boat body.

nkoenig gravatar imagenkoenig ( 2018-11-14 09:12:07 -0500 )edit

Please see my second edit.

Sietse gravatar imageSietse ( 2018-11-20 12:52:15 -0500 )edit

In a, late, response to your last comment: I do not apply any force to the joints. The model crashes by itself. Also in the simplified model mentioned in my updated question above.

Sietse gravatar imageSietse ( 2019-03-28 05:17:09 -0500 )edit
Login/Signup to Answer

Question Tools

1 follower

Stats

Asked: 2018-11-13 06:52:23 -0500

Seen: 1,750 times

Last updated: May 07 '19