Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Updating hydrodynamics plugin description #1502

Merged
merged 3 commits into from
May 23, 2022
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
2 changes: 1 addition & 1 deletion src/systems/hydrodynamics/Hydrodynamics.cc
Original file line number Diff line number Diff line change
Expand Up @@ -251,7 +251,7 @@ void Hydrodynamics::Configure(

if (!_sdf->HasElement("link_name"))
{
ignerr << "You musk specify a <link_name> for the hydrodynamic"
ignerr << "You must specify a <link_name> for the hydrodynamic"
<< " plugin to act upon";
return;
}
Expand Down
30 changes: 15 additions & 15 deletions src/systems/hydrodynamics/Hydrodynamics.hh
Original file line number Diff line number Diff line change
Expand Up @@ -41,27 +41,27 @@ namespace systems
/// plugin), etc.
///
/// # System Parameters
/// The exact description of these parameters can be found on p. 37 of
/// Fossen's book. They are used to calculate added mass, linear and quadratic
/// drag and coriolis force.
/// The exact description of these parameters can be found on p. 37 and
/// p. 43 of Fossen's book. They are used to calculate added mass, linear and
/// quadratic drag and coriolis force.
/// * <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]
/// * <xUU> - Stability derivative, 2nd order, x component [kg/m]
/// * <xU> - Stability derivative, 1st order, x component [kg]
/// * <yVV> - Stability derivative, 2nd order, y component [kg/m]
/// * <yV> - Stability derivative, 1st order, y component [kg]
/// * <zWW> - Stability derivative, 2nd order, z component [kg/m]
/// * <zW> - Stability derivative, 1st order, z component [kg]
/// * <kPP> - Stability derivative, 2nd order, roll component [kg/m^2]
/// * <kP> - Stability derivative, 1st order, roll component [kg/m]
/// * <mQQ> - Stability derivative, 2nd order, pitch component [kg/m^2]
/// * <mQ> - Stability derivative, 1st order, pitch component [kg/m]
/// * <nRR> - Stability derivative, 2nd order, yaw component [kg/m^2]
/// * <nR> - Stability derivative, 1st order, yaw component [kg/m]
/// * <xUU> - Quadratic damping, 2nd order, x component [kg/m]
/// * <xU> - Linear damping, 1st order, x component [kg]
/// * <yVV> - Quadratic damping, 2nd order, y component [kg/m]
/// * <yV> - Linear damping, 1st order, y component [kg]
/// * <zWW> - Quadratic damping, 2nd order, z component [kg/m]
/// * <zW> - Linear damping, 1st order, z component [kg]
/// * <kPP> - Quadratic damping, 2nd order, roll component [kg/m^2]
/// * <kP> - Linear damping, 1st order, roll component [kg/m]
/// * <mQQ> - Quadratic damping, 2nd order, pitch component [kg/m^2]
/// * <mQ> - Linear damping, 1st order, pitch component [kg/m]
/// * <nRR> - Quadratic damping, 2nd order, yaw component [kg/m^2]
/// * <nR> - Linear damping, 1st order, yaw component [kg/m]
/// Additionally the system also supports the following parameters:
/// * <waterDensity> - The density of the fluid its moving in.
/// Defaults to 998kgm^-3. [kgm^-3, deprecated]
Expand Down