Class containing the methods and attributes for a hydrodynamic model for a sphere in the fluid. More...
#include <HydrodynamicModel.hh>
Public Member Functions | |
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... | |
Public Member Functions inherited from gazebo::HMFossen | |
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 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 HydrodynamicModel * | create (sdf::ElementPtr _sdf, physics::LinkPtr _link) |
Create model of this type with parameter values from sdf. More... | |
Static Public Member Functions inherited from gazebo::HMFossen | |
static HydrodynamicModel * | create (sdf::ElementPtr _sdf, physics::LinkPtr _link) |
Create model of this type with parameter values from sdf. More... | |
Protected Member Functions | |
HMSphere (sdf::ElementPtr _sdf, physics::LinkPtr _link) | |
REGISTER_HYDRODYNAMICMODEL (HMSphere) | |
Register this model with the factory. More... | |
Protected Member Functions inherited from gazebo::HMFossen | |
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 | |
double | areaSection |
Area of the cross section. More... | |
double | Cd |
Drag coefficient. More... | |
double | radius |
Sphere radius. More... | |
Protected Attributes inherited from gazebo::HMFossen | |
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 = "sphere" |
Unique identifier for this geometry. More... | |
Static Protected Attributes inherited from gazebo::HMFossen | |
static const std::string | IDENTIFIER = "fossen" |
Unique identifier for this geometry. More... | |
Class containing the methods and attributes for a hydrodynamic model for a sphere in the fluid.
Definition at line 252 of file HydrodynamicModel.hh.
|
protected |
Definition at line 697 of file HydrodynamicModel.cc.
|
static |
Create model of this type with parameter values from sdf.
Definition at line 690 of file HydrodynamicModel.cc.
|
inlinevirtual |
Return (derived) type of hydrodynamic model.
Reimplemented from gazebo::HMFossen.
Definition at line 259 of file HydrodynamicModel.hh.
|
virtual |
Prints parameters.
Reimplemented from gazebo::HMFossen.
Definition at line 753 of file HydrodynamicModel.cc.
|
protected |
Register this model with the factory.
|
protected |
Area of the cross section.
Definition at line 280 of file HydrodynamicModel.hh.
|
protected |
Drag coefficient.
Definition at line 277 of file HydrodynamicModel.hh.
|
staticprotected |
Unique identifier for this geometry.
Definition at line 269 of file HydrodynamicModel.hh.
|
protected |
Sphere radius.
Definition at line 274 of file HydrodynamicModel.hh.