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::string GetType () |
Return (derived) type of hydrodynamic model. |
public virtual void Print (std::string _paramName,std::string _message) |
Prints parameters. |
public virtual bool GetParam (std::string _tag,std::vector< double > & _output) |
Return paramater in vector form for the given tag. |
public virtual bool GetParam (std::string _tag,double & _output) |
Return paramater in scalar form for the given tag. |
public virtual bool SetParam (std::string _tag,double _input) |
Set scalar parameter. |
public virtual void ApplyHydrodynamicForces (double time,const ignition::math::Vector3d & _flowVelWorld) |
Computation of the hydrodynamic forces. |
protected Eigen::Matrix6d
Ma |
Added-mass matrix. |
protected double scalingAddedMass |
Scaling of the added-mass matrix. |
protected double offsetAddedMass |
Offset for the added-mass matrix. |
protected Eigen::Matrix6d
Ca |
Added-mass associated Coriolis matrix. |
protected Eigen::Matrix6d
D |
Damping matrix. |
protected double scalingDamping |
Scaling of the damping matrix. |
protected double offsetLinearDamping |
Offset for the linear damping matrix. |
protected double offsetLinForwardSpeedDamping |
Offset for the linear damping matrix. |
protected double offsetNonLinDamping |
Offset for the linear damping matrix. |
protected Eigen::Matrix6d
DLin |
Linear damping matrix. |
protected Eigen::Matrix6d
DLinForwardSpeed |
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. |
protected Eigen::Matrix6d
DNonLin |
Nonlinear damping coefficients. |
protected std::vector< double > linearDampCoef |
Linear damping coefficients. |
protected std::vector< double > quadDampCoef |
Quadratic damping coefficients. |
protected REGISTER_HYDRODYNAMICMODEL ( HMFossen ) |
Register this model with the factory. |
protected HMFossen (sdf::ElementPtr _sdf,physics::LinkPtr _link) |
|
protected void ComputeAddedCoriolisMatrix (const Eigen::Vector6d & _vel,const Eigen::Matrix6d & _Ma, Eigen::Matrix6d & _Ca) const |
Computes the added-mass Coriolis matrix Ca. |
protected void ComputeDampingMatrix (const Eigen::Vector6d & _vel, Eigen::Matrix6d & _D) const |
Updates the damping matrix for the current velocity. |
protected Eigen::Matrix6d
GetAddedMass () const |
Returns the added-mass matrix with the scaling and offset. |
Members¶
public inline virtual std::string
GetType
()
¶
Return (derived) type of hydrodynamic model.
public virtual void
Print
(std::string _paramName,std::string _message)
¶
Prints parameters.
public virtual bool
GetParam
(std::string _tag,std::vector< double > & _output)
¶
Return paramater in vector form for the given tag.
public virtual bool
GetParam
(std::string _tag,double & _output)
¶
Return paramater in scalar form for the given tag.
public virtual bool
SetParam
(std::string _tag,double _input)
¶
Set scalar parameter.
public virtual void
ApplyHydrodynamicForces
(double time,const ignition::math::Vector3d & _flowVelWorld)
¶
Computation of the hydrodynamic forces.
protected
Eigen::Matrix6d
Ma
¶
Added-mass matrix.
protected double
scalingAddedMass
¶
Scaling of the added-mass matrix.
protected double
offsetAddedMass
¶
Offset for the added-mass matrix.
protected
Eigen::Matrix6d
Ca
¶
Added-mass associated Coriolis matrix.
protected
Eigen::Matrix6d
D
¶
Damping matrix.
protected double
scalingDamping
¶
Scaling of the damping matrix.
protected double
offsetLinearDamping
¶
Offset for the linear damping matrix.
protected double
offsetLinForwardSpeedDamping
¶
Offset for the linear damping matrix.
protected double
offsetNonLinDamping
¶
Offset for the linear damping matrix.
protected
Eigen::Matrix6d
DLin
¶
Linear damping matrix.
protected
Eigen::Matrix6d
DLinForwardSpeed
¶
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
protected
Eigen::Matrix6d
DNonLin
¶
Nonlinear damping coefficients.
protected std::vector< double >
linearDampCoef
¶
Linear damping coefficients.
protected std::vector< double >
quadDampCoef
¶
Quadratic damping coefficients.
protected
REGISTER_HYDRODYNAMICMODEL
(
HMFossen
)
¶
Register this model with the factory.
protected
HMFossen
(sdf::ElementPtr _sdf,physics::LinkPtr _link)
¶
protected void
ComputeAddedCoriolisMatrix
(const
Eigen::Vector6d
& _vel,const
Eigen::Matrix6d
& _Ma,
Eigen::Matrix6d
& _Ca) const
¶
Computes the added-mass Coriolis matrix Ca.
protected void
ComputeDampingMatrix
(const
Eigen::Vector6d
& _vel,
Eigen::Matrix6d
& _D) const
¶
Updates the damping matrix for the current velocity.
protected
Eigen::Matrix6d
GetAddedMass
() const
¶
Returns the added-mass matrix with the scaling and offset.