Overview
This tutorial explains how to create and load an underwater lander vehicle in Gazebo. This type of vehicles don't usually have control surfaces or thrusters. They typically sink until they reach the seafloor or certain depth and go back to the surface while they collect sensor measurements.
Related tutorials
https://gazebosim.org/api/sim/8/create_vehicle.html
https://gazebosim.org/api/sim/8/adding_visuals.html
https://gazebosim.org/api/sim/8/frame_reference.html
https://gazebosim.org/api/sim/8/adding_system_plugins.html
https://gazebosim.org/api/sim/8/theory_buoyancy.html
https://gazebosim.org/api/sim/8/theory_hydrodynamics.html
Create your vehicle
As an example, we'll go through the process of creating an Inkfish underwater lander vehicle.
Basic SDF
Create a workspace to store your brand new model named my_lander
.
Download the model.config
file and copy it within that directory:
In its simple version, the lander does not have any moving pieces, so the SDF model only has one single link, base_link
in our case.
Create a model.sdf
and paste the following content:
We can now test it in Gazebo. Launch it with:
You should see your model visualized as a box.
Adding visuals
Let's now add nicer-looking visuals to our lander. Download the following COLLADA
mesh file from here.
Replace the chassis_visual
element in your model.sdf
with the following block:
And launch Gazebo to see the results:
Your box should now be replaced with a better looking mesh.
Checking frame of reference
Launch your lander in Gazebo as we did before:
You can visualize the frame of reference of your vehicle by loading the plugin Transform Control
from the GUI.
Then, click on the vehicle, and then, click on the Translate mode
icon. You'll now visualize your lander frame of reference. As this is the expected frame of reference, we won't need to apply changes in the COLLADA mesh or add any <pose>
offset to our model.sdf
.
Adding plugins
Buoyancy
We are going to start extending our model adding buoyancy properties. For that, we need to do two things:
- Create a Gazebo world SDF file and load the buoyancy world plugin.
- Add
<collision>
elements to our lander model SDF.
Let's start with the world. Download the following world:
Now, open your ~/gazebo_maritime/models/my_lander/model.sdf
and add the low volume outer collision elements to the base_link
:
You can now launch Gazebo:
And visualize collisions by right-clicking on the lander, and the, View
-> Collisions
.
If you hit play, your lander will sink as expected. Although the buoyancy plugin is loaded, notice that all the collision elements that we added are low-volume. This is on purpose to make sure that our model can collide with obstacles. However, it's generating very little buoyancy.
Let's now compute the reference volume that will make the lander neutrally buoyant.
$$volume\_neutral = \frac{mass}{waterDensity} = \frac{1209.175}{1025} = 1.1796829268292683$$
Now, let's account for the volume that our lander already has thanks to the low-volume outer collision elements:
$$outer\_volume = 2*1.1325*1.1503*0.000001 + 2*0.000001*1.1503*1.5 + 2*1.325* 0.000001*1.5 = 1.00313295e-05$$
Let's now compute the volume of the main buoyancy <collision>
element:
$$main\_buoyancy\_volume = 1.1796829268292683 - 1.00313295e-05 = 1.1796728954997684$$
Let's verify that our lander is neutrally buoyant now. Add the following collision element to your base_link
:
And launch Gazebo:
Hit play, and your lander should now maintain depth!
This an example to illustrate how to calculate this reference value, however a lander is normally designed to sink.
Change the buoyancy plugin to the following value to be more realistic:
And launch Gazebo:
Hit play and the lander will slowly sink and hit the seafloor.
Hydrodynamics
As an underwater vehicle, the lander should be influenced by the water as it moves. We can do that by attaching the hydrodynamics
plugin to our lander. Add the next SDF block to your model.sdf
. Note that we have empirically adjusted its values. Follow the hydrodynamics tutorial for recommendations about how to tune its values.
Drop weight
A common feature in maritime landers is to include a drop weight device. When this device is enabled, some part of the vehicle is detached from the main chassis. At this point, the vehicle becomes positive buoyant, and starts moving up towards the water surface.
In order to simulate this behavior, we'll need to make two changes to our lander model:
- Add a new separate link to act as the drop weight.
- Attach a plugin to disconnect the previous link on demand.
Let's add the following SDF block to your model.sdf
:
The mass of the drop weight changes the buoyancy properties of the lander. Let's calculate the reference values:
$$volume\_neutral\_with\_dropweight = \frac{mass}{waterDensity} = \frac{1209.175 + 120}{1025} = 1.2967560975609755$$
$$volume\_neutral\_without\_dropweight = \frac{mass}{waterDensity} = \frac{1209.175}{1025} = 1.1796829268292683$$
We're looking for a volume that's lower than volume_neutral_with_dropweight
to cause the lander to sink from its initial configuration, and bigger than volume_neutral_without_dropweight
to cause the lander to go back to the surface when the drop weight is enabled. Let's choose 1.24
as the volume for our main buoyancy collision element. Replace the buoyancy
collision element with:
And launch Gazebo:
Hit play and observe how the lander sinks until it hits the seafloor. Then, enable the drop weight to detach the extra link:
Observe how your lander comes to the surface.