BuoyantObject.hh
Go to the documentation of this file.
1 // Copyright (c) 2016 The UUV Simulator Authors.
2 // All rights reserved.
3 //
4 // Licensed under the Apache License, Version 2.0 (the "License");
5 // you may not use this file except in compliance with the License.
6 // You may obtain a copy of the License at
7 //
8 // http://www.apache.org/licenses/LICENSE-2.0
9 //
10 // Unless required by applicable law or agreed to in writing, software
11 // distributed under the License is distributed on an "AS IS" BASIS,
12 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13 // See the License for the specific language governing permissions and
14 // limitations under the License.
15 
18 
19 #ifndef __UUV_GAZEBO_PLUGINS_BUOYANT_OBJECT_HH__
20 #define __UUV_GAZEBO_PLUGINS_BUOYANT_OBJECT_HH__
21 
22 #include <string>
23 #include <map>
24 
25 #include <gazebo/gazebo.hh>
26 #include <gazebo/physics/Link.hh>
27 #include <gazebo/physics/Collision.hh>
28 #include <gazebo/physics/Shape.hh>
29 
30 #define RESTORING_FORCE "restoring_force"
31 
32 namespace gazebo
33 {
37 {
39  public: BuoyantObject(physics::LinkPtr _link);
40 
42  public: ~BuoyantObject();
43 
45  public: void GetBuoyancyForce(const ignition::math::Pose3d &_pose,
46  ignition::math::Vector3d &buoyancyForce,
47  ignition::math::Vector3d &buoyancyTorque);
48 
50  public: void ApplyBuoyancyForce();
51 
53  public: void SetVolume(double _volume = -1);
54 
56  public: double GetVolume();
57 
59  public: void SetFluidDensity(double _fluidDensity);
60 
62  public: double GetFluidDensity();
63 
65  public: void SetCoB(const ignition::math::Vector3d &_centerOfBuoyancy);
66 
68  public: ignition::math::Vector3d GetCoB();
69 
71  public: void SetGravity(double _g);
72 
74  public: double GetGravity();
75 
77  public: void SetBoundingBox(const ignition::math::Box &_bBox);
78 
80  public: void SetStoreVector(std::string _tag);
81 
83  public: ignition::math::Vector3d GetStoredVector(std::string _tag);
84 
86  public: void SetDebugFlag(bool _debugOn = true);
87 
89  public: bool IsSubmerged();
90 
92  public: bool IsNeutrallyBuoyant();
93 
95  public: bool GetDebugFlag();
96 
98  public: void SetNeutrallyBuoyant();
99 
101  protected: void StoreVector(std::string _tag, ignition::math::Vector3d _vec);
102 
104  protected: double volume;
105 
107  protected: double scalingVolume;
108 
110  protected: double offsetVolume;
111 
113  protected: double fluidDensity;
114 
116  protected: double g;
117 
119  protected: ignition::math::Vector3d centerOfBuoyancy;
120 
123  protected: ignition::math::Box boundingBox;
124 
127  protected: std::map<std::string, ignition::math::Vector3d> hydroWrench;
128 
130  protected: bool debugFlag;
131 
133  protected: bool isSubmerged;
134 
136  protected: physics::LinkPtr link;
137 
139  // force
140  protected: bool neutrallyBuoyant;
141 
142  // \brief Metacentric width of the robot, used only for surface vessels and
143  // floating objects
144  protected: double metacentricWidth;
145 
148  protected: double metacentricLength;
149 
152  protected: double waterLevelPlaneArea;
153 
155  protected: double submergedHeight;
156 
159  protected: bool isSurfaceVessel;
160 
162  protected: bool isSurfaceVesselFloating;
163 };
164 }
165 
166 #endif
double volume
Volume of fluid displaced by the submerged object.
double submergedHeight
Height of the robot that is submerged (only for surface vessels)
void StoreVector(std::string _tag, ignition::math::Vector3d _vec)
Store vector in the hydroWrench map if the field has been created.
bool IsNeutrallyBuoyant()
Returns true if the link was set to be neutrally buoyant.
void SetDebugFlag(bool _debugOn=true)
Set debug flag to store intermediate forces and torques.
bool debugFlag
Debug flag, storing all intermediate forces and torques.
ignition::math::Box boundingBox
TEMP for calculation of the buoyancy force close to the surface.
void SetNeutrallyBuoyant()
Sets this link as neutrally buoyant.
std::map< std::string, ignition::math::Vector3d > hydroWrench
Storage for hydrodynamic and hydrostatic forces and torques for debugging purposes.
ignition::math::Vector3d GetStoredVector(std::string _tag)
Get vector from the hydroWrench map.
void SetCoB(const ignition::math::Vector3d &_centerOfBuoyancy)
Sets the position of the center of buoyancy on the body frame.
double GetGravity()
Get stored acceleration of gravity.
bool neutrallyBuoyant
If true, the restoring force will be equal to the gravitational.
double offsetVolume
Offset for the volume.
double g
Acceleration of gravity.
double waterLevelPlaneArea
If the cross section area around water level of the surface vessel is not given, it will be computed ...
bool GetDebugFlag()
Returns the debug flag.
void SetBoundingBox(const ignition::math::Box &_bBox)
Sets bounding box.
bool isSubmerged
Is submerged flag.
void SetFluidDensity(double _fluidDensity)
Sets the fluid density in kg/m^3.
void ApplyBuoyancyForce()
Applies buoyancy force on link.
double GetVolume()
Returns the stored link submerged volume.
~BuoyantObject()
Destructor.
bool isSurfaceVessel
Flag set to true if the information about the metacentric width and height is available.
void SetVolume(double _volume=-1)
Sets the link&#39;s submerged volume.
void SetStoreVector(std::string _tag)
Adds a field in the hydroWrench map.
BuoyantObject(physics::LinkPtr _link)
Constructor.
void SetGravity(double _g)
Set acceleration of gravity.
double fluidDensity
Fluid density.
ignition::math::Vector3d centerOfBuoyancy
Center of buoyancy in the body frame.
ignition::math::Vector3d GetCoB()
Returns the stored center of buoyancy.
void GetBuoyancyForce(const ignition::math::Pose3d &_pose, ignition::math::Vector3d &buoyancyForce, ignition::math::Vector3d &buoyancyTorque)
Returns the buoyancy force vector in the world frame.
double metacentricLength
Metacentric length of the robot, used only for surface vessels and floating objects.
double GetFluidDensity()
Returns the stored fluid density.
Class describing the dynamics of a buoyant object, useful for simple representations of underwater st...
physics::LinkPtr link
Pointer to the correspondent robot link.
double scalingVolume
Scaling factor for the volume.
bool isSurfaceVesselFloating
Flag set to true if the vessel has reached its submerged height.
bool IsSubmerged()
Returns true if the robot is completely submerged.


uuv_gazebo_plugins
Author(s): Musa Morena Marcusso Manhaes , Sebastian Scherer , Luiz Ricardo Douat
autogenerated on Mon Jul 1 2019 19:39:12