Public Member Functions | Static Public Member Functions | Protected Member Functions | Protected Attributes | Static Protected Attributes | List of all members
gazebo::HMFossen Class Reference

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: More...

#include <HydrodynamicModel.hh>

Inheritance diagram for gazebo::HMFossen:
Inheritance graph
[legend]

Public Member Functions

virtual void ApplyHydrodynamicForces (double time, const ignition::math::Vector3d &_flowVelWorld)
 Computation of the hydrodynamic forces. More...
 
virtual bool GetParam (std::string _tag, std::vector< double > &_output)
 Return paramater in vector form for the given tag. More...
 
virtual bool GetParam (std::string _tag, double &_output)
 Return paramater in scalar form for the given tag. More...
 
virtual std::string GetType ()
 Return (derived) type of hydrodynamic model. More...
 
virtual void Print (std::string _paramName, std::string _message=std::string())
 Prints parameters. More...
 
virtual bool SetParam (std::string _tag, double _input)
 Set scalar parameter. More...
 
- Public Member Functions inherited from gazebo::BuoyantObject
void ApplyBuoyancyForce ()
 Applies buoyancy force on link. More...
 
 BuoyantObject (physics::LinkPtr _link)
 Constructor. More...
 
void GetBuoyancyForce (const ignition::math::Pose3d &_pose, ignition::math::Vector3d &buoyancyForce, ignition::math::Vector3d &buoyancyTorque)
 Returns the buoyancy force vector in the world frame. More...
 
ignition::math::Vector3d GetCoB ()
 Returns the stored center of buoyancy. More...
 
bool GetDebugFlag ()
 Returns the debug flag. More...
 
double GetFluidDensity ()
 Returns the stored fluid density. More...
 
double GetGravity ()
 Get stored acceleration of gravity. More...
 
ignition::math::Vector3d GetStoredVector (std::string _tag)
 Get vector from the hydroWrench map. More...
 
double GetVolume ()
 Returns the stored link submerged volume. More...
 
bool IsNeutrallyBuoyant ()
 Returns true if the link was set to be neutrally buoyant. More...
 
bool IsSubmerged ()
 Returns true if the robot is completely submerged. More...
 
void SetBoundingBox (const ignition::math::Box &_bBox)
 Sets bounding box. More...
 
void SetCoB (const ignition::math::Vector3d &_centerOfBuoyancy)
 Sets the position of the center of buoyancy on the body frame. More...
 
void SetDebugFlag (bool _debugOn=true)
 Set debug flag to store intermediate forces and torques. More...
 
void SetFluidDensity (double _fluidDensity)
 Sets the fluid density in kg/m^3. More...
 
void SetGravity (double _g)
 Set acceleration of gravity. More...
 
void SetNeutrallyBuoyant ()
 Sets this link as neutrally buoyant. More...
 
void SetStoreVector (std::string _tag)
 Adds a field in the hydroWrench map. More...
 
void SetVolume (double _volume=-1)
 Sets the link's submerged volume. More...
 
 ~BuoyantObject ()
 Destructor. More...
 

Static Public Member Functions

static HydrodynamicModelcreate (sdf::ElementPtr _sdf, physics::LinkPtr _link)
 Create model of this type with parameter values from sdf. More...
 

Protected Member Functions

void ComputeAddedCoriolisMatrix (const Eigen::Vector6d &_vel, const Eigen::Matrix6d &_Ma, Eigen::Matrix6d &_Ca) const
 Computes the added-mass Coriolis matrix Ca. More...
 
void ComputeDampingMatrix (const Eigen::Vector6d &_vel, Eigen::Matrix6d &_D) const
 Updates the damping matrix for the current velocity. More...
 
Eigen::Matrix6d GetAddedMass () const
 Returns the added-mass matrix with the scaling and offset. More...
 
 HMFossen (sdf::ElementPtr _sdf, physics::LinkPtr _link)
 
 REGISTER_HYDRODYNAMICMODEL (HMFossen)
 Register this model with the factory. More...
 
- Protected Member Functions inherited from gazebo::HydrodynamicModel
bool CheckParams (sdf::ElementPtr _sdf)
 Returns true if all parameters are available from the SDF element. More...
 
void ComputeAcc (Eigen::Vector6d _velRel, double _time, double _alpha=0.3)
 Filter acceleration (fix due to the update structure of Gazebo) More...
 
ignition::math::Vector3d FromNED (ignition::math::Vector3d _vec)
 Convert vector to comply with the NED reference frame. More...
 
 HydrodynamicModel (sdf::ElementPtr _sdf, physics::LinkPtr _link)
 Protected constructor: Use the factory for object creation. More...
 
ignition::math::Vector3d ToNED (ignition::math::Vector3d _vec)
 Convert vector to comply with the NED reference frame. More...
 
- Protected Member Functions inherited from gazebo::BuoyantObject
void StoreVector (std::string _tag, ignition::math::Vector3d _vec)
 Store vector in the hydroWrench map if the field has been created. More...
 

Protected Attributes

Eigen::Matrix6d Ca
 Added-mass associated Coriolis matrix. More...
 
Eigen::Matrix6d D
 Damping matrix. More...
 
Eigen::Matrix6d DLin
 Linear damping matrix. More...
 
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. More...
 
Eigen::Matrix6d DNonLin
 Nonlinear damping coefficients. More...
 
std::vector< double > linearDampCoef
 Linear damping coefficients. More...
 
Eigen::Matrix6d Ma
 Added-mass matrix. More...
 
double offsetAddedMass
 Offset for the added-mass matrix. More...
 
double offsetLinearDamping
 Offset for the linear damping matrix. More...
 
double offsetLinForwardSpeedDamping
 Offset for the linear damping matrix. More...
 
double offsetNonLinDamping
 Offset for the linear damping matrix. More...
 
std::vector< double > quadDampCoef
 Quadratic damping coefficients. More...
 
double scalingAddedMass
 Scaling of the added-mass matrix. More...
 
double scalingDamping
 Scaling of the damping matrix. More...
 
- Protected Attributes inherited from gazebo::HydrodynamicModel
Eigen::Vector6d filteredAcc
 Filtered linear & angular acceleration vector in link frame. This is used to prevent the model to become unstable given that Gazebo only calls the update function at the beginning or at the end of a iteration of the physics engine. More...
 
double lastTime
 Last timestamp (in seconds) at which ApplyHydrodynamicForces was called. More...
 
Eigen::Vector6d lastVelRel
 Last body-fixed relative velocity (nu_R in Fossen's equations) More...
 
std::vector< std::string > params
 List of parameters needed from the SDF element. More...
 
double Re
 Reynolds number (not used by all models) More...
 
double temperature
 Temperature (not used by all models) More...
 
- Protected Attributes inherited from gazebo::BuoyantObject
ignition::math::Box boundingBox
 TEMP for calculation of the buoyancy force close to the surface. More...
 
ignition::math::Vector3d centerOfBuoyancy
 Center of buoyancy in the body frame. More...
 
bool debugFlag
 Debug flag, storing all intermediate forces and torques. More...
 
double fluidDensity
 Fluid density. More...
 
double g
 Acceleration of gravity. More...
 
std::map< std::string, ignition::math::Vector3d > hydroWrench
 Storage for hydrodynamic and hydrostatic forces and torques for debugging purposes. More...
 
bool isSubmerged
 Is submerged flag. More...
 
bool isSurfaceVessel
 Flag set to true if the information about the metacentric width and height is available. More...
 
bool isSurfaceVesselFloating
 Flag set to true if the vessel has reached its submerged height. More...
 
physics::LinkPtr link
 Pointer to the correspondent robot link. More...
 
double metacentricLength
 Metacentric length of the robot, used only for surface vessels and floating objects. More...
 
double metacentricWidth
 
bool neutrallyBuoyant
 If true, the restoring force will be equal to the gravitational. More...
 
double offsetVolume
 Offset for the volume. More...
 
double scalingVolume
 Scaling factor for the volume. More...
 
double submergedHeight
 Height of the robot that is submerged (only for surface vessels) More...
 
double volume
 Volume of fluid displaced by the submerged object. More...
 
double waterLevelPlaneArea
 If the cross section area around water level of the surface vessel is not given, it will be computed from the object's bounding box. More...
 

Static Protected Attributes

static const std::string IDENTIFIER = "fossen"
 Unique identifier for this geometry. More...
 

Detailed Description

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:

Definition at line 153 of file HydrodynamicModel.hh.

Constructor & Destructor Documentation

gazebo::HMFossen::HMFossen ( sdf::ElementPtr  _sdf,
physics::LinkPtr  _link 
)
protected

Definition at line 223 of file HydrodynamicModel.cc.

Member Function Documentation

void gazebo::HMFossen::ApplyHydrodynamicForces ( double  time,
const ignition::math::Vector3d &  _flowVelWorld 
)
virtual

Computation of the hydrodynamic forces.

Implements gazebo::HydrodynamicModel.

Definition at line 360 of file HydrodynamicModel.cc.

void gazebo::HMFossen::ComputeAddedCoriolisMatrix ( const Eigen::Vector6d _vel,
const Eigen::Matrix6d _Ma,
Eigen::Matrix6d _Ca 
) const
protected

Computes the added-mass Coriolis matrix Ca.

Definition at line 449 of file HydrodynamicModel.cc.

void gazebo::HMFossen::ComputeDampingMatrix ( const Eigen::Vector6d _vel,
Eigen::Matrix6d _D 
) const
protected

Updates the damping matrix for the current velocity.

Definition at line 463 of file HydrodynamicModel.cc.

HydrodynamicModel * gazebo::HMFossen::create ( sdf::ElementPtr  _sdf,
physics::LinkPtr  _link 
)
static

Create model of this type with parameter values from sdf.

Definition at line 216 of file HydrodynamicModel.cc.

Eigen::Matrix6d gazebo::HMFossen::GetAddedMass ( ) const
protected

Returns the added-mass matrix with the scaling and offset.

Definition at line 490 of file HydrodynamicModel.cc.

bool gazebo::HMFossen::GetParam ( std::string  _tag,
std::vector< double > &  _output 
)
virtual

Return paramater in vector form for the given tag.

Implements gazebo::HydrodynamicModel.

Definition at line 497 of file HydrodynamicModel.cc.

bool gazebo::HMFossen::GetParam ( std::string  _tag,
double &  _output 
)
virtual

Return paramater in scalar form for the given tag.

Implements gazebo::HydrodynamicModel.

Definition at line 540 of file HydrodynamicModel.cc.

virtual std::string gazebo::HMFossen::GetType ( )
inlinevirtual

Return (derived) type of hydrodynamic model.

Implements gazebo::HydrodynamicModel.

Reimplemented in gazebo::HMBox, gazebo::HMSpheroid, gazebo::HMCylinder, and gazebo::HMSphere.

Definition at line 160 of file HydrodynamicModel.hh.

void gazebo::HMFossen::Print ( std::string  _paramName,
std::string  _message = std::string() 
)
virtual

Prints parameters.

Implements gazebo::HydrodynamicModel.

Reimplemented in gazebo::HMBox, gazebo::HMSpheroid, gazebo::HMCylinder, and gazebo::HMSphere.

Definition at line 625 of file HydrodynamicModel.cc.

gazebo::HMFossen::REGISTER_HYDRODYNAMICMODEL ( HMFossen  )
protected

Register this model with the factory.

bool gazebo::HMFossen::SetParam ( std::string  _tag,
double  _input 
)
virtual

Set scalar parameter.

Implements gazebo::HydrodynamicModel.

Definition at line 581 of file HydrodynamicModel.cc.

Member Data Documentation

Eigen::Matrix6d gazebo::HMFossen::Ca
protected

Added-mass associated Coriolis matrix.

Definition at line 210 of file HydrodynamicModel.hh.

Eigen::Matrix6d gazebo::HMFossen::D
protected

Damping matrix.

Definition at line 213 of file HydrodynamicModel.hh.

Eigen::Matrix6d gazebo::HMFossen::DLin
protected

Linear damping matrix.

Definition at line 228 of file HydrodynamicModel.hh.

Eigen::Matrix6d gazebo::HMFossen::DLinForwardSpeed
protected

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

Definition at line 237 of file HydrodynamicModel.hh.

Eigen::Matrix6d gazebo::HMFossen::DNonLin
protected

Nonlinear damping coefficients.

Definition at line 240 of file HydrodynamicModel.hh.

const std::string gazebo::HMFossen::IDENTIFIER = "fossen"
staticprotected

Unique identifier for this geometry.

Definition at line 180 of file HydrodynamicModel.hh.

std::vector<double> gazebo::HMFossen::linearDampCoef
protected

Linear damping coefficients.

Definition at line 243 of file HydrodynamicModel.hh.

Eigen::Matrix6d gazebo::HMFossen::Ma
protected

Added-mass matrix.

Definition at line 201 of file HydrodynamicModel.hh.

double gazebo::HMFossen::offsetAddedMass
protected

Offset for the added-mass matrix.

Definition at line 207 of file HydrodynamicModel.hh.

double gazebo::HMFossen::offsetLinearDamping
protected

Offset for the linear damping matrix.

Definition at line 219 of file HydrodynamicModel.hh.

double gazebo::HMFossen::offsetLinForwardSpeedDamping
protected

Offset for the linear damping matrix.

Definition at line 222 of file HydrodynamicModel.hh.

double gazebo::HMFossen::offsetNonLinDamping
protected

Offset for the linear damping matrix.

Definition at line 225 of file HydrodynamicModel.hh.

std::vector<double> gazebo::HMFossen::quadDampCoef
protected

Quadratic damping coefficients.

Definition at line 246 of file HydrodynamicModel.hh.

double gazebo::HMFossen::scalingAddedMass
protected

Scaling of the added-mass matrix.

Definition at line 204 of file HydrodynamicModel.hh.

double gazebo::HMFossen::scalingDamping
protected

Scaling of the damping matrix.

Definition at line 216 of file HydrodynamicModel.hh.


The documentation for this class was generated from the following files:


uuv_gazebo_plugins
Author(s): Musa Morena Marcusso Manhaes , Sebastian Scherer , Luiz Ricardo Douat
autogenerated on Thu Jun 18 2020 03:28:24