Skip to content

hydrodynamic_params_tutorial

crvogt edited this page Nov 23, 2023 · 4 revisions

Adjusting the Hydrodynamic Model

  • The buoyancy model we use for our default USV is implemented via our Surface plugin
  • This simulates buoyancy of objects at the surface of a fluid.
  • We attach an instance to each hull (wamv_gazebo_dynamics_plugin.xacro).
  • The plugin assumes a cylindrical hull by default, but it is possible to override this behavior.

Steps

Step 1: Modify parameters

<plugin filename="libSurface.so" name="vrx::Surface">
 <link_name>${namespace}/base_link</link_name>
 <hull_length>4.9</hull_length>
 <hull_radius>0.213</hull_radius>
 <fluid_level>0</fluid_level>
 <points>
    <point>0.6 1.03 0</point>
    <point>-1.4 1.03 0</point>
  </points>
  <wavefield>
    <topic>/vrx/wavefield/parameters</topic>
  </wavefield>
</plugin>

This is the attached plugin for a single hull boat, where the hull is simplified as a cylinder defined by hull_length and hull_radius.

For a twin-hull boat, such as the WAM-V, a separate instance of the plugin would need to be used for each hull.

For the WAM-V, try decreasing hull_length by half.

Step 2: Rebuild

Recompile your workspace:

cd <VRX_WS>
GZ_VERSION=garden 
colcon build --merge-install

Step 3: Test

Launch the simulation:

ros2 launch vrx_gz competition.launch.py world:=sydney_regatta

Zoom in to your WAM-V. If you only adjusted the hull length for one of the hulls, the WAM-V should appear lopsided. If you adjusted it for both hulls, the WAM-V should be sitting lower down in the water.

Clone this wiki locally