Ignition Gazebo

API Reference

6.1.0
Buoyancy Class Reference

A system that simulates buoyancy of objects immersed in fluid. All SDF parameters are optional. This system must be attached to the world and this system will apply buoyancy to all links that have inertia and collision shapes. More...

#include <Buoyancy.hh>

Public Member Functions

 Buoyancy ()
 Constructor. More...
 
 ~Buoyancy () override=default
 Destructor. More...
 
void Configure (const Entity &_entity, const std::shared_ptr< const sdf::Element > &_sdf, EntityComponentManager &_ecm, EventManager &_eventMgr) override
 Configure the system. More...
 
bool IsEnabled (Entity _entity, const EntityComponentManager &_ecm) const
 Check if an entity is enabled or not. More...
 
void PreUpdate (const UpdateInfo &_info, EntityComponentManager &_ecm) override
 
- Public Member Functions inherited from System
 System ()=default
 Constructor. More...
 
virtual ~System ()=default
 Destructor. More...
 

Detailed Description

A system that simulates buoyancy of objects immersed in fluid. All SDF parameters are optional. This system must be attached to the world and this system will apply buoyancy to all links that have inertia and collision shapes.

The volume and center of volume will be computed for each link, and stored as components. During each iteration, Archimedes' principle is applied to each link with a volume and center of volume component.

Plane shapes are not handled by this plugin, and will not be affected by buoyancy.

System Parameters

  • <uniform_fluid_density> sets the density of the fluid that surrounds the buoyant object. [Units: kgm^-3]
  • <graded_buoyancy> allows you to define a world where the buoyancy changes with height. An example of such a world could be if we are simulating an open ocean with its surface and under water behaviour. This mode slices the volume of the collision mesh according to where the water line is set. When defining a <graded_buoyancy> tag, one must also define <default_density> and <density_change> tags.
  • <default_density> is the default fluid which the world should be filled with. [Units: kgm^-3]
  • <density_change> allows you to define a new layer.
  • <above_depth> a child property of <density_change>. This determines the height at which the next fluid layer should start. [Units: m]
  • <density> the density of the fluid in this layer. [Units: kgm^-3]
  • <enable> used to indicate which models will have buoyancy. Add one enable element per model or link. This element accepts names scoped from the top level model (i.e. <model>::<nested_model>::<link>). If there are no enabled entities, all models in simulation will be affected by buoyancy.

Examples

uniform_fluid_density world.

The buoyancy.sdf SDF file contains three submarines. The first submarine is neutrally buoyant, the second sinks, and the third floats. To run:

ign gazebo -v 4 buoyancy.sdf

graded_buoyancy world

Often when simulating a maritime environment one may need to simulate both surface and underwater vessels. This means the buoyancy plugin needs to take into account two different fluids. One being water with a density of 1000kgm^-3 and another being air with a very light density of say 1kgm^-3. An example for such a configuration may be found in the graded_buoyancy.sdf world.

ign gazebo -v 4 graded_buoyancy.sdf

You should be able to see a sphere bobbing up and down undergoing simple harmonic motion on the surface of the fluid (this is expected behaviour as the SHM is usually damped by the hydrodynamic forces. See the hydro- dynamics plugin for an example of how to use it). The key part of this is

<graded_buoyancy>
<default_density>1000</default_density>
<density_change>
<above_depth>0</above_depth>
<density>1</density>
</density_change>
</graded_buoyancy>

The default density tag says that by default the world has a fluid density of 1000kgm^-3. This essentially states that by default the world is filled with dihydrogen monoxide (aka water). The <density_change> tag essentially establishes the fact that there is a nother fluid. The <above_depth> tag says that above z=0 there is another fluid with a different density. The density of that fluid is defined by the <density> tag. We will be simulating air with a fluid density of 1kgm^-3.

Constructor & Destructor Documentation

◆ Buoyancy()

Buoyancy ( )

Constructor.

◆ ~Buoyancy()

~Buoyancy ( )
overridedefault

Destructor.

Member Function Documentation

◆ Configure()

void Configure ( const Entity _entity,
const std::shared_ptr< const sdf::Element > &  _sdf,
EntityComponentManager _ecm,
EventManager _eventMgr 
)
overridevirtual

Configure the system.

Parameters
[in]_entityThe entity this plugin is attached to.
[in]_sdfThe SDF Element associated with this system plugin.
[in]_ecmThe EntityComponentManager of the given simulation instance.
[in]_eventMgrThe EventManager of the given simulation instance.

Implements ISystemConfigure.

◆ IsEnabled()

bool IsEnabled ( Entity  _entity,
const EntityComponentManager _ecm 
) const

Check if an entity is enabled or not.

Parameters
[in]_entityTarget entity
[in]_ecmEntity component manager
Returns
True if buoyancy should be applied.

◆ PreUpdate()

void PreUpdate ( const UpdateInfo _info,
EntityComponentManager _ecm 
)
overridevirtual

Implements ISystemPreUpdate.


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