BuoyantObject
class gazebo::BuoyantObject
¶
Class describing the dynamics of a buoyant object, useful for simple representations of underwater structures.
Summary¶
Members | Descriptions |
---|---|
public BuoyantObject (physics::LinkPtr _link) |
Constructor. |
public ~BuoyantObject () |
Destructor. |
public void GetBuoyancyForce (const ignition::math::Pose3d & _pose,ignition::math::Vector3d & buoyancyForce,ignition::math::Vector3d & buoyancyTorque) |
Returns the buoyancy force vector in the world frame. |
public void ApplyBuoyancyForce () |
Applies buoyancy force on link. |
public void SetVolume (double _volume) |
Sets the link's submerged volume. |
public double GetVolume () |
Returns the stored link submerged volume. |
public void SetFluidDensity (double _fluidDensity) |
Sets the fluid density in kg/m^3. |
public double GetFluidDensity () |
Returns the stored fluid density. |
public void SetCoB (const ignition::math::Vector3d & _centerOfBuoyancy) |
Sets the position of the center of buoyancy on the body frame. |
public ignition::math::Vector3d GetCoB () |
Returns the stored center of buoyancy. |
public void SetGravity (double _g) |
Set acceleration of gravity. |
public double GetGravity () |
Get stored acceleration of gravity. |
public void SetBoundingBox (const ignition::math::Box & _bBox) |
Sets bounding box. |
public void SetStoreVector (std::string _tag) |
Adds a field in the hydroWrench map. |
public ignition::math::Vector3d GetStoredVector (std::string _tag) |
Get vector from the hydroWrench map. |
public void SetDebugFlag (bool _debugOn) |
Set debug flag to store intermediate forces and torques. |
public bool IsSubmerged () |
Returns true if the robot is completely submerged. |
public bool IsNeutrallyBuoyant () |
Returns true if the link was set to be neutrally buoyant. |
public bool GetDebugFlag () |
Returns the debug flag. |
public void SetNeutrallyBuoyant () |
Sets this link as neutrally buoyant. |
protected double volume |
Volume of fluid displaced by the submerged object. |
protected double scalingVolume |
Scaling factor for the volume. |
protected double offsetVolume |
Offset for the volume. |
protected double fluidDensity |
Fluid density. |
protected double g |
Acceleration of gravity. |
protected ignition::math::Vector3d centerOfBuoyancy |
Center of buoyancy in the body frame. |
protected ignition::math::Box boundingBox |
TEMP for calculation of the buoyancy force close to the surface. |
protected std::map< std::string, ignition::math::Vector3d > hydroWrench |
Storage for hydrodynamic and hydrostatic forces and torques for debugging purposes. |
protected bool debugFlag |
Debug flag, storing all intermediate forces and torques. |
protected bool isSubmerged |
Is submerged flag. |
protected physics::LinkPtr link |
Pointer to the correspondent robot link. |
protected bool neutrallyBuoyant |
If true, the restoring force will be equal to the gravitational. |
protected double metacentricWidth |
|
protected double metacentricLength |
Metacentric length of the robot, used only for surface vessels and floating objects. |
protected 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. |
protected double submergedHeight |
Height of the robot that is submerged (only for surface vessels) |
protected bool isSurfaceVessel |
Flag set to true if the information about the metacentric width and height is available. |
protected bool isSurfaceVesselFloating |
Flag set to true if the vessel has reached its submerged height. |
protected void StoreVector (std::string _tag,ignition::math::Vector3d _vec) |
Store vector in the hydroWrench map if the field has been created. |
Members¶
public
BuoyantObject
(physics::LinkPtr _link)
¶
Constructor.
public
~BuoyantObject
()
¶
Destructor.
public void
GetBuoyancyForce
(const ignition::math::Pose3d & _pose,ignition::math::Vector3d & buoyancyForce,ignition::math::Vector3d & buoyancyTorque)
¶
Returns the buoyancy force vector in the world frame.
public void
ApplyBuoyancyForce
()
¶
Applies buoyancy force on link.
public void
SetVolume
(double _volume)
¶
Sets the link's submerged volume.
public double
GetVolume
()
¶
Returns the stored link submerged volume.
public void
SetFluidDensity
(double _fluidDensity)
¶
Sets the fluid density in kg/m^3.
public double
GetFluidDensity
()
¶
Returns the stored fluid density.
public void
SetCoB
(const ignition::math::Vector3d & _centerOfBuoyancy)
¶
Sets the position of the center of buoyancy on the body frame.
public ignition::math::Vector3d
GetCoB
()
¶
Returns the stored center of buoyancy.
public void
SetGravity
(double _g)
¶
Set acceleration of gravity.
public double
GetGravity
()
¶
Get stored acceleration of gravity.
public void
SetBoundingBox
(const ignition::math::Box & _bBox)
¶
Sets bounding box.
public void
SetStoreVector
(std::string _tag)
¶
Adds a field in the hydroWrench map.
public ignition::math::Vector3d
GetStoredVector
(std::string _tag)
¶
Get vector from the hydroWrench map.
public void
SetDebugFlag
(bool _debugOn)
¶
Set debug flag to store intermediate forces and torques.
public bool
IsSubmerged
()
¶
Returns true if the robot is completely submerged.
public bool
IsNeutrallyBuoyant
()
¶
Returns true if the link was set to be neutrally buoyant.
public bool
GetDebugFlag
()
¶
Returns the debug flag.
public void
SetNeutrallyBuoyant
()
¶
Sets this link as neutrally buoyant.
protected double
volume
¶
Volume of fluid displaced by the submerged object.
protected double
scalingVolume
¶
Scaling factor for the volume.
protected double
offsetVolume
¶
Offset for the volume.
protected double
fluidDensity
¶
Fluid density.
protected double
g
¶
Acceleration of gravity.
protected ignition::math::Vector3d
centerOfBuoyancy
¶
Center of buoyancy in the body frame.
protected ignition::math::Box
boundingBox
¶
TEMP for calculation of the buoyancy force close to the surface.
protected std::map< std::string, ignition::math::Vector3d >
hydroWrench
¶
Storage for hydrodynamic and hydrostatic forces and torques for debugging purposes.
protected bool
debugFlag
¶
Debug flag, storing all intermediate forces and torques.
protected bool
isSubmerged
¶
Is submerged flag.
protected physics::LinkPtr
link
¶
Pointer to the correspondent robot link.
protected bool
neutrallyBuoyant
¶
If true, the restoring force will be equal to the gravitational.
protected double
metacentricWidth
¶
protected double
metacentricLength
¶
Metacentric length of the robot, used only for surface vessels and floating objects.
protected 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.
protected double
submergedHeight
¶
Height of the robot that is submerged (only for surface vessels)
protected bool
isSurfaceVessel
¶
Flag set to true if the information about the metacentric width and height is available.
protected bool
isSurfaceVesselFloating
¶
Flag set to true if the vessel has reached its submerged height.
protected void
StoreVector
(std::string _tag,ignition::math::Vector3d _vec)
¶
Store vector in the hydroWrench map if the field has been created.