Skip to content

Commit

Permalink
Deprecate use of added mass via hydrodynamics (#2493)
Browse files Browse the repository at this point in the history
* Deprecate use of added mass via hydrodynamics

I believe we should deprecate this option as it has instabilities. The
`fluid_added_mass` approach is superior. We should update our tutorials
as well.

---------

Signed-off-by: Arjo Chakravarty <[email protected]>
Co-authored-by: Carlos Agüero <[email protected]>
  • Loading branch information
arjo129 and caguero authored Aug 12, 2024
1 parent 811d4d0 commit 5c4f0cf
Show file tree
Hide file tree
Showing 2 changed files with 28 additions and 9 deletions.
18 changes: 17 additions & 1 deletion src/systems/hydrodynamics/Hydrodynamics.cc
Original file line number Diff line number Diff line change
Expand Up @@ -340,7 +340,11 @@ void Hydrodynamics::Configure(
<< "\thttps://github.com/gazebosim/gz-sim/pull/1888" << std::endl;
}


// Added mass according to Fossen's equations (p 37)
// Note: Adding added mass here is deprecated and will be removed in
// Gazebo J as this formulation has instabilities.
bool addedMassSpecified = false;
this->dataPtr->Ma = Eigen::MatrixXd::Zero(6, 6);
for(auto i = 0; i < 6; i++)
{
Expand All @@ -350,12 +354,24 @@ void Hydrodynamics::Configure(
prefix += "Dot";
prefix += snameConventionVel[j];
this->dataPtr->Ma(i, j) = SdfParamDouble(_sdf, prefix, 0);
addedMassSpecified = (std::abs(this->dataPtr->Ma(i, j)) > 1e-6)
&& addedMassSpecified;
}
}

_sdf->Get<bool>("disable_coriolis", this->dataPtr->disableCoriolis, false);
_sdf->Get<bool>("disable_added_mass", this->dataPtr->disableAddedMass, false);

if (!this->dataPtr->disableAddedMass || addedMassSpecified)
{
gzerr << "The use of added mass through this plugin is deprecated and will"
<< "be removed in Gazebo J* as this formulation has instabilities."
<< " We recommend using the SDF `<fluid_added_mass>` tag based method"
<< "[http://sdformat.org/spec?ver=1.11&elem=link"
<< "#inertial_fluid_added_mass]"
<< "To get rid of this warning we recommend setting"
<< "`<disable_added_mass> to true."
<< std::endl;
}
// Create model object, to access convenient functions
auto model = gz::sim::Model(_entity);

Expand Down
19 changes: 11 additions & 8 deletions src/systems/hydrodynamics/Hydrodynamics.hh
Original file line number Diff line number Diff line change
Expand Up @@ -46,12 +46,12 @@ namespace systems
/// quadratic drag and coriolis force.
///
/// ### Diagonal terms:
/// * <xDotU> - Added mass in x direction [kg]
/// * <yDotV> - Added mass in y direction [kg]
/// * <zDotW> - Added mass in z direction [kg]
/// * <kDotP> - Added mass in roll direction [kgm^2]
/// * <mDotQ> - Added mass in pitch direction [kgm^2]
/// * <nDotR> - Added mass in yaw direction [kgm^2]
/// * <xDotU> - (Deprecated) Added mass in x direction [kg]
/// * <yDotV> - (Deprecated) Added mass in y direction [kg]
/// * <zDotW> - (Deprecated) Added mass in z direction [kg]
/// * <kDotP> - (Deprecated) Added mass in roll direction [kgm^2]
/// * <mDotQ> - (Deprecated) Added mass in pitch direction [kgm^2]
/// * <nDotR> - (Deprecated) Added mass in yaw direction [kgm^2]
/// * <xUabsU> - Quadratic damping, 2nd order, x component [kg/m]
/// * <xU> - Linear damping, 1st order, x component [kg]
/// * <yVabsV> - Quadratic damping, 2nd order, y component [kg/m]
Expand All @@ -70,10 +70,13 @@ namespace systems
/// non-diagonal sides. We use the SNAMe convention of naming search terms.
/// (x, y, z) correspond to the respective axis. (k, m, n) correspond to
/// roll, pitch and yaw. Similarly U, V, W represent velocity vectors in
/// X, Y and Z axis while P, Q, R representangular velocity in roll, pitch
/// X, Y and Z axis while P, Q, R represent angular velocity in roll, pitch
/// and yaw axis respectively.
/// * Added Mass: <{x|y|z|k|m|n}Dot{U|V|W|P|Q|R}> e.g. <xDotR>
/// Units are either kg or kgm^2 depending on the choice of terms.
/// (Deprecated) Units are either kg or kgm^2 depending on the
/// choice of terms. You should use the sdf method based spec
// for `fluid_added_mass`:
/// http://sdformat.org/spec?ver=1.11&elem=link#inertial_fluid_added_mass
/// * Quadratic Damping With abs term (this is probably what you want):
/// <{x|y|z|k|m|n}{U|V|W|P|Q|R}abs{U|V|W|P|Q|R}>
/// e.g. <xRabsQ>
Expand Down

0 comments on commit 5c4f0cf

Please sign in to comment.