diff --git a/tutorials.md.in b/tutorials.md.in
index 34f61c9305..e36ec8e812 100644
--- a/tutorials.md.in
+++ b/tutorials.md.in
@@ -83,6 +83,10 @@ Gazebo @GZ_DESIGNATION_CAP@ library and how to use the library effectively.
## Maritime
+* \subpage theory_buoyancy "Buoyancy: " Describe the theory of operation of the
+buoyancy plugin.
+* \subpage theory_hydrodynamics "Hydrodynamics:" Describe the theory of
+operation of the hydrodynamics plugin.
* \subpage create_vehicle "Create a maritime vehicle:" How to design a maritime
model.
* \subpage adding_visuals "Adding visuals:" How to import 3D meshes into Gazebo
diff --git a/tutorials/files/theory_hydrodynamics/buoyant_cylinder.sdf b/tutorials/files/theory_hydrodynamics/buoyant_cylinder.sdf
new file mode 100644
index 0000000000..60e84d11d8
--- /dev/null
+++ b/tutorials/files/theory_hydrodynamics/buoyant_cylinder.sdf
@@ -0,0 +1,355 @@
+
+
+
+
+
+ 0.0 1.0 1.0
+ 0.0 0.7 0.8
+
+ false
+
+
+
+ true
+ 0 0 10 0 0 0
+ 1 1 1 1
+ 0.5 0.5 0.5 1
+
+ 1000
+ 0.9
+ 0.01
+ 0.001
+
+ -0.5 0.1 -0.9
+
+
+
+
+
+
+
+ 1025
+
+ 0
+ 1.125
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ 3D View
+ false
+ docked
+
+ ogre2
+ scene
+ 0.4 0.4 0.4
+ 0.8 0.8 0.8
+
+ 0 6 6 0 0.5 -1.57
+
+
+
+
+
+ 0.1
+
+ 3000000
+
+
+
+
+
+ floating
+ 5
+ 5
+ false
+
+
+
+
+
+
+
+
+ false
+ 5
+ 5
+ floating
+ false
+
+
+
+
+
+
+
+
+ false
+ 5
+ 5
+ floating
+ false
+
+
+
+
+
+
+
+
+ false
+ 5
+ 5
+ floating
+ false
+
+
+
+
+
+
+
+
+ false
+ 5
+ 5
+ floating
+ false
+
+ false
+
+
+
+
+
+
+
+ false
+ 5
+ 5
+ floating
+ false
+
+
+
+
+
+
+
+
+ false
+ 5
+ 5
+ floating
+ false
+
+
+
+
+
+
+
+
+ false
+ 5
+ 5
+ floating
+ false
+
+
+
+
+
+ World control
+ false
+ false
+ 72
+ 121
+ 1
+ floating
+
+
+
+
+
+ true
+ true
+ true
+
+
+
+
+ World stats
+ false
+ false
+ 110
+ 290
+ 1
+ floating
+
+
+
+
+
+ true
+ true
+ true
+ true
+
+
+
+ Inspector
+ docked_collapsed
+
+
+
+
+ docked_collapsed
+
+
+
+ 6
+ 0
+
+ 50000
+ 0 100000 0 0 0 0.32
+ 0 1 0 1
+
+
+
+ 100
+ 0
+
+ 1
+ 0 0 0 0 0 0
+ 0.5 0.5 0.5 1
+
+
+
+
+
+
+ true
+
+
+
+
+ 0 0 1
+
+ 300000 300000
+
+
+ 1.0
+
+
+
+
+
+
+
+
+
+ 0.02
+ 1
+
+
+
+
+
+
+
+ 0 0 0 0 0 0
+ 10
+
+ 0.35032999999999995
+ 0
+ 0
+ 0.35032999999999995
+ 0
+ 0.61250000000000006
+
+
+
+
+
+
+ 1 1 0.009948450858321252
+
+
+
+
+
+ 0.08 0 0.05 0 0 0
+
+
+ 0.35
+ 0.23
+
+
+
+
+
+
+
+ base_link
+ 0.2
+ 0.01
+ 0.1
+
+ 1 0
+
+
+
+
+
+ base_link
+ -0.04876161
+ -1.26324739
+ -1.26324739
+ 0
+ -0.3346
+ -0.3346
+ -0.62282
+ -5
+ -60.127
+ -5
+ -6.0127
+ -100
+ -0.001916
+ -1
+ -6.32698957
+ -1
+ -6.32698957
+ -1
+
+
+
+
+
+
diff --git a/tutorials/theory_buoyancy.md b/tutorials/theory_buoyancy.md
new file mode 100644
index 0000000000..aca219116b
--- /dev/null
+++ b/tutorials/theory_buoyancy.md
@@ -0,0 +1,98 @@
+\page theory_buoyancy
+
+# Overview
+
+This tutorial describes the theory of operation of the buoyancy plugin, an
+essential piece needed in most of the maritime simulations.
+
+# The buoyancy plugin
+
+This plugin is attached to the world to provide certain buoyancy to the
+vehicles. The buoyancy force opposes gravity exerted on the robot. The
+parameters of the plugin are configured via SDF in the world file. Check the
+[Buoyancy.hh](https://github.com/gazebosim/gz-sim/blob/gz-sim8/src/systems/buoyancy/Buoyancy.hh)
+Gazebo header file for a complete description of all the accepted parameters.
+
+The buoyancy plugin uses the `` elements of each SDF model to compute
+the volume of fluid displaced.
+
+A common pattern for the maritime domain is to create very thin collision
+elements surrounding the vehicle (with low volume) and a separate collision
+element within the vehicle itself. The collection of low volume collision
+elements work as a shell to generate contacts when necessary. The extra
+collision element is only used to generate the aggregated desired air volume.
+
+The outer set of collision elements in combination with the buoyancy collision
+element induce forces at the center of each `` element. If you
+followed the recommendation for creating low-volume outer collisions, the
+predominant force will be applied at the center of the buoyancy collision
+element. You can tune the location of that collision with the `` tag,
+to match your expected center of buoyancy.
+
+The buoyancy force is proportional to the volume of air in the vehicle according
+to this equation:
+
+$$volume\\_neutral = \frac{mass}{waterDensity}$$
+
+Pure water's density is `1000 kgm^-3` and seawater's density is `1025 kgm^-3`
+approximately. The mass of your vehicle is something that you'll decide or know
+by adding the mass of all your links. With that in mind, you'll be able to
+compute the volume of air that will make your vehicle neutrally buoyant.
+
+If your vehicle is neutrally buoyant, `volume_neutral` should be the total
+amount of volume that you should have by adjusting the size of your
+`` elements. If your vehicle is not neutrally buoyant, this value
+will serve as a reference. If the total volume is smaller than `volume_neutral`,
+the vehicle will sink. Otherwise, it will move up.
+
+The `/examples/worlds/buoyancy.sdf` SDF file (included with
+Gazebo) contains an example with three submarines. The first submarine is
+neutrally buoyant, the second sinks, and the third floats. Run the following
+command to see an example of a buoyancy plugin configured with a uniform fluid
+density:
+
+```bash
+gz sim buoyancy.sdf
+```
+
+# Graded buoyancy
+
+Often when simulating a maritime environment one may need to simulate both
+surface and underwater vessels. This means the buoyancy plugin needs to
+take into account two different fluids. One being water with a density of
+`~1000 kgm^-3` and another being air with a very light density of say `1 kgm^-3`.
+An example for such a configuration may be found in the
+`/examples/worlds/graded_buoyancy.sdf` world (included
+with Gazebo).
+
+```bash
+gz sim graded_buoyancy.sdf
+```
+
+You should be able to see a sphere bobbing up and down undergoing simple
+harmonic motion on the surface of the fluid (this is expected behaviour
+as the harmonic motion is usually damped by the hydrodynamic forces. See the
+hydrodynamics tutorial for an example of how to use it). The key part of this is
+
+```xml
+
+ 1000
+
+ 0
+ 1
+
+
+```
+
+The default density tag says that by default the world has a fluid density
+of `1000 kgm^-3`. This essentially states that by default the world is filled
+with dihydrogen monoxide (aka water). The `` tag essentially
+establishes the fact that there is a another fluid. The `` tag says
+that above z=0 there is another fluid with a different density. The density of
+that fluid is defined by the `` tag. We will be simulating air with a
+fluid density of `1 kgm^-3`.
+
+# Known limitations
+
+When the buoyancy plugin is configured in `graded buoyancy mode`, only ``
+and `` collision geometries are supported.
diff --git a/tutorials/theory_hydrodynamics.md b/tutorials/theory_hydrodynamics.md
new file mode 100644
index 0000000000..65853f5f10
--- /dev/null
+++ b/tutorials/theory_hydrodynamics.md
@@ -0,0 +1,166 @@
+\page theory_hydrodynamics
+
+# Overview
+
+This tutorial describes the theory of operation of the hydrodynamics plugin.
+It's heavily based on [3], and we recommend to read the full paper for a deeper
+understanding of its theory.
+
+# The hydrodynamics plugin
+
+To approximate the motion of the vehicle in the ocean environment, we adapt
+Fossen’s six degree-of-freedom robot-like vectorial model for marine craft [2]
+expressed as
+
+$$M ẍ + D(ẋ)ẋ + C(ẋ)ẋ = F$$
+
+where `M` is the added mass matrix, `D(ẋ)` is the damping matrix, `C(ẋ)` is the
+Coriolis matrix, and `ẋ` is the velocity six-vector.
+
+If present, ocean current is approximated by adding a term `vc` to the velocity:
+
+$$M ẍ + D(ẋ − vc )(ẋ − vc ) + C(ẋ − vc )(ẋ − vc ) = F$$
+
+The hydrodynamic forces include the added mass terms due to inertia of the
+surrounding fluid, the Coriolis-centripetal matrix for the added mass, and
+hydrodynamic damping. The hydrodynamic damping includes forces due to
+radiation-induced potential damping, skin friction, wave drift damping, vortex
+shedding and lifting forces. These effects are aggregated in the hydrodynamic
+damping matrix. This approximation of the hydrodynamic effects is implemented in
+this Gazebo plugin. The user defines the characteristics of the vessel under
+test through a vessel-specific configuration that includes the hydrodynamic
+derivatives. During each time step of the simulation, the plugin is executed
+with access to the state of the vessel and environment. The hydrodynamic force
+terms are calculated based on this state information and the user-defined vessel
+characteristics. The resulting force and moment values are then applied to the
+vessel through the Gazebo API for inclusion in the next iteration of the physics
+engine.
+
+The parameters of the plugin are configured via SDF in the model file.
+The next table summarizes all the available SDF parameters.
+
+Parameter | Description
+------------------| -------------
+ | Added mass in surge
+ | Added mass in sway
+ | Added mass in heave
+ | Added mass in roll
+ | Added mass in pitch
+ | Added mass in yaw
+ | Quadratic drag in surge
+ | Linear drag in surge
+ | Quadratic drag in sway
+ | Linear drag in sway
+ | Quadratic drag in heave
+ | Linear drag in heave
+ | Quadratic drag in roll
+ | Linear drag in roll
+ | Quadratic drag in pitch
+ | Linear drag in pitch
+ | Quadratic drag in yaw
+ | Linear drag in yaw
+ | Default ocean current vector
+
+**Note about added mass**: SDFormat also supports added mass natively. Until we
+deprecate the added mass parameters of this plugin, do not set the added mass
+parameters in both places, choose one (either in this plugin or under
+`` of your link).
+
+# A simple example
+
+Let's download the provided `buoyant_cylinder.sdf` world and run to see an
+example of a cylinder with three plugins attached:
+
+* Buoyancy: It will make the cylinder float on the surface of the water.
+* Hydrodynamics: It will simulate the damping generated by the fluid
+surrounding the cylinder.
+* Trajectory follower: It will apply some force to move the cylinder one meter
+in the positive `X` direction.
+
+```bash
+mkdir -p ~/gazebo_maritime/worlds
+wget https://raw.githubusercontent.com/gazebosim/gz-sim/main/tutorials/files/theory_hydrodynamics/buoyant_cylinder.sdf -o ~/gazebo_maritime/worlds/buoyant_cylinder.sdf
+gz sim -r ~/gazebo_maritime/worlds/buoyant_cylinder.sdf
+```
+
+Observe how the cylinder does not sink, and slowly makes its way until it
+reaches (1, 0, 0) in world coordinates.
+
+Now let's make a change in the hydrodynamics parameters. Considering that the
+model only moves in `X` direction (or surge in the maritime terminology), we're
+going to reduce the value of `` and `` parameters. Update these
+parameters to:
+
+```xml
+-0.32282
+-2.5
+```
+
+And run Gazebo again:
+
+```bash
+gz sim -r ~/gazebo_maritime/worlds/buoyant_cylinder.sdf
+```
+
+Notice how the vehicle does not stop at the 1 meter mark. Instead, the cylinder
+stops further. This is because we lowered the linear and quadratic drag in the
+direction that the model is moving.
+
+Let's now try the opposite. Go ahead and update the same parameters to the
+following values:
+
+```xml
+-3.5
+-20
+```
+
+And run Gazebo:
+
+```bash
+gz sim -r ~/gazebo_maritime/worlds/buoyant_cylinder.sdf
+```
+
+See how slow the cylinder moves. With these set of parameters we increased the
+damping in the surge axis, causing the vehicle to slowly move towards its goal.
+
+# Experimental - How to tune the parameters
+
+The hydrodynamics plugin requires a large number of parameters to model the
+added mass and drag behaviors of underwater vehicles. This section describes a
+method to generate an initial set of parameters for the hydrodynamics plugin.
+Note these parameters need to be tested and possibly tweaked to guarantee model stability.
+
+## Added mass
+
+A python library called [Capytaine](https://github.com/capytaine/capytaine) can
+be used to determine the added mass matrix of your vehicle. Capytaine enables
+the user to import a mesh (.stl), define a set of linear potential flow problems
+and solve these using the included Boundary Element Method (BEM) solver.
+
+Capytaine is typically used to model the interaction between floating bodies and
+waves, however it can be applied to ROVs by setting the wave frequency and free
+surface both to infinity (this assumes that the added mass is approximately
+constant since the ROV does not operate near the wave zone and that it operates
+in infinitely deep water respectively) [1](p.14), [2](p.18).
+
+Furthermore, it is recommended to use a simplified mesh when computing the added
+mass with Capytaine, since a complex mesh is computationally prohibitive.
+
+## Linear and quadratic damping
+
+Computing the linear and quadratic damping coefficients is generally not
+possible using computational analysis and is usually done experimentally
+[1](p.28). If determining the damping coefficients experimentally is not
+feasible, the same method described by Berg2012 can be used to estimate these
+values from a similar ROV [1](p.28-31).
+
+# References
+
+[1] BERG, V. Development and Commissioning of a DP system for ROV SF 30k,
+2012.
+
+[2] FOSSEN , T. I. Lecture notes: Ttk 4190 guidance, navigation and control of
+vehicles, February 2021.
+
+[3] BINGHAM, B. et al., Toward Maritime Robotic Simulation in Gazebo, Oceans
+Conference, 2019.