forked from gazebosim/gz-sim
-
Notifications
You must be signed in to change notification settings - Fork 0
Commit
This commit does not belong to any branch on this repository, and may belong to a fork outside of the repository.
Signed-off-by: Arjo Chakravarty <[email protected]> Signed-off-by: Louise Poubel <[email protected]> Co-authored-by: Louise Poubel <[email protected]> Signed-off-by: William Lew <[email protected]>
- Loading branch information
1 parent
a207e7f
commit 924b506
Showing
8 changed files
with
738 additions
and
0 deletions.
There are no files selected for viewing
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,142 @@ | ||
<?xml version="1.0" ?> | ||
<!-- | ||
This example shows you how to use the BuoyancyEngine system 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] | ||
## Topics | ||
* Subscribes to a ignition::msgs::Double on `buoyancy_engine` or | ||
`/model/{namespace}/buoyancy_engine`. This is the set point for the | ||
engine. | ||
* Publishes a ignition::msgs::Double on `buoyancy_engine` or | ||
`/model/{namespace}/buoyancy_engine/current_volume` on the current volume | ||
## Examples | ||
To get started run: | ||
``` | ||
ign gazebo buoyancy_engine.sdf | ||
``` | ||
Enter the following in a separate terminal: | ||
``` | ||
ign topic -t /model/buoyant_box/buoyancy_engine/ -m ignition.msgs.Double | ||
-p "data: 0.003" | ||
``` | ||
To see the box float up. | ||
``` | ||
ign topic -t /model/buoyant_box/buoyancy_engine/ -m ignition.msgs.Double | ||
-p "data: 0.001" | ||
``` | ||
To see the box go down. | ||
To see the current volume enter: | ||
``` | ||
ign topic -t /model/buoyant_box/buoyancy_engine/current_volume -e | ||
``` | ||
--> | ||
<sdf version="1.6"> | ||
<world name="buoyant_tethys"> | ||
<scene> | ||
<!-- For turquoise ambient --> | ||
<ambient>0.0 1.0 1.0</ambient> | ||
<background>0.0 0.7 0.8</background> | ||
</scene> | ||
|
||
<physics name="1ms" type="ode"> | ||
<max_step_size>0.001</max_step_size> | ||
<real_time_factor>1.0</real_time_factor> | ||
</physics> | ||
<plugin | ||
filename="ignition-gazebo-physics-system" | ||
name="ignition::gazebo::systems::Physics"> | ||
</plugin> | ||
<plugin | ||
filename="ignition-gazebo-user-commands-system" | ||
name="ignition::gazebo::systems::UserCommands"> | ||
</plugin> | ||
<plugin | ||
filename="ignition-gazebo-scene-broadcaster-system" | ||
name="ignition::gazebo::systems::SceneBroadcaster"> | ||
</plugin> | ||
<plugin | ||
filename="ignition-gazebo-contact-system" | ||
name="ignition::gazebo::systems::Contact"> | ||
</plugin> | ||
|
||
<plugin | ||
filename="ignition-gazebo-buoyancy-system" | ||
name="ignition::gazebo::systems::Buoyancy"> | ||
<uniform_fluid_density>1000</uniform_fluid_density> | ||
</plugin> | ||
|
||
<light type="directional" name="sun"> | ||
<cast_shadows>true</cast_shadows> | ||
<pose>0 0 10 0 0 0</pose> | ||
<diffuse>1 1 1 1</diffuse> | ||
<specular>0.5 0.5 0.5 1</specular> | ||
<attenuation> | ||
<range>1000</range> | ||
<constant>0.9</constant> | ||
<linear>0.01</linear> | ||
<quadratic>0.001</quadratic> | ||
</attenuation> | ||
<direction>-0.5 0.1 -0.9</direction> | ||
</light> | ||
|
||
<model name="buoyant_box"> | ||
<pose>0 0 0 0 0 0</pose> | ||
<link name='body'> | ||
<inertial> | ||
<mass>1000</mass> | ||
<inertia> | ||
<ixx>133.3333</ixx> | ||
<iyy>133.3333</iyy> | ||
<izz>133.3333</izz> | ||
</inertia> | ||
</inertial> | ||
<visual name='body_visual'> | ||
<geometry> | ||
<box> | ||
<size>1 1 1</size> | ||
</box> | ||
</geometry> | ||
</visual> | ||
<collision name='body_collision'> | ||
<geometry> | ||
<box> | ||
<size>1 1 1</size> | ||
</box> | ||
</geometry> | ||
</collision> | ||
</link> | ||
<plugin | ||
filename="libignition-gazebo-buoyancy-engine-system.so" | ||
name="ignition::gazebo::systems::BuoyancyEngine"> | ||
<link_name>body</link_name> | ||
<namespace>buoyant_box</namespace> | ||
<min_volume>0.0</min_volume> | ||
<neutral_volume>0.002</neutral_volume> | ||
<default_volume>0.002</default_volume> | ||
<max_volume>0.003</max_volume> | ||
<max_inflation_rate>0.0003</max_inflation_rate> | ||
</plugin> | ||
|
||
</model> | ||
</world> | ||
</sdf> |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Oops, something went wrong.