Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
gazebo::HydrodynamicModel Class Referenceabstract

#include <HydrodynamicModel.hh>

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

Public Member Functions

virtual void ApplyHydrodynamicForces (double time, const ignition::math::Vector3d &_flowVelWorld)=0
 Computation of the hydrodynamic forces. More...
 
virtual bool GetParam (std::string _tag, std::vector< double > &_output)=0
 Return paramater in vector form for the given tag. More...
 
virtual bool GetParam (std::string _tag, double &_output)=0
 Return paramater in vector form for the given tag. More...
 
virtual std::string GetType ()=0
 Returns type of model. More...
 
virtual void Print (std::string _paramName, std::string _message=std::string())=0
 Prints parameters. More...
 
virtual bool SetParam (std::string _tag, double _input)=0
 Set a scalar parameters. 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...
 

Protected Member Functions

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

Detailed Description

Definition at line 42 of file HydrodynamicModel.hh.

Constructor & Destructor Documentation

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

Protected constructor: Use the factory for object creation.

Definition at line 22 of file HydrodynamicModel.cc.

Member Function Documentation

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

Computation of the hydrodynamic forces.

Implemented in gazebo::HMFossen.

bool gazebo::HydrodynamicModel::CheckParams ( sdf::ElementPtr  _sdf)
protected

Returns true if all parameters are available from the SDF element.

Definition at line 143 of file HydrodynamicModel.cc.

void gazebo::HydrodynamicModel::ComputeAcc ( Eigen::Vector6d  _velRel,
double  _time,
double  _alpha = 0.3 
)
protected

Filter acceleration (fix due to the update structure of Gazebo)

Definition at line 102 of file HydrodynamicModel.cc.

ignition::math::Vector3d gazebo::HydrodynamicModel::FromNED ( ignition::math::Vector3d  _vec)
protected

Convert vector to comply with the NED reference frame.

Definition at line 137 of file HydrodynamicModel.cc.

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

Return paramater in vector form for the given tag.

Implemented in gazebo::HMFossen.

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

Return paramater in vector form for the given tag.

Implemented in gazebo::HMFossen.

virtual std::string gazebo::HydrodynamicModel::GetType ( )
pure virtual
virtual void gazebo::HydrodynamicModel::Print ( std::string  _paramName,
std::string  _message = std::string() 
)
pure virtual
virtual bool gazebo::HydrodynamicModel::SetParam ( std::string  _tag,
double  _input 
)
pure virtual

Set a scalar parameters.

Implemented in gazebo::HMFossen.

ignition::math::Vector3d gazebo::HydrodynamicModel::ToNED ( ignition::math::Vector3d  _vec)
protected

Convert vector to comply with the NED reference frame.

Definition at line 128 of file HydrodynamicModel.cc.

Member Data Documentation

Eigen::Vector6d gazebo::HydrodynamicModel::filteredAcc
protected

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.

Definition at line 87 of file HydrodynamicModel.hh.

double gazebo::HydrodynamicModel::lastTime
protected

Last timestamp (in seconds) at which ApplyHydrodynamicForces was called.

Definition at line 91 of file HydrodynamicModel.hh.

Eigen::Vector6d gazebo::HydrodynamicModel::lastVelRel
protected

Last body-fixed relative velocity (nu_R in Fossen's equations)

Definition at line 94 of file HydrodynamicModel.hh.

std::vector<std::string> gazebo::HydrodynamicModel::params
protected

List of parameters needed from the SDF element.

Definition at line 97 of file HydrodynamicModel.hh.

double gazebo::HydrodynamicModel::Re
protected

Reynolds number (not used by all models)

Definition at line 100 of file HydrodynamicModel.hh.

double gazebo::HydrodynamicModel::temperature
protected

Temperature (not used by all models)

Definition at line 103 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