Skip to content

Commit

Permalink
Wave Body MBARI: add collision mesh and change default BEM file (#77)
Browse files Browse the repository at this point in the history
* Wave Body MBARI: add collision mesh for buoy

- Add simplified collision meshes for the buoy at different levels of refinement.
- Use the mesh with 316 faces in the model.
- Add BEM file generated using Capytaine and the 5548 face mesh.

Signed-off-by: Rhys Mainwaring <[email protected]>

* Wave Body MBARI: change default the BEM data file

- The excitation data in the hdf5 file generated from WAMIT data has the wrong sign, use Capytaine / bemio generated file in the meanwhile.
- Simplify ramp function.

Signed-off-by: Rhys Mainwaring <[email protected]>
  • Loading branch information
srmainwaring committed Nov 30, 2022
1 parent b025023 commit ff049d0
Show file tree
Hide file tree
Showing 7 changed files with 65 additions and 16 deletions.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
21 changes: 18 additions & 3 deletions gz-waves-models/models/mbari_buoy/model.sdf
Original file line number Diff line number Diff line change
Expand Up @@ -21,6 +21,17 @@
The inertial data in the data sheet looks like it may be for a
coordinate system with y-up as the smallest diagonal element is Iyy
and we'd expect the inertia to be approx. symmetric about the z axis.
Collision mesh:
The collision mesh buoy_float_collision_wp_f316.stl was generated
in Blender from a simple bevelled cylinder created in FreeCAD.
- The bevel at the base of 45 deg does not quite align with the visual
which has a slightly different angle (shallower).
- The collision mesh has the origin set 0.41m above the base, which is
less than the 0.5m from the engineering diagram, but is set to align
with the visual buoy_float.stl which is offset -2.27m below the
waterplane (= base_link origin)
-->
<link name="base_link">
<pose>0 0 0 0 0 0</pose>
Expand Down Expand Up @@ -59,11 +70,15 @@
</material>
</visual>
<collision name="collision">
<pose>0 0 0.19 0 0 0 </pose>
<!-- <pose>0 0 0.19 0 0 0 </pose> -->
<pose>0 0 0 0 0 0 </pose>
<geometry>
<box>
<mesh>
<uri>model://mbari_buoy/meshes/buoy_float_collision_wp_f316.stl</uri>
</mesh>
<!-- <box>
<size>2.34 2.34 1</size>
</box>
</box> -->
</geometry>
</collision>
</link>
Expand Down
55 changes: 43 additions & 12 deletions gz-waves-models/worlds/mbari_buoy.sdf
Original file line number Diff line number Diff line change
Expand Up @@ -42,7 +42,7 @@
</light>

<include>
<uri>model://regular_waves_6s_2m</uri>
<uri>model://regular_waves_15s_2m</uri>
</include>

<include>
Expand All @@ -54,12 +54,22 @@
name="gz::sim::systems::LinearWaveBody">

<!-- BEM HDF5 data file -->
<hdf5_file>model://mbari_buoy/config/hydrodata/mbari_buoy.h5</hdf5_file>
<!--
TODO: check the generation of HDF5 from WAMIT data - there is a
sign difference in the excitation data. May be different conventions
used in Capytaine vs WAMIT. Testing in WEC-Sim suggests that
mbari_buoy.h5 excitation coefficients have the wrong sign.
-->
<!-- generated from WAMIT data: BuoyA5.1, BuoyA5.3 -->
<!-- <hdf5_file>model://mbari_buoy/config/hydrodata/mbari_buoy.h5</hdf5_file> -->

<!-- independently generated using Capytaine and WEC-Sim bemio -->
<hdf5_file>model://mbari_buoy/config/hydrodata/buoy_float_collision_wp_f5548.h5</hdf5_file>

<!-- waves parameter overrides -->
<waves>
<regular>
<period>6</period>
<period>15</period>
<height>2</height>
<direction>0</direction>
<phase>0</phase>
Expand All @@ -82,19 +92,40 @@
<!--
Dimensioned hydrodynamics coefficients for T=6.0s (w = 1.0472 rad/s)
-->
<!-- <hydro_coeffs>
<hydro_coeffs>
<scaled>0</scaled>
<hydrostatic>
<!-- cleaned coefficients for testing
<linear_restoring>
0. 0. 0. 0. 0. 0.
0. 0. 0. 0. 0. 0.
0. 0. 34690.6 0. 0. 0.
0. 0. 0. 14256.3 0. 0.
0. 0. 0. 0. 14256.3 0.
0. 0. 0. 0. 0. 0.
</linear_restoring>
0 0 0 0 0 0
0 0 0 0 0 0
0 0 34690 0 0 0
0 0 0 14256 0 0
0 0 0 0 14256 0
0 0 0 0 0 0
</linear_restoring> -->
</hydrostatic>
</hydro_coeffs> -->
<radiation>
<!-- symmetrised data for T=6s, H=2m - for testing
<added_mass>
704 0 0 0 343 0
0 704 0 -343 0 0
0 0 4592 0 0 0
0 -343 0 510 0 0
343 0 0 0 510 0
0 0 0 0 0 0
</added_mass> -->
<!-- as above, diagonals only - for testing
<added_mass>
704 0 0 0 0 0
0 704 0 0 0 0
0 0 4592 0 0 0
0 0 0 510 0 0
0 0 0 0 510 0
0 0 0 0 0 0
</added_mass> -->
</radiation>
</hydro_coeffs>

<!-- enable / disable forces -->
<forces>
Expand Down
5 changes: 4 additions & 1 deletion gz-waves/src/systems/linear_wave_body/LinearWaveBody.cc
Original file line number Diff line number Diff line change
Expand Up @@ -179,6 +179,9 @@ class gz::sim::systems::LinearWaveBodyPrivate
///
/// 11. Optimise interpolation to eliminate unnecessary copies.
///
/// 12. Use math::eigen3::convert for converting Matrix and Vector types.
///
///
///

/// \brief WEC-Sim BEMIO hydro data structure (read from HDF5 file)
Expand Down Expand Up @@ -2336,7 +2339,7 @@ void LinearWaveBodyPrivate::UpdateExcitationForces(const UpdateInfo &_info,
double tau = t/tr;

if (tau < 1)
return 0.5*(1.0 + std::sin(3.0/2.0*GZ_PI + GZ_PI*tau));
return 0.5*(1.0 + std::cos(GZ_PI*(1.0 + tau));
else
return 1.0;
};
Expand Down

0 comments on commit ff049d0

Please sign in to comment.