-
Notifications
You must be signed in to change notification settings - Fork 193
hydrodynamic_params_tutorial
- The hydrodynamics models we use for the default USV is implemented in the Simple Hydrodynamics plugin
- The coefficients of this plugin characterize the linear and nonlinear drag on the WAM-V
- 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 of Surface plugin to each hull, and an instance of the Simple Hydrodynamics plugin to the whole boat (
wamv_gazebo_dynamics_plugin.xacro
).
For the Surface plugin:
<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 the WAM-V, try decreasing hull_length
by half.
It's worth noting that the plugin assumes a cylindrical hull by default, but it is possible to override this behavior.
Recompile your workspace:
cd <VRX_WS>
GZ_VERSION=garden
colcon build --merge-install
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.
Return modified WAM-V Surface plugin variables to their original values.
For the Simple Hydrodynamics plugin
<plugin
filename="libSimpleHydrodynamics.so"
name="vrx::SimpleHydrodynamics">
<link_name>${namespace}/base_link</link_name>
<!-- Added mass -->
<xDotU>0.0</xDotU>
<yDotV>0.0</yDotV>
<nDotR>0.0</nDotR>
<!-- Linear and quadratic drag -->
<xU>100.0</xU>
<xUU>150.0</xUU>
<yV>100.0</yV>
<yVV>100.0</yVV>
<zW>500.0</zW>
<kP>300.0</kP>
<kPP>600.0</kPP>
<mQ>900.0</mQ>
<mQQ>900.0</mQQ>
<nR>800.0</nR>
<nRR>800.0</nRR>
</plugin>
xU
and xUU
are the linear and nonlinear drag terms, respectively, in the surge direction. Increase the value of each variable to the point of being able to see a visible change in the simulation (muliplying by two seems like a good start). Then, rebuild following Steps 2 & 3.
The WAM-V's driving characteristics should have changed noticeably. If you increased the values as suggested, the WAM-V should seem slower in the surge direction.
For a deeper dive into the effect each coefficient has, this FAU Publication https://doi.org/10.1016/j.oceaneng.2016.09.037 gives a good overview.