18 #ifndef USV_GAZEBO_PLUGINS_BUOYANCY_GAZEBO_PLUGIN_HH_ 19 #define USV_GAZEBO_PLUGINS_BUOYANCY_GAZEBO_PLUGIN_HH_ 25 #include <gazebo/common/common.hh> 26 #include <gazebo/common/Event.hh> 27 #include <gazebo/common/Plugin.hh> 28 #include <gazebo/physics/physics.hh> 29 #include <ignition/math/Pose3.hh> 30 #include <ignition/math/Vector3.hh> 56 public:
void Load(
const physics::ModelPtr model,
57 const sdf::ElementPtr elem);
60 public: std::string
Disp();
69 public: ignition::math::Pose3d
pose;
120 public:
virtual void Load(physics::ModelPtr _model,
121 sdf::ElementPtr _sdf);
124 public:
virtual void Init();
127 protected:
virtual void OnUpdate();
149 protected: std::map<int, gazebo::physics::LinkPtr>
linkMap;
162 protected: std::map<gazebo::physics::LinkPtr, double>
linkHeights;
171 protected: std::shared_ptr<const asv::WaveParameters>
waveParams;
ignition::math::Pose3d pose
Pose of buoyancy relative to link.
double fluidLevel
The height of the fluid/air interface [m]. Defaults to 0.
int linkId
Associated link ID.
This plugin simulates buoyancy of an object in fluid. <wave_model>: Name of the wave model object (op...
void Load(const physics::ModelPtr model, const sdf::ElementPtr elem)
Load buoyancy object from SDF.
std::vector< buoyancy::BuoyancyObject > buoyancyObjects
List of buoyancy objects for model.
::buoyancy::ShapeVolumePtr shape
Buoyancy object's shape properties.
std::unique_ptr< ShapeVolume > ShapeVolumePtr
std::map< gazebo::physics::LinkPtr, double > linkHeightDots
Map of water velocity at each link.
std::map< gazebo::physics::LinkPtr, double > linkHeights
Map of water height at each link from previous timestep.
std::string Disp()
Display string for buoyancy object.
std::shared_ptr< const asv::WaveParameters > waveParams
The wave parameters.
std::map< int, gazebo::physics::LinkPtr > linkMap
Map of <link ID, link pointer>
double lastSimTime
Previous update time.
double angularDrag
Angular drag coefficient. Defaults to 0.
BuoyancyObject()
Default constructor.
double mass
Object mass (from inertial elem)
std::string linkName
Associated link name.
std::string waveModelName
The name of the wave model.
event::ConnectionPtr updateConnection
Connection to World Update events.
double fluidDensity
The density of the fluid in which the object is submerged in kg/m^3. Defaults to 1000, the fluid density of water at 15 Celsius.
double linearDrag
Linear drag coefficient. Defaults to 0.
physics::ModelPtr model
Pointer to base model.
A class for storing buoyancy object properties.
physics::WorldPtr world
Pointer to the Gazebo world Retrieved when the model is loaded.