Gazebo Fortress: ODE Internal error while using ignition-gazebo-thruster-system and ignition-gazebo-hydrodynamics-system
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 important role on the dynamics of the system, with does not allow us to circumnavigate the issue.
The commands used are below:
ign topic -t /model/puffy/joint/left_propeller_joint/cmd_pos -m ignition.msgs.Double -p 'data: -0.4'
ign topic -t /model/puffy/joint/right_propeller_joint/cmd_pos -m ignition.msgs.Double -p 'data: -0.4'
Attached below the sdf files involved in the tests and the crash outlet from terminal Note that the crash outlet results to be the same in all cases.
Terminal Output:
~/ros_ws/src$ ign gazebo sample_world.sdf
QStandardPaths: XDG_RUNTIME_DIR not set, defaulting to '/tmp/runtime-docker'
ODE INTERNAL ERROR 1: assertion "aabbBound >= dMinIntExact && aabbBound < dMaxIntExact" failed in collide() [collision_space.cpp:460]
Stack trace (most recent call last):
#31 Object "/lib/x86_64-linux-gnu/libruby-3.0.so.3.0", at 0x7fd6f44cfca6, in
#30 Object "/lib/x86_64-linux-gnu/libruby-3.0.so.3.0", at 0x7fd6f44ccfd5, in
#29 Object "/lib/x86_64-linux-gnu/libruby-3.0.so.3.0", at 0x7fd6f44cac44, in
#28 Object "/lib/x86_64-linux-gnu/libruby-3.0.so.3.0", at 0x7fd6f4416a2e, in
#27 Object "/lib/x86_64-linux-gnu/libruby-3.0.so.3.0", at 0x7fd6f43419bc, in rb_protect
#26 Object "/lib/x86_64-linux-gnu/libruby-3.0.so.3.0", at 0x7fd6f44d9c71, in rb_yield
#25 Object "/lib/x86_64-linux-gnu/libruby-3.0.so.3.0", at 0x7fd6f44d531c, in rb_vm_exec
#24 Object "/lib/x86_64-linux-gnu/libruby-3.0.so.3.0", at 0x7fd6f44cfca6, in
#23 Object "/lib/x86_64-linux-gnu/libruby-3.0.so.3.0", at 0x7fd6f44ccfd5, in
#22 Object "/lib/x86_64-linux-gnu/libruby-3.0.so.3.0", at 0x7fd6f44cac44, in
#21 Object "/usr/lib/x86_64-linux-gnu/ruby/3.0.0/fiddle.so", at 0x7fd6f085944b, in
#20 Object "/lib/x86_64-linux-gnu/libruby-3.0.so.3.0", at 0x7fd6f4498098, in rb_nogvl
#19 Object "/usr/lib/x86_64-linux-gnu/ruby/3.0.0/fiddle.so", at 0x7fd6f0858d6b, in
#18 Object "/lib/x86_64-linux-gnu/libffi.so.8", at 0x7fd6f082b492, in
#17 Object "/lib/x86_64-linux-gnu/libffi.so.8", at 0x7fd6f082ee2d, in
#16 Object "/usr/lib/x86_64-linux-gnu/libignition-gazebo6-ign.so.6.13.0", at 0x7fd6efd90a53, in runServer
#15 Object "/lib/x86_64-linux-gnu/libignition-gazebo6.so.6", at 0x7fd6efa5e635, in
#14 Object "/lib/x86_64-linux-gnu/libignition-gazebo6.so.6", at 0x7fd6efa6c91a, in ignition::gazebo::v6::SimulationRunner::Run(unsigned long)
#13 Object "/lib/x86_64-linux-gnu/libignition-gazebo6.so.6", at 0x7fd6efa6bfdd, in ignition::gazebo::v6::SimulationRunner::Step(ignition::gazebo::v6::UpdateInfo const&)
#12 Object "/lib/x86_64-linux-gnu/libignition-gazebo6.so.6", at 0x7fd6efa67f5a, in ignition::gazebo::v6::SimulationRunner::UpdateSystems()
#11 Object "/usr/lib/x86_64-linux-gnu/ign-gazebo-6/plugins/libignition-gazebo-physics-system.so", at 0x7fd6e83b21e8, in ignition::gazebo::v6::systems::Physics::Update(ignition::gazebo::v6::UpdateInfo const&, ignition::gazebo::v6::EntityComponentManager&)
#10 Object "/usr/lib/x86_64-linux-gnu/ign-gazebo-6/plugins/libignition-gazebo-physics-system.so", at 0x7fd6e83b287e, in ignition::gazebo::v6::systems::PhysicsPrivate::Step(std::chrono::duration<long, std::ratio<1l, 1000000000l> > const&)
#9 Object "/usr/lib/x86_64-linux-gnu/ign-physics-5/engine-plugins/libignition-physics-dartsim-plugin.so", at 0x7fd6d87624d8, in ignition::physics::dartsim::SimulationFeatures::WorldForwardStep(ignition::physics::Identity const&, ignition::physics::SpecifyData<ignition::physics::RequireData<ignition::physics::WorldPoses>, ignition::physics::ExpectData<ignition::physics::ChangedWorldPoses, ignition::physics::Contacts, ignition::physics::JointPositions> >&, ignition::physics::CompositeData&, ignition::physics::ExpectData<ignition::physics::ApplyExternalForceTorques, ignition::physics::ApplyGeneralizedForces, ignition::physics::VelocityControlCommands, ignition::physics::ServoControlCommands> const&)
#8 Object "/lib/x86_64-linux-gnu/libdart.so.6.12", at 0x7fd6d83dce73, in dart::simulation::World::step(bool)
#7 Object "/lib/x86_64-linux-gnu/libdart.so.6.12", at 0x7fd6d83c2705, in dart::constraint::ConstraintSolver::solve()
#6 Object "/lib/x86_64-linux-gnu/libdart.so.6.12", at 0x7fd6d83c0fe1, in dart::constraint::ConstraintSolver::updateConstraints()
#5 Object "/lib/x86_64-linux-gnu/libdart-collision-ode.so.6.12", at 0x7fd6e010c1cb, in dart::collision::OdeCollisionDetector::collide(dart::collision::CollisionGroup*, dart::collision::CollisionOption const&, dart::collision::CollisionResult*)
#4 Object "/lib/x86_64-linux-gnu/libode.so.8", at 0x7fd6c8717266, in dxHashSpace::collide(void*, void (*)(void*, dxGeom*, dxGeom*))
#3 Object "/lib/x86_64-linux-gnu/libode.so.8", at 0x7fd6c871f7b7, in dDebug
#2 Object "/lib/x86_64-linux-gnu/libc.so.6", at 0x7fd6f409b7f2, in abort
#1 Object "/lib/x86_64-linux-gnu/libc.so.6", at 0x7fd6f40b5475, in raise
#0 Object "/lib/x86_64-linux-gnu/libc.so.6", at 0x7fd6f4109a7c, in pthread_kill
Aborted (Signal sent by tkill() 771713 1000)
Stack trace (most recent call last):
#30 Object "[0xffffffffffffffff]", at 0xffffffffffffffff, in
#29 Object "ign gazebo gui", at 0x5571ef4631c4, in _start
#28 Object "/lib/x86_64-linux-gnu/libc.so.6", at 0x7fd6f409ce3f, in __libc_start_main
#27 Object "/lib/x86_64-linux-gnu/libc.so.6", at 0x7fd6f409cd8f, in
#26 Object "ign gazebo gui", at 0x5571ef46317e, in
#25 Object "/lib/x86_64-linux-gnu/libruby-3.0.so.3.0", at 0x7fd6f4343e29, in ruby_run_node
#24 Object "/lib/x86_64-linux-gnu/libruby-3.0.so.3.0", at 0x7fd6f4340327, in
#23 Object "/lib/x86_64-linux-gnu/libruby-3.0.so.3.0", at 0x7fd6f44d531c, in rb_vm_exec
#22 Object "/lib/x86_64-linux-gnu/libruby-3.0.so.3.0", at 0x7fd6f44cfca6, in
#21 Object "/lib/x86_64-linux-gnu/libruby-3.0.so.3.0", at 0x7fd6f44ccfd5, in
#20 Object "/lib/x86_64-linux-gnu/libruby-3.0.so.3.0", at 0x7fd6f44cac44, in
#19 Object "/lib/x86_64-linux-gnu/libruby-3.0.so.3.0", at 0x7fd6f4416a2e, in
#18 Object "/lib/x86_64-linux-gnu/libruby-3.0.so.3.0", at 0x7fd6f43419bc, in rb_protect
#17 Object "/lib/x86_64-linux-gnu/libruby-3.0.so.3.0", at 0x7fd6f44d9c71, in rb_yield
#16 Object "/lib/x86_64-linux-gnu/libruby-3.0.so.3.0", at 0x7fd6f44d531c, in rb_vm_exec
#15 Object "/lib/x86_64-linux-gnu/libruby-3.0.so.3.0", at 0x7fd6f44cfca6, in
#14 Object "/lib/x86_64-linux-gnu/libruby-3.0.so.3.0", at 0x7fd6f44ccfd5, in
#13 Object "/lib/x86_64-linux-gnu/libruby-3.0.so.3.0", at 0x7fd6f44cac44, in
#12 Object "/usr/lib/x86_64-linux-gnu/ruby/3.0.0/fiddle.so", at 0x7fd6f085944b, in
#11 Object "/lib/x86_64-linux-gnu/libruby-3.0.so.3.0", at 0x7fd6f4498098, in rb_nogvl
#10 Object "/usr/lib/x86_64-linux-gnu/ruby/3.0.0/fiddle.so", at 0x7fd6f0858d6b, in
#9 Object "/lib/x86_64-linux-gnu/libffi.so.8", at 0x7fd6f082b492, in
#8 Object "/lib/x86_64-linux-gnu/libffi.so.8", at 0x7fd6f082ee2d, in
#7 Object "/usr/lib/x86_64-linux-gnu/libignition-gazebo6-ign.so.6.13.0", at 0x7fd6efd8d86c, in runGui
#6 Object "/lib/x86_64-linux-gnu/libignition-gazebo6-gui.so.6", at 0x7fd6efbb3aeb, in ignition::gazebo::v6::gui::runGui(int&, char**, char const*, char const*, int, char const*)
#5 Object "/lib/x86_64-linux-gnu/libignition-gui6.so.6", at 0x7fd6ee91b16c, in ignition::gui::Application::~Application()
#4 Object "/lib/x86_64-linux-gnu/libQt5Core.so.5", at 0x7fd6eec70923, in QObject::~QObject()
#3 Object "/lib/x86_64-linux-gnu/libQt5Core.so.5", at 0x7fd6eec65a6d, in QObjectPrivate::deleteChildren()
#2 Object "/lib/x86_64-linux-gnu/libignition-gazebo6-gui.so.6", at 0x7fd6efbbbf2c, in ignition::gazebo::v6::GuiRunner::~GuiRunner()
#1 Object "/lib/x86_64-linux-gnu/libignition-gazebo6-gui.so.6", at 0x7fd6efbbbf11, in ignition::gazebo::v6::GuiRunner::~GuiRunner()
#0 Object "/lib/x86_64-linux-gnu/libignition-gazebo6-gui.so.6", at 0x7fd6efbca74b, in void ignition::utils::detail::DefaultDelete<ignition::gazebo::v6::GuiRunner::Implementation>(ignition::gazebo::v6::GuiRunner::Implementation*)
Segmentation fault (Address not mapped to object [0x7fd6b4ff4f18])
SDF FILES: sample_world.sdf
<?xml version="1.0" ?>
<sdf version="1.8">
<world name="sample_world">
<!-- TEST1 -->
<!-- <physics name="1ms" type="ignored">
<max_step_size>0.02</max_step_size>
<real_time_factor>1.0</real_time_factor>
</physics> -->
<!-- TEST2 -->
<physics default="1" name="default_physics" type="bullet">
<real_time_update_rate>1000.0</real_time_update_rate>
<max_contacts>20</max_contacts>
<max_step_size>0.001</max_step_size>
<real_time_factor>1.0</real_time_factor>
</physics>
<plugin
filename="ignition-gazebo-physics-system"
name="ignition::gazebo::systems::Physics">
<!-- <engine>
<filename>DART</filename>
</engine> -->
</plugin>
<plugin
filename="ignition-gazebo-user-commands-system"
name="ignition::gazebo::systems::UserCommands">
</plugin>
<plugin
filename="ignition-gazebo-scene-broadcaster-system"
name="ignition::gazebo::systems::SceneBroadcaster">
</plugin>
<plugin
filename="ignition-gazebo-buoyancy-system"
name="ignition::gazebo::systems::Buoyancy">
<uniform_fluid_density>1000</uniform_fluid_density>
</plugin>
<light type="directional" name="sun">
<cast_shadows>true</cast_shadows>
<pose degrees="true"> 0 0 10 0 0 0</pose>
<diffuse>0.8 0.8 0.8 1</diffuse>
<specular>0.2 0.2 0.2 1</specular>
<attenuation>
<range>1000</range>
<constant>0.9</constant>
<linear>0.01</linear>
<quadratic>0.001</quadratic>
</attenuation>
<direction>-0.5 0.1 -0.9</direction>
</light>
<model name="ground_plane">
<static>true</static>
<link name="link">
<collision name="collision">
<geometry>
<plane>
<normal>0 0 1</normal>
<size>10000 10000</size>
</plane>
</geometry>
</collision>
<visual name="visual">
<geometry>
<plane>
<normal>0 0 1</normal>
<size>10000 10000</size>
</plane>
</geometry>
<material>
<ambient>0.9 0.9 0.9 0.9</ambient>
<diffuse>0.9 0.9 0.9 0.9</diffuse>
<specular>0.9 0.9 0.9 0.9</specular>
</material>
</visual>
</link>
</model>
<include>
<uri>puffy.sdf</uri>
<pose degrees="true"> 0 0 1 0 0 0</pose>
<name>puffy</name>
</include>
</world>
</sdf>
puffy.sdf
<?xml version="1.0"?>
<sdf version="1.9">
<model name="puffy">
<enable_wind>true</enable_wind>
<include merge="true">
<pose degrees="true">0 0 0 0 0 0</pose>
<uri>geom.sdf</uri>
<plugin
filename="ignition-gazebo-hydrodynamics-system"
name="ignition::gazebo::systems::Hydrodynamics">
<link_name>base_link</link_name>
<enable_coriolis>false</enable_coriolis>
<!-- <xDotU>-1.09</xDotU>
<yDotV>-2.26</yDotV>
<zDotW>-2.26</zDotW>
<kDotP>0</kDotP>
<mDotQ>-0.0025</mDotQ>
<nDotR>-0.0025</nDotR> -->
<xDotU>-0.81</xDotU>
<yDotV>-0.5</yDotV>
<zDotW>-0.5</zDotW>
<kDotP>0</kDotP>
<mDotQ>0</mDotQ>
<nDotR>0</nDotR>
<xUU>-4.0</xUU>
<xU>-0.001</xU>
<yVV>-25.0</yVV>
<yV>-0.001</yV>
<zWW>-8.0</zWW>
<zW>-0.001</zW>
<kPP>-0.1</kPP>
<kP>-0.001</kP>
<mQQ>-0.5</mQQ>
<mQ>-0.001</mQ>
<nRR>-0.2</nRR>
<nR>-0.01</nR>
</plugin>
<plugin
filename="ignition-gazebo-thruster-system"
name="ignition::gazebo::systems::Thruster">
<namespace>puffy</namespace>
<joint_name>right_propeller_joint</joint_name>
<thrust_coefficient>0.1</thrust_coefficient>
<fluid_density>1000</fluid_density>
<propeller_diameter>0.01</propeller_diameter>
<velocity_control>true</velocity_control>
<!-- <use_angvel_cmd>false</use_angvel_cmd> -->
<p_gain>0.1</p_gain>
<i_gain>0</i_gain>
<d_gain>0</d_gain>
</plugin>
<plugin
filename="ignition-gazebo-thruster-system"
name="ignition::gazebo::systems::Thruster">
<namespace>puffy</namespace>
<joint_name>left_propeller_joint</joint_name>
<thrust_coefficient>0.1</thrust_coefficient>
<fluid_density>1000</fluid_density>
<propeller_diameter>0.01</propeller_diameter>
<velocity_control>true</velocity_control>
<p_gain>0.1</p_gain>
<i_gain>0</i_gain>
<d_gain>0</d_gain>
</plugin>
</include>
</model>
</sdf>
geom.sdf
<?xml version="1.0" ?>
<sdf version="1.8">
<model name='puffy'>
<link name='base_link'>
<pose degrees="true"> 0 0 0 0 0 0 </pose>
<inertial>
<mass>0.79999</mass>
<inertia>
<ixx>0.0015</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>0.0015</iyy>
<iyz>0</iyz>
<izz>0.0015</izz>
</inertia>
</inertial>
<visual name='visual'>
<geometry>
<box>
<size>0.1 0.1 0.1</size>
</box>
</geometry>
<material>
<ambient>0 1 0.0 1</ambient>
<diffuse> 1 0.5 0.5 1</diffuse>
<specular>0 1 0.0 1</specular>
</material>
</visual>
<collision name='collision'>
<pose degrees="true"> 0 0 0.01 0 0 0 </pose>
<geometry>
<box>
<size>0.1 0.1 0.08</size>
</box>
</geometry>
</collision>
</link>
<!--Left propeller-->
<link name='left_propeller'>
<pose degrees="true"> 0.1 -0.04 0 0 0 0</pose>
<inertial>
<mass>0.001</mass>
<inertia>
<ixx>0.000002</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>0.000002</iyy>
<iyz>0</iyz>
<izz>0.000002</izz>
</inertia>
</inertial>
<visual name='visual'>
<geometry>
<box>
<size>0.01 0.01 0.01</size>
</box>
</geometry>
<material>
<ambient>1.0 0.0 0.0 1</ambient>
<diffuse>1.0 0.0 0.0 1</diffuse>
<specular>1.0 0.0 0.0 1</specular>
</material>
</visual>
<collision name='collision'>
<pose degrees="true"> 0 0 0 0 0 0 </pose>
<geometry>
<box>
<size>0.01 0.01 0.01</size>
</box>
</geometry>
</collision>
</link>
<!--Right propeller-->
<link name='right_propeller'>
<pose degrees="true"> 0.1 0.04 0 0 0 0</pose>
<inertial>
<mass>0.001</mass>
<inertia>
<ixx>0.000002</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>0.000002</iyy>
<iyz>0</iyz>
<izz>0.000002</izz>
</inertia>
</inertial>
<visual name='visual'>
<geometry>
<box>
<size>0.01 0.01 0.01</size>
</box>
</geometry>
<material>
<ambient>1.0 0.0 0.0 1</ambient>
<diffuse>1.0 0.0 0.0 1</diffuse>
<specular>1.0 0.0 0.0 1</specular>
</material>
</visual>
<collision name='collision'>
<pose degrees="true"> 0 0 0 0 0 0 </pose>
<geometry>
<box>
<size>0.01 0.01 0.01</size>
</box>
</geometry>
</collision>
</link>
<!--left propeller joint-->
<joint name='left_propeller_joint' type='revolute'>
<pose degrees="true"> 0 0 0 0 0 0</pose>
<parent>base_link</parent>
<child>left_propeller</child>
<axis>
<xyz>1 0 0 </xyz>
<limit>
<lower>-1.79769e+308</lower>
<upper>1.79769e+308</upper>
</limit>
</axis>
</joint>
<!--right propeller joint-->
<joint name='right_propeller_joint' type='revolute'>
<pose degrees="true"> 0 0 0 0 0 0</pose>
<parent>base_link</parent>
<child>right_propeller</child>
<axis>
<xyz>1 0 0 </xyz>
<limit>
<lower>-1.79769e+308</lower>
<upper>1.79769e+308</upper>
</limit>
</axis>
</joint>
</model>
</sdf>
Asked by save_xx on 2022-12-22 07:32:39 UTC
Answers
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.
Asked by quarkytale on 2023-02-01 17:25:12 UTC
Comments