Gazebo Sim

API Reference

7.9.0
BuoyancyEnginePlugin Class Reference

This class provides a simple mechanical bladder which is used to control the buoyancy of an underwater glider. It uses Archimedes' principle to apply an upward force based on the volume of the bladder. It listens to the topic buoyancy_engine or /model/{namespace}/buoyancy_engine topic for the volume of the bladder in cubicmeters. More...

#include <BuoyancyEngine.hh>

Public Member Functions

 BuoyancyEnginePlugin ()
 Constructor. More...
 
void Configure (const Entity &_entity, const std::shared_ptr< const sdf::Element > &_sdf, EntityComponentManager &_ecm, EventManager &)
 Configure the system. More...
 
void PreUpdate (const UpdateInfo &_info, EntityComponentManager &_ecm)
 
- Public Member Functions inherited from System
 System ()=default
 Constructor. More...
 
virtual ~System ()=default
 Destructor. More...
 

Detailed Description

This class provides a simple mechanical bladder which is used to control the buoyancy of an underwater glider. It uses Archimedes' principle to apply an upward force based on the volume of the bladder. It listens to the topic buoyancy_engine or /model/{namespace}/buoyancy_engine topic for the volume of the bladder in cubicmeters.

Parameters

<link_name> - The link which the plugin is attached to [required, string] <namespace> - The namespace for the topic. If empty the plugin will listen on buoyancy_engine otherwise it listens on /model/{namespace}/buoyancy_engine [optional, string] <min_volume> - Minimum volume of the engine [optional, float, default=0.00003m^3] <neutral_volume> - At this volume the engine has neutral buoyancy. Used to estimate the weight of the engine [optional, float, default=0.0003m^3] <default_volume> - The volume which the engine starts at [optional, float, default=0.0003m^3] <max_volume> - Maximum volume of the engine [optional, float, default=0.00099m^3] <max_inflation_rate> - Maximum inflation rate for bladder [optional, float, default=0.000003m^3/s] <fluid_density> - The fluid density of the liquid its suspended in kgm^-3. [optional, float, default=1000kgm^-3] <surface> - The Z height in metres at which the surface of the water is. If not defined then there is no surface [optional, float]

Topics

  • Subscribes to a gz::msgs::Double on buoyancy_engine or /model/{namespace}/buoyancy_engine. This is the set point for the engine.
  • Publishes a gz::msgs::Double on buoyancy_engine or /model/{namespace}/buoyancy_engine/current_volume on the current volume

Examples

To get started run:

gz sim buoyancy_engine.sdf

Enter the following in a separate terminal:

gz topic -t /model/buoyant_box/buoyancy_engine/ -m gz.msgs.Double
-p "data: 0.003"

To see the box float up.

gz topic -t /model/buoyant_box/buoyancy_engine/ -m gz.msgs.Double
-p "data: 0.001"

To see the box go down. To see the current volume enter:

gz topic -t /model/buoyant_box/buoyancy_engine/current_volume -e

Constructor & Destructor Documentation

◆ BuoyancyEnginePlugin()

Constructor.

Member Function Documentation

◆ Configure()

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

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.

◆ PreUpdate()

void PreUpdate ( const UpdateInfo _info,
EntityComponentManager _ecm 
)
virtual

Implements ISystemPreUpdate.


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