Gazebo | Ignition | Community
Ask Your Question
1

Gazebo Fortress: ODE Internal error while using ignition-gazebo-thruster-system and ignition-gazebo-hydrodynamics-system

asked 2022-12-22 06:32:39 -0500

save_xx gravatar image

We are testing a simplified underwater robot in simulation and we are facing an issue with the ignition-gazebo-thruster-system and ignition-gazebo-hydrodynamics-system plugins.

We are working in a Docker (ubuntu 22.04) and we have updated and upgraded the system before testing. We are working with Ignition Gazebo 6:Fortess The first issue we are facing is the following: Thruster-system plugin cannot be operated with velocity control set to false:

In our understanding, by setting the label <velocity_control> to false, it allows to apply a value of force in Newton in the direction of the thruster axis, instead of sending a rotation command.

What we found is that, by assigning the value to false instead of true, the system crashes a moment after a motor command is sent. The impression is that the robot is “shot” out of boundaries the moment the command is received. Motor command are being currently sent via terminal, the command is as follow

ign topic -t /model/puffy/joint/left_propeller_joint/cmd_pos -m ignition.msgs.Double -p 'data: -0.0000001'

We tested different input values ( +/- 4 & +/- 0.1) , and right propeller with identical result. We tried using <physics name="1ms" type="ignored"> under TEST1 (commented in the code) and <physics default="1" name="default_physics" type="bullet"> underTEST2 , with: bulled, ode , dart

The issue with the hydrodynamic plugin can be divided in two parts: 1st Issue – If the value of the added mass exceeds <xDotU> 0.785, the system crashes shortly after starting moving

While testing a simplified version of an underwater robot we experienced difficulties related to the plugin <ignition-gazebo-hydrodynamics-system>. The first issue is that by applying a value higher than 0.785 (such as 0.79) to the added mass <xDotU> the system crashes. The impression is that the robot is “shot” out of boundaries. This happens the moment the robot starts moving, either due to a propeller or due to gravity (if the mass is not set exactly to 0.8, the buoyancy and weight are not equal). It usually takes 1-5 seconds for the crash to occour.

Again, we tried using <physics name="1ms" type="ignored"> under TEST1 (commented in the code) and <physics default="1" name="default_physics" type="bullet"> underTEST2 , with: bulled, ode , dart

2nd Issue – When activating both propeller at the same input value, the robot rotates around the vertical axis.

Related to the same issue, setting a lower added mass value, on <xDotU>,<yDotV>,<zDotW>, the system does not crash, but presents an unusual behavior: when the commands below are sent (we use separate terminals), the robot, instead of moving forward, continues to steer. Depending with propeller was activated first, the robot will continue steering in such direction. Notice that we set a drag value that should quickly kill the residual rotational speed (<nR> and <nRR>). Also if <xDotU>,<yDotV>,<zDotW> are set to zero, the issues disappears and the robot behaves as expected.

For our study we require to model a <xDotU> and <yDotV> with different values as the play an ... (more)

edit retag flag offensive close merge delete

1 Answer

Sort by » oldest newest most voted
0

answered 2023-02-01 16:25:12 -0500

It can be frustrating to see the sim just crash. I have worked with/on the hydrodynamics plugin a bit. Trying out the model and world you shared, in the meantime,

Any reason why Coriolis force is disabled? (qualitative behavior should be independent but still)

I'd double check units and signs of the plugin parameters. A way to validate the sign is to enable added mass coefficients one by one and apply an external force (using the wrench plugin) to that axis, notice the behavior.

Also, what's the nature of the damping coefficients, X_{uu} or X_{u|u|}, if you're using the later then need to specify the tags as xUabsU, see https://github.com/gazebosim/gz-sim/blob/ign-gazebo6/src/systems/hydrodynamics/Hydrodynamics.cc#L49-L51.

Hope it helps.

edit flag offensive delete link more
Login/Signup to Answer

Question Tools

1 follower

Stats

Asked: 2022-12-22 06:32:39 -0500

Seen: 266 times

Last updated: Dec 22 '22