-
Notifications
You must be signed in to change notification settings - Fork 304
/
Copy pathbuoyancy_engine.sdf
188 lines (181 loc) · 6.03 KB
/
buoyancy_engine.sdf
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
<?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
```
You will see two boxes. The box on the right doesn't have a surface set whereas
the box on the left does. When commanded to go up, the box on the left will rise
until it breaches and then start oscillating around the surface. On the other
hand the box on the right will rise forever as no surface is set.
Enter the following in a separate terminal:
```
ign topic -t /model/buoyant_box/buoyancy_engine/ -m ignition.msgs.Double
-p "data: 0.003"
```
The boxes will float up. Note that the box on the left will start oscillating
once it breaches the surface.
```
ign topic -t /model/buoyant_box/buoyancy_engine/ -m ignition.msgs.Double
-p "data: 0.001"
```
The boxes will 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>
<model name="buoyant_box_surface">
<pose>0 5 -0.8 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>
<surface>0</surface>
</plugin>
</model>
</world>
</sdf>