Gazebo Sim

API Reference

10.1.1
gz::sim::systems::hydrodynamics Namespace Reference

Functions

Eigen::Matrix< double, 6, 6 > buildCoriolisMatrix (const Eigen::Matrix< double, 6, 6 > &_Ma, const Eigen::Matrix< double, 6, 1 > &_state)
 Build the negated added-mass Coriolis matrix (-C_A) per Fossen (2011) Theorem 6.2, eq 6.43.
 
Eigen::Matrix< double, 6, 6 > buildDampingMatrix (const double(&_linearTerms)[36], const double(&_quadAbsDerivs)[216], const double(&_quadDerivs)[216], const Eigen::Matrix< double, 6, 1 > &_state)
 Build the hydrodynamic damping matrix from linear and quadratic stability derivatives.
 
Eigen::Matrix< double, 6, 6 > buildFullCoriolisMatrix (const Eigen::Matrix< double, 6, 6 > &_Ma, const Eigen::Matrix< double, 6, 1 > &_state)
 Build the added-mass Coriolis matrix C_A(v) for a full (non-diagonal) 6x6 added mass matrix, per Fossen (2011) eq. 6.43.
 
Eigen::Matrix3d skew3 (const Eigen::Vector3d &_v)
 3x3 skew-symmetric (cross-product) matrix from a 3-vector.
 

Function Documentation

◆ buildCoriolisMatrix()

Eigen::Matrix< double, 6, 6 > buildCoriolisMatrix ( const Eigen::Matrix< double, 6, 6 > &  _Ma,
const Eigen::Matrix< double, 6, 1 > &  _state 
)
inline

Build the negated added-mass Coriolis matrix (-C_A) per Fossen (2011) Theorem 6.2, eq 6.43.

Uses only diagonal elements of _Ma. The returned matrix is skew-symmetric: C + C^T = 0. The Fossen sign convention is that diagonal elements of _Ma are negative (e.g. X_u_dot < 0).

Parameters
[in]_Ma6x6 added mass matrix
[in]_state6x1 body-frame velocity [u,v,w,p,q,r]
Returns
6x6 matrix equal to -C_A (skew-symmetric)

◆ buildDampingMatrix()

Eigen::Matrix< double, 6, 6 > buildDampingMatrix ( const double(&)  _linearTerms[36],
const double(&)  _quadAbsDerivs[216],
const double(&)  _quadDerivs[216],
const Eigen::Matrix< double, 6, 1 > &  _state 
)
inline

Build the hydrodynamic damping matrix from linear and quadratic stability derivatives.

For each (i,j) entry the coefficient is: D(i,j) = -linear[i*6+j]

  • sum_k( quadAbs[i*36+j*6+k] * |state(k)| )
  • sum_k( quad[i*36+j*6+k] * state(k) )

The damping force is then D * state.

Parameters
[in]_linearTerms36-element array of linear damping coefficients
[in]_quadAbsDerivs216-element array of |v|-quadratic damping
[in]_quadDerivs216-element array of v-quadratic damping
[in]_state6x1 body-frame velocity [u,v,w,p,q,r]
Returns
6x6 damping matrix D

◆ buildFullCoriolisMatrix()

Eigen::Matrix< double, 6, 6 > buildFullCoriolisMatrix ( const Eigen::Matrix< double, 6, 6 > &  _Ma,
const Eigen::Matrix< double, 6, 1 > &  _state 
)
inline

Build the added-mass Coriolis matrix C_A(v) for a full (non-diagonal) 6x6 added mass matrix, per Fossen (2011) eq. 6.43.

This function uses the physical (positive) sign convention for M_A, matching the SDF <fluid_added_mass> specification.

Given: M_A = | M11 M12 | v = | v1 | (v1 = linear, v2 = angular) | M21 M22 | | v2 |

The Coriolis matrix is: C_A(v) = | 0 -S(M11*v1 + M12*v2) | | -S(M11*v1+M12*v2) -S(M21*v1 + M22*v2) |

The returned matrix is skew-symmetric: C_A + C_A^T = 0.

Parameters
[in]_Ma6x6 added mass matrix (positive physical values)
[in]_state6x1 body-frame velocity [u,v,w,p,q,r]
Returns
6x6 Coriolis matrix C_A (skew-symmetric)

References skew3().

◆ skew3()

Eigen::Matrix3d skew3 ( const Eigen::Vector3d &  _v)
inline

3x3 skew-symmetric (cross-product) matrix from a 3-vector.

S(v) * x = v x x (cross product)

Parameters
[in]_v3-vector
Returns
3x3 skew-symmetric matrix

Referenced by buildFullCoriolisMatrix().