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

This plugin simulates buoyancy of an object in fluid. <wave_model>: Name of the wave model object (optional) More...

#include <buoyancy_gazebo_plugin.hh>

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

Public Member Functions

 BuoyancyPlugin ()
 Constructor. More...
 
virtual void Init ()
 
virtual void Load (physics::ModelPtr _model, sdf::ElementPtr _sdf)
 

Protected Member Functions

virtual void OnUpdate ()
 Callback for World Update events. More...
 

Protected Attributes

double angularDrag
 Angular drag coefficient. Defaults to 0. More...
 
std::vector< buoyancy::BuoyancyObjectbuoyancyObjects
 List of buoyancy objects for model. More...
 
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. More...
 
double fluidLevel
 The height of the fluid/air interface [m]. Defaults to 0. More...
 
double lastSimTime
 Previous update time. More...
 
double linearDrag
 Linear drag coefficient. Defaults to 0. More...
 
std::map< gazebo::physics::LinkPtr, double > linkHeightDots
 Map of water velocity at each link. More...
 
std::map< gazebo::physics::LinkPtr, double > linkHeights
 Map of water height at each link from previous timestep. More...
 
std::map< int, gazebo::physics::LinkPtr > linkMap
 Map of <link ID, link pointer> More...
 
physics::ModelPtr model
 Pointer to base model. More...
 
event::ConnectionPtr updateConnection
 Connection to World Update events. More...
 
std::string waveModelName
 The name of the wave model. More...
 
std::shared_ptr< const asv::WaveParameterswaveParams
 The wave parameters. More...
 
physics::WorldPtr world
 Pointer to the Gazebo world Retrieved when the model is loaded. More...
 

Detailed Description

This plugin simulates buoyancy of an object in fluid. <wave_model>: Name of the wave model object (optional)

<fluid_density>: Sets the density of the fluid that surrounds the buoyant object [kg/m^3]. This parameter is optional (default value 997 kg/m^3).

<fluid_level>: The height of the fluid/air interface [m]. This parameter is optional (default value 0 m).

<linear_drag>: Linear drag coefficent [N/(m/s)]. Translational drag implement as linear function of velocity. This parameter is optional.

<angular_drag>: Angular drag coefficent [(Nm)/(rad/s)]. Rotational drag implemented as linear function of velocity. This parameter is optional.

<buoyancy>: Describes the volume properties For example:

<buoyancy name="buoyancy1"> <link_name>link</link_name> <geometry> ... </geometry> </buoyancy>

<link>: Name of associated link element

<geometry>: Geometry element specifying buoyancy object's volume properties. Supported shapes: box, sphere, cylinder

Definition at line 114 of file buoyancy_gazebo_plugin.hh.

Constructor & Destructor Documentation

BuoyancyPlugin::BuoyancyPlugin ( )

Constructor.

Definition at line 106 of file buoyancy_gazebo_plugin.cc.

Member Function Documentation

void BuoyancyPlugin::Init ( )
virtual

Definition at line 207 of file buoyancy_gazebo_plugin.cc.

void BuoyancyPlugin::Load ( physics::ModelPtr  _model,
sdf::ElementPtr  _sdf 
)
virtual

Definition at line 117 of file buoyancy_gazebo_plugin.cc.

void BuoyancyPlugin::OnUpdate ( )
protectedvirtual

Callback for World Update events.

Definition at line 214 of file buoyancy_gazebo_plugin.cc.

Member Data Documentation

double gazebo::BuoyancyPlugin::angularDrag
protected

Angular drag coefficient. Defaults to 0.

Definition at line 143 of file buoyancy_gazebo_plugin.hh.

std::vector<buoyancy::BuoyancyObject> gazebo::BuoyancyPlugin::buoyancyObjects
protected

List of buoyancy objects for model.

Definition at line 146 of file buoyancy_gazebo_plugin.hh.

double gazebo::BuoyancyPlugin::fluidDensity
protected

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.

Definition at line 134 of file buoyancy_gazebo_plugin.hh.

double gazebo::BuoyancyPlugin::fluidLevel
protected

The height of the fluid/air interface [m]. Defaults to 0.

Definition at line 137 of file buoyancy_gazebo_plugin.hh.

double gazebo::BuoyancyPlugin::lastSimTime
protected

Previous update time.

Definition at line 168 of file buoyancy_gazebo_plugin.hh.

double gazebo::BuoyancyPlugin::linearDrag
protected

Linear drag coefficient. Defaults to 0.

Definition at line 140 of file buoyancy_gazebo_plugin.hh.

std::map<gazebo::physics::LinkPtr, double> gazebo::BuoyancyPlugin::linkHeightDots
protected

Map of water velocity at each link.

Definition at line 165 of file buoyancy_gazebo_plugin.hh.

std::map<gazebo::physics::LinkPtr, double> gazebo::BuoyancyPlugin::linkHeights
protected

Map of water height at each link from previous timestep.

Definition at line 162 of file buoyancy_gazebo_plugin.hh.

std::map<int, gazebo::physics::LinkPtr> gazebo::BuoyancyPlugin::linkMap
protected

Map of <link ID, link pointer>

Definition at line 149 of file buoyancy_gazebo_plugin.hh.

physics::ModelPtr gazebo::BuoyancyPlugin::model
protected

Pointer to base model.

Definition at line 152 of file buoyancy_gazebo_plugin.hh.

event::ConnectionPtr gazebo::BuoyancyPlugin::updateConnection
protected

Connection to World Update events.

Definition at line 130 of file buoyancy_gazebo_plugin.hh.

std::string gazebo::BuoyancyPlugin::waveModelName
protected

The name of the wave model.

Definition at line 159 of file buoyancy_gazebo_plugin.hh.

std::shared_ptr<const asv::WaveParameters> gazebo::BuoyancyPlugin::waveParams
protected

The wave parameters.

Definition at line 171 of file buoyancy_gazebo_plugin.hh.

physics::WorldPtr gazebo::BuoyancyPlugin::world
protected

Pointer to the Gazebo world Retrieved when the model is loaded.

Definition at line 156 of file buoyancy_gazebo_plugin.hh.


The documentation for this class was generated from the following files:


usv_gazebo_plugins
Author(s): Brian Bingham , Carlos Aguero
autogenerated on Thu May 7 2020 03:54:47