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

Update added-mass of lrauv model and remove added mass definitions from examples #2608

Open
wants to merge 14 commits into
base: gz-sim9
Choose a base branch
from
Open
4 changes: 4 additions & 0 deletions Migration.md
Original file line number Diff line number Diff line change
Expand Up @@ -23,6 +23,10 @@ release will remove the deprecated code.
`gz::sim::systems::kPostPhysicsSensorPriority` constant to ensure that its
`Update` phase executes after `Physics::Update` and before systems with
default priority.
* **Deprecated**
+ In the Hydrodynamics system, added mass has been deprecated in favour of
the builtin sdformat `<fuel_added_mass>` tag that offers better stability
guarantees.

## Gazebo Sim 7.x to 8.0
* **Deprecated**
Expand Down
24 changes: 3 additions & 21 deletions examples/worlds/acoustic_comms_demo.sdf
Original file line number Diff line number Diff line change
Expand Up @@ -71,7 +71,7 @@

<include>
<pose>0 0 1 0 0 1.57</pose>
<uri>https://fuel.gazebosim.org/1.0/accurrent/models/MBARI Tethys LRAUV</uri>
<uri>https://fuel.gazebosim.org/1.0/arjo129/models/LRAUV-PostIonic</uri>

<!-- Acoustic comms endpoint -->
<plugin
Expand Down Expand Up @@ -148,12 +148,6 @@
filename="gz-sim-hydrodynamics-system"
name="gz::sim::systems::Hydrodynamics">
<link_name>base_link</link_name>
<xDotU>-4.876161</xDotU>
<yDotV>-126.324739</yDotV>
<zDotW>-126.324739</zDotW>
<kDotP>0</kDotP>
<mDotQ>-33.46</mDotQ>
<nDotR>-33.46</nDotR>
<xUU>-6.2282</xUU>
<xU>0</xU>
<yVV>-601.27</yVV>
Expand All @@ -172,7 +166,7 @@

<include>
<pose>15 0 1 0 0 1.57</pose>
<uri>https://fuel.gazebosim.org/1.0/accurrent/models/MBARI Tethys LRAUV</uri>
<uri>https://fuel.gazebosim.org/1.0/arjo129/models/LRAUV-PostIonic</uri>
<name>triton</name>

<!-- Acoustic comms endpoint -->
Expand Down Expand Up @@ -250,12 +244,6 @@
filename="gz-sim-hydrodynamics-system"
name="gz::sim::systems::Hydrodynamics">
<link_name>base_link</link_name>
<xDotU>-4.876161</xDotU>
<yDotV>-126.324739</yDotV>
<zDotW>-126.324739</zDotW>
<kDotP>0</kDotP>
<mDotQ>-33.46</mDotQ>
<nDotR>-33.46</nDotR>
<xUU>-6.2282</xUU>
<xU>0</xU>
<yVV>-601.27</yVV>
Expand All @@ -274,7 +262,7 @@

<include>
<pose>-15 0 1 0 0 1.57</pose>
<uri>https://fuel.gazebosim.org/1.0/accurrent/models/MBARI Tethys LRAUV</uri>
<uri>https://fuel.gazebosim.org/1.0/arjo129/models/LRAUV-PostIonic</uri>
<name>daphne</name>

<!-- Acoustic comms endpoint -->
Expand Down Expand Up @@ -352,12 +340,6 @@
filename="gz-sim-hydrodynamics-system"
name="gz::sim::systems::Hydrodynamics">
<link_name>base_link</link_name>
<xDotU>-4.876161</xDotU>
<yDotV>-126.324739</yDotV>
<zDotW>-126.324739</zDotW>
<kDotP>0</kDotP>
<mDotQ>-33.46</mDotQ>
<nDotR>-33.46</nDotR>
<xUU>-6.2282</xUU>
<xU>0</xU>
<yVV>-601.27</yVV>
Expand Down
8 changes: 1 addition & 7 deletions examples/worlds/auv_controls.sdf
Original file line number Diff line number Diff line change
Expand Up @@ -71,7 +71,7 @@

<include>
<pose>0 0 1 0 0 1.57</pose>
<uri>https://fuel.gazebosim.org/1.0/accurrent/models/MBARI%20Tethys%20LRAUV</uri>
<uri>https://fuel.gazebosim.org/1.0/arjo129/models/LRAUV-PostIonic</uri>

<!-- Joint controllers -->
<plugin
Expand Down Expand Up @@ -141,12 +141,6 @@
filename="gz-sim-hydrodynamics-system"
name="gz::sim::systems::Hydrodynamics">
<link_name>base_link</link_name>
<xDotU>-4.876161</xDotU>
<yDotV>-126.324739</yDotV>
<zDotW>-126.324739</zDotW>
<kDotP>0</kDotP>
<mDotQ>-33.46</mDotQ>
<nDotR>-33.46</nDotR>
<xUabsU>-6.2282</xUabsU>
<xU>0</xU>
<yVabsV>-601.27</yVabsV>
Expand Down
12 changes: 2 additions & 10 deletions examples/worlds/dvl_world.sdf
Original file line number Diff line number Diff line change
Expand Up @@ -134,12 +134,11 @@
</visual>
</link>
</model>

<include>
<pose>0 0 -80 0 0 1.57</pose>
<uri>https://fuel.gazebosim.org/1.0/accurrent/models/MBARI Tethys LRAUV</uri>
<uri>https://fuel.gazebosim.org/1.0/arjo129/models/LRAUV-PostIonic</uri>

<experimental:params>
<experimental:params>U
<sensor
element_id="base_link" action="add"
name="teledyne_pathfinder_dvl"
Expand Down Expand Up @@ -267,13 +266,6 @@
filename="gz-sim-hydrodynamics-system"
name="gz::sim::systems::Hydrodynamics">
<link_name>base_link</link_name>
<xDotU>-4.876161</xDotU>
<yDotV>-126.324739</yDotV>
<zDotW>-126.324739</zDotW>
<kDotP>0</kDotP>
<mDotQ>-33.46</mDotQ>
<nDotR>-33.46</nDotR>
<xUabsU>-6.2282</xUabsU>
<xU>0</xU>
<yVabsV>-601.27</yVabsV>
<yV>0</yV>
Expand Down
8 changes: 1 addition & 7 deletions examples/worlds/lrauv_control_demo.sdf
Original file line number Diff line number Diff line change
Expand Up @@ -175,7 +175,7 @@

<include>
<pose>0 0 1 0 0 0</pose>
<uri>https://fuel.gazebosim.org/1.0/accurrent/models/MBARI Tethys LRAUV</uri>
<uri>https://fuel.gazebosim.org/1.0/arjo129/models/LRAUV-PostIonic</uri>

<plugin
filename="gz-sim-odometry-publisher-system"
Expand Down Expand Up @@ -250,12 +250,6 @@
filename="gz-sim-hydrodynamics-system"
name="gz::sim::systems::Hydrodynamics">
<link_name>base_link</link_name>
<xDotU>-4.876161</xDotU>
<yDotV>-126.324739</yDotV>
<zDotW>-126.324739</zDotW>
<kDotP>0</kDotP>
<mDotQ>-33.46</mDotQ>
<nDotR>-33.46</nDotR>
<xUabsU>-6.2282</xUabsU>
<xU>0</xU>
<yVabsV>-601.27</yVabsV>
Expand Down
25 changes: 3 additions & 22 deletions examples/worlds/multi_lrauv_race.sdf
Original file line number Diff line number Diff line change
Expand Up @@ -59,7 +59,7 @@

<include>
<pose>0 0 1 0 0 1.57</pose>
<uri>https://fuel.gazebosim.org/1.0/accurrent/models/MBARI Tethys LRAUV</uri>
<uri>https://fuel.gazebosim.org/1.0/arjo129/models/LRAUV-PostIonic</uri>

<!-- Joint controllers -->
<plugin
Expand Down Expand Up @@ -128,12 +128,6 @@
filename="gz-sim-hydrodynamics-system"
name="gz::sim::systems::Hydrodynamics">
<link_name>base_link</link_name>
<xDotU>-4.876161</xDotU>
<yDotV>-126.324739</yDotV>
<zDotW>-126.324739</zDotW>
<kDotP>0</kDotP>
<mDotQ>-33.46</mDotQ>
<nDotR>-33.46</nDotR>
<yUabsU>-6.2282</yUabsU>
<xU>0</xU>
<yVabsV>-601.27</yVabsV>
Expand All @@ -152,7 +146,7 @@

<include>
<pose>5 0 1 0 0 1.57</pose>
<uri>https://fuel.gazebosim.org/1.0/accurrent/models/MBARI Tethys LRAUV</uri>
<uri>https://fuel.gazebosim.org/1.0/arjo129/models/LRAUV-PostIonic</uri>
<name>triton</name>

<!-- Joint controllers -->
Expand Down Expand Up @@ -222,13 +216,6 @@
filename="gz-sim-hydrodynamics-system"
name="gz::sim::systems::Hydrodynamics">
<link_name>base_link</link_name>
<xDotU>-4.876161</xDotU>
<yDotV>-126.324739</yDotV>
<zDotW>-126.324739</zDotW>
<kDotP>0</kDotP>
<mDotQ>-33.46</mDotQ>
<nDotR>-33.46</nDotR>
<yUabsU>-6.2282</yUabsU>
<xU>0</xU>
<yVabsV>-601.27</yVabsV>
<yV>0</yV>
Expand All @@ -246,7 +233,7 @@

<include>
<pose>-5 0 1 0 0 1.57</pose>
<uri>https://fuel.gazebosim.org/1.0/accurrent/models/MBARI Tethys LRAUV</uri>
<uri>https://fuel.gazebosim.org/1.0/arjo129/models/LRAUV-PostIonic</uri>
<name>daphne</name>

<!-- Joint controllers -->
Expand Down Expand Up @@ -316,12 +303,6 @@
filename="gz-sim-hydrodynamics-system"
name="gz::sim::systems::Hydrodynamics">
<link_name>base_link</link_name>
<xDotU>-4.876161</xDotU>
<yDotV>-126.324739</yDotV>
<zDotW>-126.324739</zDotW>
<kDotP>0</kDotP>
<mDotQ>-33.46</mDotQ>
<nDotR>-33.46</nDotR>
<yUabsU>-6.2282</yUabsU>
<xU>0</xU>
<yVabsV>-601.27</yVabsV>
Expand Down
6 changes: 0 additions & 6 deletions tutorials/adding_system_plugins.md
Original file line number Diff line number Diff line change
Expand Up @@ -103,12 +103,6 @@ Uncomment the following block from `buoyant_turtle.sdf`:
filename="gz-sim-hydrodynamics-system"
name="gz::sim::systems::Hydrodynamics">
<link_name>base_link</link_name>
<xDotU>-0.04876161</xDotU>
<yDotV>-1.26324739</yDotV>
<zDotW>-1.26324739</zDotW>
<kDotP>0</kDotP>
<mDotQ>-0.3346</mDotQ>
<nDotR>-0.3346</nDotR>
<xUabsU>-0.62282</xUabsU>
<xU>-5</xU>
<yVabsV>-60.127</yVabsV>
Expand Down
14 changes: 8 additions & 6 deletions tutorials/files/theory_hydrodynamics/buoyant_cylinder.sdf
Original file line number Diff line number Diff line change
Expand Up @@ -291,6 +291,14 @@
<iyz>0</iyz>
<izz>0.61250000000000006</izz>
</inertia>
<fluid_added_mass>
<xx>0.04876161</xx>
<yy>1.26324739</yy>
<zz>1.26324739</zz>
<pp>0</pp>
<qq>0.3346</qq>
<rr>0.3346</rr>
</fluid_added_mass>
</inertial>

<collision name='collision'>
Expand Down Expand Up @@ -329,12 +337,6 @@
filename="gz-sim-hydrodynamics-system"
name="gz::sim::systems::Hydrodynamics">
<link_name>base_link</link_name>
<xDotU>-0.04876161</xDotU>
<yDotV>-1.26324739</yDotV>
<zDotW>-1.26324739</zDotW>
<kDotP>0</kDotP>
<mDotQ>-0.3346</mDotQ>
<nDotR>-0.3346</nDotR>
<xUabsU>-0.62282</xUabsU>
<xU>-5</xU>
<yVabsV>-60.127</yVabsV>
Expand Down
11 changes: 2 additions & 9 deletions tutorials/files/underwater_vehicles/buoyant_lrauv.sdf
Original file line number Diff line number Diff line change
Expand Up @@ -271,16 +271,10 @@
</plugin>

<!-- Uncomment to add hydrodynamics -->
<!-- <plugin
<plugin
arjo129 marked this conversation as resolved.
Show resolved Hide resolved
filename="gz-sim-hydrodynamics-system"
name="gz::sim::systems::Hydrodynamics">
<link_name>base_link</link_name>
<xDotU>-4.876161</xDotU>
<yDotV>-126.324739</yDotV>
<zDotW>-126.324739</zDotW>
<kDotP>0</kDotP>
<mDotQ>-33.46</mDotQ>
<nDotR>-33.46</nDotR>
<xUabsU>-6.2282</xUabsU>
<xU>0</xU>
<yVabsV>-601.27</yVabsV>
Expand All @@ -293,8 +287,7 @@
<mQ>0</mQ>
<nRabsR>-632.698957</nRabsR>
<nR>0</nR>
</plugin> -->

</plugin>
</include>
</model>

Expand Down
25 changes: 25 additions & 0 deletions tutorials/files/underwater_vehicles/my_lrauv/model.sdf
Original file line number Diff line number Diff line change
Expand Up @@ -60,7 +60,32 @@
<iyz>-0.0000000006729</iyz>
<izz>0.0002633558262</izz>
</inertia>
<fluid_added_mass>
<xx>4.876161</xx>
<xy>0.0</xy>
<xz>0.0</xz>
<xp>0.0</xp>
<xq>0.0</xq>
<xr>0.0</xr>
<yy>126.324739</yy>
<yz>0.0</yz>
<yp>0.0</yp>
<yq>0.0</yq>
<yr>0.0</yr>
<zz>126.324739</zz>
<zp>0.0</zp>
<zq>0.0</zq>
<zr>0.0</zr>
<pp>0.1916</pp>
<pq>33.46</pq>
<pr>0.0</pr>
<qq>0.0</qq>
<qr>33.46</qr>
<rr>0.0</rr>
</fluid_added_mass>

</inertial>

<collision name="collision">
<geometry>
<box>
Expand Down
Loading
Loading