Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Buoyancy improvements #818

Merged
merged 44 commits into from
Sep 22, 2021
Merged
Show file tree
Hide file tree
Changes from 43 commits
Commits
Show all changes
44 commits
Select commit Hold shift + click to select a range
2e28e1d
fix broken diagram
arjo129 May 3, 2021
52a8451
Begin initial support for buoyancy transitions
arjo129 May 3, 2021
ecbf6fb
Add support for sphere volume
arjo129 May 11, 2021
d5f7fff
skeletal cylinder stuff
arjo129 May 14, 2021
c2e6f1e
Add simple case
arjo129 May 14, 2021
f43cf80
Add cylinder buouyancy
arjo129 May 15, 2021
6e98053
Added CircleSegmentSliceArea method
arjo129 May 18, 2021
f7476e3
Add SDF parsing
arjo129 May 18, 2021
37ec3ff
Merge branch 'ign-gazebo5' into arjo/buoyancy_improvements
arjo129 May 18, 2021
74768f9
Merge branch 'main' into arjo/buoyancy_improvements
arjo129 Aug 16, 2021
d604f7d
Fix compile issues, fix center of mass issues
arjo129 Aug 26, 2021
8ca5288
terminates after bad access. Need to add inertial component
arjo129 Aug 29, 2021
716898d
remove rotation, no more crashes
arjo129 Aug 29, 2021
baefadb
no more crashes, still not working
arjo129 Aug 29, 2021
be27c73
Added warnings
arjo129 Aug 30, 2021
e864eba
tweak behaviour to have simple harmonic motion behaviour.
arjo129 Aug 30, 2021
58d96dc
Add box type error.
arjo129 Aug 30, 2021
823b104
add default error message
arjo129 Aug 30, 2021
ba8f8bb
style fixes
arjo129 Aug 30, 2021
d584b26
:facepalm: more compile errors.
arjo129 Aug 30, 2021
3263975
add comments
arjo129 Aug 31, 2021
0171118
add more docs
arjo129 Aug 31, 2021
214ecba
style
arjo129 Sep 1, 2021
63dcf62
Add comments
arjo129 Sep 2, 2021
8ba1fce
fix typo
arjo129 Sep 2, 2021
f6dc72c
update typo
arjo129 Sep 2, 2021
93cfdf6
fixing spelling
arjo129 Sep 2, 2021
92971de
tests are still broken
arjo129 Sep 2, 2021
3661e87
fiz graded buoyancy test
arjo129 Sep 3, 2021
02e03f6
Revert changes with regards to torque correction.
arjo129 Sep 3, 2021
b712604
restore old buoyancy
arjo129 Sep 3, 2021
f5a7cdf
style fixes
arjo129 Sep 3, 2021
5a9a7db
Rename volsum to prevent cofusion
arjo129 Sep 16, 2021
a8260bb
Remove GUI elements
arjo129 Sep 16, 2021
c586a3d
minor tweaks
arjo129 Sep 16, 2021
d59b128
more tweaks
arjo129 Sep 16, 2021
fd627bd
Update docs
arjo129 Sep 16, 2021
57f30e0
reordering
arjo129 Sep 16, 2021
24f5b0a
Docs
arjo129 Sep 17, 2021
4dfc57c
:x: :bug: Fix regression.
arjo129 Sep 20, 2021
43fe492
Added plane, sinking cube. Still not pretty: But in my defence I did …
arjo129 Sep 20, 2021
80b27ae
merged from main
chapulina Sep 21, 2021
2abcabd
Add new example and fix it shooting up
chapulina Sep 21, 2021
f6ce49f
Merge branch 'main' into arjo/buoyancy_improvements
chapulina Sep 22, 2021
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
308 changes: 308 additions & 0 deletions examples/worlds/graded_buoyancy.sdf
Original file line number Diff line number Diff line change
@@ -0,0 +1,308 @@
<?xml version="1.0" ?>
<!--
Ignition Gazebo buoyancy plugin demo. This world demonstrates a graded
buoyancy world consisting of some basic shapes which should eventually float
up.
-->
<sdf version="1.6">
<world name="buoyancy">

<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-buoyancy-system"
name="ignition::gazebo::systems::Buoyancy">
<graded_buoyancy>
<default_density>1000</default_density>
<density_change>
<above_depth>0</above_depth>
<density>1</density>
</density_change>
</graded_buoyancy>
</plugin>

<gui fullscreen="0">

<!-- 3D scene -->
<plugin filename="GzScene3D" name="3D View">
<ignition-gui>
<title>3D View</title>
<property type="bool" key="showTitleBar">false</property>
<property type="string" key="state">docked</property>
</ignition-gui>

<engine>ogre2</engine>
<scene>scene</scene>
<ambient_light>0.4 0.4 0.4</ambient_light>
<background_color>0.8 0.8 0.8</background_color>
<camera_pose>-10 -2 5.6 0 0.5 0</camera_pose>
</plugin>

<!-- World control -->
<plugin filename="WorldControl" name="World control">
<ignition-gui>
<title>World control</title>
<property type="bool" key="showTitleBar">false</property>
<property type="bool" key="resizable">false</property>
<property type="double" key="height">72</property>
<property type="double" key="width">121</property>
<property type="double" key="z">1</property>

<property type="string" key="state">floating</property>
<anchors target="3D View">
<line own="left" target="left"/>
<line own="bottom" target="bottom"/>
</anchors>
</ignition-gui>

<play_pause>true</play_pause>
<step>true</step>
<start_paused>true</start_paused>
<service>/world/buoyancy/control</service>
<stats_topic>/world/buoyancy/stats</stats_topic>
</plugin>

<!-- World statistics -->
<plugin filename="WorldStats" name="World stats">
<ignition-gui>
<title>World stats</title>
<property type="bool" key="showTitleBar">false</property>
<property type="bool" key="resizable">false</property>
<property type="double" key="height">110</property>
<property type="double" key="width">290</property>
<property type="double" key="z">1</property>

<property type="string" key="state">floating</property>
<anchors target="3D View">
<line own="right" target="right"/>
<line own="bottom" target="bottom"/>
</anchors>
</ignition-gui>

<sim_time>true</sim_time>
<real_time>true</real_time>
<real_time_factor>true</real_time_factor>
<iterations>true</iterations>
<topic>/world/buoyancy/stats</topic>
</plugin>

</gui>

<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="water_plane">
<static>true</static>
<link name="link">
<visual name="water_plane">
<geometry>
<plane>
<size>100 100</size>
<normal>0 0 1</normal>
</plane>
</geometry>
<material>
<ambient>0 0 1 0.5</ambient>
<diffuse>0 0 1 0.5</diffuse>
<specular>0 0 1 0.5</specular>
</material>
</visual>
</link>
</model>

<!-- This sphere should bob up and down. -->
<model name='ball_lighter_than_water'>
<pose>0 0 0 0 0 0</pose>
<link name='body'>
<pose>0 0 0 0 0 0</pose>
<inertial>
<mass>25</mass>
<inertia>
<ixx>86.28907821859966</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>86.28907821859966</iyy>
<iyz>0</iyz>
<izz>5.026548245743671</izz>
</inertia>
</inertial>

<visual name='body_visual'>
<geometry>
<sphere>
<radius>0.2</radius>
</sphere>
</geometry>
</visual>
<collision name='body_collision'>
<geometry>
<sphere>
<radius>0.2</radius>
</sphere>
</geometry>
</collision>
</link>
</model>

<!-- This box should float. -->
<model name='box_lighter_than_water'>
<pose>3 5 0 0.3 0.2 0.1</pose>
<link name='body'>
<inertial>
<mass>200</mass>
<inertia>
<ixx>33.33</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>33.33</iyy>
<iyz>0</iyz>
<izz>33.33</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>
</model>

<!-- This balloon should shoot up -->
<model name='balloon_lighter_than_air'>
<pose>0 -5 -5 0 0 0</pose>
<link name='body'>
<pose>0 0 0 0 0 0</pose>
<inertial>
<mass>0.1</mass>
<inertia>
<ixx>86.28907821859966</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>86.28907821859966</iyy>
<iyz>0</iyz>
<izz>5.026548245743671</izz>
</inertia>
</inertial>

<visual name='body_visual'>
<geometry>
<sphere>
<radius>0.2</radius>
</sphere>
</geometry>
</visual>
<collision name='body_collision'>
<geometry>
<sphere>
<radius>0.2</radius>
</sphere>
</geometry>
</collision>
</link>
</model>

<!-- This box is neutrally buoyant and therefore should stay still -->
<model name='box_neutral_buoyancy'>
<pose>0 5 -3 0 0 0</pose>
<link name='body'>
<inertial>
<mass>1000</mass>
<pose>0 0 0.1 0 0 0</pose>
<inertia>
<ixx>86.28907821859966</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>86.28907821859966</iyy>
<iyz>0</iyz>
<izz>5.026548245743671</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>
</model>

<!-- This box is negatively buoyant and therefore should sink -->
<model name='box_negative_buoyancy'>
<pose>0 -8 0 0 0 0</pose>
<link name='body'>
<inertial>
<mass>1050</mass>
<pose>0 0 0.1 0 0 0</pose>
<inertia>
<ixx>86.28907821859966</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>86.28907821859966</iyy>
<iyz>0</iyz>
<izz>5.026548245743671</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>
</model>
</world>
</sdf>

Loading