HMFossen
class gazebo::HMFossen¶
class gazebo::HMFossen : public gazebo::HydrodynamicModel
Class containting the methods and attributes for a Fossen robot-like hydrodynamic model. The restoring forces are applied by the BuoyantObject class methods. Using the plugin for UUV models will use both this and the buoyant object class definitions, therefore the restoring forces were not inherited here. References:
- Fossen, Thor, "Handbook of Marine Craft and Hydrodynamics and Motion Control", 2011
Summary¶
| Members | Descriptions |
|---|---|
public inline virtual std::stringGetType() |
Return (derived) type of hydrodynamic model. |
public virtual voidPrint(std::string _paramName,std::string _message) |
Prints parameters. |
public virtual boolGetParam(std::string _tag,std::vector< double > & _output) |
Return paramater in vector form for the given tag. |
public virtual boolGetParam(std::string _tag,double & _output) |
Return paramater in scalar form for the given tag. |
public virtual boolSetParam(std::string _tag,double _input) |
Set scalar parameter. |
public virtual voidApplyHydrodynamicForces(double time,const ignition::math::Vector3d & _flowVelWorld) |
Computation of the hydrodynamic forces. |
protectedEigen::Matrix6dMa |
Added-mass matrix. |
protected doublescalingAddedMass |
Scaling of the added-mass matrix. |
protected doubleoffsetAddedMass |
Offset for the added-mass matrix. |
protectedEigen::Matrix6dCa |
Added-mass associated Coriolis matrix. |
protectedEigen::Matrix6dD |
Damping matrix. |
protected doublescalingDamping |
Scaling of the damping matrix. |
protected doubleoffsetLinearDamping |
Offset for the linear damping matrix. |
protected doubleoffsetLinForwardSpeedDamping |
Offset for the linear damping matrix. |
protected doubleoffsetNonLinDamping |
Offset for the linear damping matrix. |
protectedEigen::Matrix6dDLin |
Linear damping matrix. |
protectedEigen::Matrix6dDLinForwardSpeed |
Linear damping matrix proportional only to the forward speed (useful for modeling AUVs). From [1], according to Newman (1977), there is a damping force component that linearly increases with the presence of forward speed, particularly so for slender bodies. |
protectedEigen::Matrix6dDNonLin |
Nonlinear damping coefficients. |
protected std::vector< double >linearDampCoef |
Linear damping coefficients. |
protected std::vector< double >quadDampCoef |
Quadratic damping coefficients. |
protectedREGISTER_HYDRODYNAMICMODEL(HMFossen) |
Register this model with the factory. |
protectedHMFossen(sdf::ElementPtr _sdf,physics::LinkPtr _link) |
|
protected voidComputeAddedCoriolisMatrix(constEigen::Vector6d& _vel,constEigen::Matrix6d& _Ma,Eigen::Matrix6d& _Ca) const |
Computes the added-mass Coriolis matrix Ca. |
protected voidComputeDampingMatrix(constEigen::Vector6d& _vel,Eigen::Matrix6d& _D) const |
Updates the damping matrix for the current velocity. |
protectedEigen::Matrix6dGetAddedMass() const |
Returns the added-mass matrix with the scaling and offset. |
Members¶
public inline virtual std::stringGetType()¶
Return (derived) type of hydrodynamic model.
public virtual voidPrint(std::string _paramName,std::string _message)¶
Prints parameters.
public virtual boolGetParam(std::string _tag,std::vector< double > & _output)¶
Return paramater in vector form for the given tag.
public virtual boolGetParam(std::string _tag,double & _output)¶
Return paramater in scalar form for the given tag.
public virtual boolSetParam(std::string _tag,double _input)¶
Set scalar parameter.
public virtual voidApplyHydrodynamicForces(double time,const ignition::math::Vector3d & _flowVelWorld)¶
Computation of the hydrodynamic forces.
protectedEigen::Matrix6dMa¶
Added-mass matrix.
protected doublescalingAddedMass¶
Scaling of the added-mass matrix.
protected doubleoffsetAddedMass¶
Offset for the added-mass matrix.
protectedEigen::Matrix6dCa¶
Added-mass associated Coriolis matrix.
protectedEigen::Matrix6dD¶
Damping matrix.
protected doublescalingDamping¶
Scaling of the damping matrix.
protected doubleoffsetLinearDamping¶
Offset for the linear damping matrix.
protected doubleoffsetLinForwardSpeedDamping¶
Offset for the linear damping matrix.
protected doubleoffsetNonLinDamping¶
Offset for the linear damping matrix.
protectedEigen::Matrix6dDLin¶
Linear damping matrix.
protectedEigen::Matrix6dDLinForwardSpeed¶
Linear damping matrix proportional only to the forward speed (useful for modeling AUVs). From [1], according to Newman (1977), there is a damping force component that linearly increases with the presence of forward speed, particularly so for slender bodies.
References: [1] Refsnes - 2007 - Nonlinear model-based control of slender body AUVs
protectedEigen::Matrix6dDNonLin¶
Nonlinear damping coefficients.
protected std::vector< double >linearDampCoef¶
Linear damping coefficients.
protected std::vector< double >quadDampCoef¶
Quadratic damping coefficients.
protectedREGISTER_HYDRODYNAMICMODEL(HMFossen)¶
Register this model with the factory.
protectedHMFossen(sdf::ElementPtr _sdf,physics::LinkPtr _link)¶
protected voidComputeAddedCoriolisMatrix(constEigen::Vector6d& _vel,constEigen::Matrix6d& _Ma,Eigen::Matrix6d& _Ca) const¶
Computes the added-mass Coriolis matrix Ca.
protected voidComputeDampingMatrix(constEigen::Vector6d& _vel,Eigen::Matrix6d& _D) const¶
Updates the damping matrix for the current velocity.
protectedEigen::Matrix6dGetAddedMass() const¶
Returns the added-mass matrix with the scaling and offset.