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

Class describing the dynamics of a buoyant object, useful for simple representations of underwater structures. More...

#include <BuoyantObject.hh>

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

Public Member Functions

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

void StoreVector (std::string _tag, ignition::math::Vector3d _vec)
 Store vector in the hydroWrench map if the field has been created. More...
 

Protected Attributes

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

Class describing the dynamics of a buoyant object, useful for simple representations of underwater structures.

Definition at line 36 of file BuoyantObject.hh.

Constructor & Destructor Documentation

gazebo::BuoyantObject::BuoyantObject ( physics::LinkPtr  _link)

Constructor.

Definition at line 24 of file BuoyantObject.cc.

gazebo::BuoyantObject::~BuoyantObject ( )

Destructor.

Definition at line 63 of file BuoyantObject.cc.

Member Function Documentation

void gazebo::BuoyantObject::ApplyBuoyancyForce ( )

Applies buoyancy force on link.

Definition at line 166 of file BuoyantObject.cc.

void gazebo::BuoyantObject::GetBuoyancyForce ( const ignition::math::Pose3d &  _pose,
ignition::math::Vector3d &  buoyancyForce,
ignition::math::Vector3d &  buoyancyTorque 
)

Returns the buoyancy force vector in the world frame.

Definition at line 82 of file BuoyantObject.cc.

ignition::math::Vector3d gazebo::BuoyantObject::GetCoB ( )

Returns the stored center of buoyancy.

Definition at line 247 of file BuoyantObject.cc.

bool gazebo::BuoyantObject::GetDebugFlag ( )

Returns the debug flag.

Definition at line 263 of file BuoyantObject.cc.

double gazebo::BuoyantObject::GetFluidDensity ( )

Returns the stored fluid density.

Definition at line 237 of file BuoyantObject.cc.

double gazebo::BuoyantObject::GetGravity ( )

Get stored acceleration of gravity.

Definition at line 257 of file BuoyantObject.cc.

ignition::math::Vector3d gazebo::BuoyantObject::GetStoredVector ( std::string  _tag)

Get vector from the hydroWrench map.

Definition at line 276 of file BuoyantObject.cc.

double gazebo::BuoyantObject::GetVolume ( )

Returns the stored link submerged volume.

Definition at line 224 of file BuoyantObject.cc.

bool gazebo::BuoyantObject::IsNeutrallyBuoyant ( )

Returns true if the link was set to be neutrally buoyant.

Definition at line 304 of file BuoyantObject.cc.

bool gazebo::BuoyantObject::IsSubmerged ( )

Returns true if the robot is completely submerged.

Definition at line 298 of file BuoyantObject.cc.

void gazebo::BuoyantObject::SetBoundingBox ( const ignition::math::Box &  _bBox)

Sets bounding box.

Definition at line 208 of file BuoyantObject.cc.

void gazebo::BuoyantObject::SetCoB ( const ignition::math::Vector3d &  _centerOfBuoyancy)

Sets the position of the center of buoyancy on the body frame.

Definition at line 240 of file BuoyantObject.cc.

void gazebo::BuoyantObject::SetDebugFlag ( bool  _debugOn = true)

Set debug flag to store intermediate forces and torques.

Definition at line 260 of file BuoyantObject.cc.

void gazebo::BuoyantObject::SetFluidDensity ( double  _fluidDensity)

Sets the fluid density in kg/m^3.

Definition at line 230 of file BuoyantObject.cc.

void gazebo::BuoyantObject::SetGravity ( double  _g)

Set acceleration of gravity.

Definition at line 250 of file BuoyantObject.cc.

void gazebo::BuoyantObject::SetNeutrallyBuoyant ( )

Sets this link as neutrally buoyant.

Definition at line 66 of file BuoyantObject.cc.

void gazebo::BuoyantObject::SetStoreVector ( std::string  _tag)

Adds a field in the hydroWrench map.

Definition at line 266 of file BuoyantObject.cc.

void gazebo::BuoyantObject::SetVolume ( double  _volume = -1)

Sets the link's submerged volume.

Definition at line 217 of file BuoyantObject.cc.

void gazebo::BuoyantObject::StoreVector ( std::string  _tag,
ignition::math::Vector3d  _vec 
)
protected

Store vector in the hydroWrench map if the field has been created.

Definition at line 287 of file BuoyantObject.cc.

Member Data Documentation

ignition::math::Box gazebo::BuoyantObject::boundingBox
protected

TEMP for calculation of the buoyancy force close to the surface.

Definition at line 123 of file BuoyantObject.hh.

ignition::math::Vector3d gazebo::BuoyantObject::centerOfBuoyancy
protected

Center of buoyancy in the body frame.

Definition at line 119 of file BuoyantObject.hh.

bool gazebo::BuoyantObject::debugFlag
protected

Debug flag, storing all intermediate forces and torques.

Definition at line 130 of file BuoyantObject.hh.

double gazebo::BuoyantObject::fluidDensity
protected

Fluid density.

Definition at line 113 of file BuoyantObject.hh.

double gazebo::BuoyantObject::g
protected

Acceleration of gravity.

Definition at line 116 of file BuoyantObject.hh.

std::map<std::string, ignition::math::Vector3d> gazebo::BuoyantObject::hydroWrench
protected

Storage for hydrodynamic and hydrostatic forces and torques for debugging purposes.

Definition at line 127 of file BuoyantObject.hh.

bool gazebo::BuoyantObject::isSubmerged
protected

Is submerged flag.

Definition at line 133 of file BuoyantObject.hh.

bool gazebo::BuoyantObject::isSurfaceVessel
protected

Flag set to true if the information about the metacentric width and height is available.

Definition at line 159 of file BuoyantObject.hh.

bool gazebo::BuoyantObject::isSurfaceVesselFloating
protected

Flag set to true if the vessel has reached its submerged height.

Definition at line 162 of file BuoyantObject.hh.

physics::LinkPtr gazebo::BuoyantObject::link
protected

Pointer to the correspondent robot link.

Definition at line 136 of file BuoyantObject.hh.

double gazebo::BuoyantObject::metacentricLength
protected

Metacentric length of the robot, used only for surface vessels and floating objects.

Definition at line 148 of file BuoyantObject.hh.

double gazebo::BuoyantObject::metacentricWidth
protected

Definition at line 144 of file BuoyantObject.hh.

bool gazebo::BuoyantObject::neutrallyBuoyant
protected

If true, the restoring force will be equal to the gravitational.

Definition at line 140 of file BuoyantObject.hh.

double gazebo::BuoyantObject::offsetVolume
protected

Offset for the volume.

Definition at line 110 of file BuoyantObject.hh.

double gazebo::BuoyantObject::scalingVolume
protected

Scaling factor for the volume.

Definition at line 107 of file BuoyantObject.hh.

double gazebo::BuoyantObject::submergedHeight
protected

Height of the robot that is submerged (only for surface vessels)

Definition at line 155 of file BuoyantObject.hh.

double gazebo::BuoyantObject::volume
protected

Volume of fluid displaced by the submerged object.

Definition at line 104 of file BuoyantObject.hh.

double gazebo::BuoyantObject::waterLevelPlaneArea
protected

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.

Definition at line 152 of file BuoyantObject.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