Gazebo Sim

API Reference

10.1.1
Hydrodynamics Class Reference

Hydrodynamic damping and current forces for underwater vehicles. More...

#include <Hydrodynamics.hh>

Public Member Functions

 Hydrodynamics ()
 Constructor.
 
 ~Hydrodynamics () override
 Destructor.
 
void Configure (const Entity &_entity, const std::shared_ptr< const sdf::Element > &_sdf, EntityComponentManager &_ecm, EventManager &) override
 Documentation inherited.
 
void PostUpdate (const UpdateInfo &_info, const EntityComponentManager &_ecm) override
 Documentation inherited.
 
void PreUpdate (const UpdateInfo &_info, EntityComponentManager &_ecm) override
 Documentation inherited.
 
void Reset (const UpdateInfo &_info, EntityComponentManager &_ecm) override
 Documentation inherited.
 
- Public Member Functions inherited from System
 System ()=default
 Constructor.
 
virtual ~System ()=default
 Destructor.
 
- Public Member Functions inherited from ISystemConfigure
virtual ~ISystemConfigure ()=default
 
- Public Member Functions inherited from ISystemPreUpdate
virtual ~ISystemPreUpdate ()=default
 
- Public Member Functions inherited from ISystemPostUpdate
virtual ~ISystemPostUpdate ()=default
 
- Public Member Functions inherited from ISystemReset
virtual ~ISystemReset ()=default
 

Additional Inherited Members

- Public Types inherited from System
using PriorityType = int32_t
 Signed integer type used for specifying priority of the execution order of PreUpdate and Update phases.
 
- Static Public Attributes inherited from System
static constexpr PriorityType kDefaultPriority = {0}
 Default priority value for execution order of the PreUpdate and Update phases.
 
static constexpr std::string_view kPriorityElementName
 Name of the XML element from which the priority value will be parsed.
 

Detailed Description

Hydrodynamic damping and current forces for underwater vehicles.

Computes linear and quadratic damping (drag) forces in the body frame per Fossen's 6-DOF marine craft model [1][2]. Should be used together with the Buoyancy plugin. The relevant terms from Fossen's equation of motion are:

D(v_r) * v_r

where v_r = v - v_current is the velocity relative to the fluid in the body frame.

Based on Brian Bingham's plugin for VRX.

Added Mass and Coriolis

When using the DART physics engine, added mass should be specified using the SDF <fluid_added_mass> tag on the link's <inertial> element. DART integrates added mass implicitly (unconditionally stable) and automatically computes the full non-diagonal Coriolis matrix. See: http://sdformat.org/spec?ver=1.11&elem=link#inertial_fluid_added_mass

Other physics engines (Bullet, MuJoCo) do not support native added mass. Use the legacy plugin parameters (<xDotU>, etc.) instead.

Do not set added mass in both places simultaneously. If both <fluid_added_mass> and plugin parameters are active, forces are double-counted. The plugin emits an error if this is detected.

When both <fluid_added_mass> and an ocean current are present, this plugin automatically applies a Coriolis correction so that the Coriolis force uses the relative velocity v_r rather than the absolute velocity v. This correction is zero when there is no current.

SNAME Naming Convention

Damping parameters follow the SNAME (Society of Naval Architects and Marine Engineers) 1950 convention. The first lowercase letter denotes the force/moment axis, and the remaining uppercase letters denote the velocity components:

| Axis | x (surge) | y (sway) | z (heave) | k (roll) | m (pitch) | n (yaw) | |---—|--------—|-------—|--------—|-------—|--------—| |------—| | Velocity | U | V | W | P | Q | R |

For example, <yVabsV> is the quadratic drag on the sway axis due to |V|*V, and <nR> is the linear yaw damping due to yaw rate R.

System Parameters

Required

  • <link_name> - Link to apply hydrodynamic forces to. [string]

Damping (Drag)

Diagonal terms:

  • <xU> - Linear damping, surge [kg/s]
  • <yV> - Linear damping, sway [kg/s]
  • <zW> - Linear damping, heave [kg/s]
  • <kP> - Linear damping, roll [kgm^2/s]
  • <mQ> - Linear damping, pitch [kgm^2/s]
  • <nR> - Linear damping, yaw [kgm^2/s]
  • <xUabsU> - Quadratic abs damping, surge [kg/m]
  • <yVabsV> - Quadratic abs damping, sway [kg/m]
  • <zWabsW> - Quadratic abs damping, heave [kg/m]
  • <kPabsP> - Quadratic abs damping, roll [kgm^2/rad^2]
  • <mQabsQ> - Quadratic abs damping, pitch [kgm^2/rad^2]
  • <nRabsR> - Quadratic abs damping, yaw [kgm^2/rad^2]

Cross terms and off-diagonal entries follow the same pattern:

  • Linear: <{x|y|z|k|m|n}{U|V|W|P|Q|R}> e.g. <xR>
  • Quadratic abs (recommended): <{x|y|z|k|m|n}{U|V|W|P|Q|R}abs{U|V|W|P|Q|R}> e.g. <xRabsQ>
  • Quadratic (may cause oscillations): <{x|y|z|k|m|n}{U|V|W|P|Q|R}{U|V|W|P|Q|R}> e.g. <xRQ>

All damping coefficients default to 0.

Added Mass (Deprecated with DART)

Plugin-based added mass uses explicit integration, which is only conditionally stable. When using the DART physics engine, migrate to the SDF <fluid_added_mass> tag instead (see above). Other physics engines (Bullet, MuJoCo) do not support native added mass, so plugin-based parameters are the only option.

Do not set added mass in both places simultaneously. If both <fluid_added_mass> and plugin parameters are active, forces are double-counted.

To suppress the deprecation warning, set <disable_added_mass> to true.

Legacy parameters (Fossen sign convention, values should be negative):

  • <xDotU> - Added mass, surge [kg]
  • <yDotV> - Added mass, sway [kg]
  • <zDotW> - Added mass, heave [kg]
  • <kDotP> - Added mass, roll [kgm^2]
  • <mDotQ> - Added mass, pitch [kgm^2]
  • <nDotR> - Added mass, yaw [kgm^2]
  • Cross terms: <{x|y|z|k|m|n}Dot{U|V|W|P|Q|R}> e.g. <xDotR>

Ocean Current

  • <default_current> - Constant current velocity in world frame. [gz::math::Vector3d, default: 0 0 0, m/s]
  • <namespace> - If set, the plugin subscribes to /model/<namespace>/ocean_current instead of /ocean_current. Useful for per-vehicle currents in multi-robot scenarios. [string, optional]

Currents can also be loaded from data files via the EnvironmentPreload system. If any lookup_current_* tag is present, topic-based currents are ignored:

  • <lookup_current_x> - CSV column for x current [string]
  • <lookup_current_y> - CSV column for y current [string]
  • <lookup_current_z> - CSV column for z current [string]

Feature Flags

  • <disable_coriolis> - Disable the plugin's legacy Coriolis force. Note: does not disable the implicit Coriolis from <fluid_added_mass>. [bool, default: false]
  • <disable_added_mass> - Disable the plugin's legacy added mass force. [bool, default: false]

Example

Recommended configuration using <fluid_added_mass> on the link (handled by the physics engine) and this plugin for damping:

<link name="base_link">
<inertial>
<mass>147.8671</mass>
<fluid_added_mass>
<xx>4.876161</xx>
<yy>126.324739</yy>
<zz>126.324739</zz>
<qq>33.46</qq>
<rr>33.46</rr>
</fluid_added_mass>
</inertial>
</link>
<plugin filename="gz-sim-hydrodynamics-system"
name="systems::Hydrodynamics">
<link_name>base_link</link_name>
<xUabsU>-6.2282</xUabsU>
<yVabsV>-601.27</yVabsV>
<zWabsW>-601.27</zWabsW>
<kPabsP>-0.1916</kPabsP>
<mQabsQ>-632.698957</mQabsQ>
<nRabsR>-632.698957</nRabsR>
</plugin>

A complete working example is available in examples/worlds/auv_controls.sdf. Run it with:

gz sim auv_controls.sdf

References

[1] Fossen, T. I. "Guidance and Control of Ocean Vehicles." Wiley, 1994. [2] Fossen, T. I. "Handbook of Marine Craft Hydrodynamics and Motion Control." Wiley, 2011.

Constructor & Destructor Documentation

◆ Hydrodynamics()

Constructor.

◆ ~Hydrodynamics()

~Hydrodynamics ( )
override

Destructor.

Member Function Documentation

◆ Configure()

void Configure ( const Entity _entity,
const std::shared_ptr< const sdf::Element > &  _sdf,
EntityComponentManager _ecm,
EventManager  
)
overridevirtual

Documentation inherited.

Implements ISystemConfigure.

◆ PostUpdate()

void PostUpdate ( const UpdateInfo _info,
const EntityComponentManager _ecm 
)
overridevirtual

Documentation inherited.

Implements ISystemPostUpdate.

◆ PreUpdate()

void PreUpdate ( const UpdateInfo _info,
EntityComponentManager _ecm 
)
overridevirtual

Documentation inherited.

Implements ISystemPreUpdate.

◆ Reset()

void Reset ( const UpdateInfo _info,
EntityComponentManager _ecm 
)
overridevirtual

Documentation inherited.

Implements ISystemReset.


The documentation for this class was generated from the following file: