Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Buoyancy plugin refactor #500

Merged
merged 16 commits into from
Sep 8, 2022
22 changes: 20 additions & 2 deletions vrx_ign/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -20,6 +20,8 @@ find_package(ignition-plugin1 REQUIRED COMPONENTS loader register)
set(IGN_PLUGIN_VER ${ignition-plugin1_VERSION_MAJOR})
find_package(ignition-rendering6 REQUIRED)
set(IGN_RENDERING_VER ${ignition-rendering6_VERSION_MAJOR})
find_package(ignition-utils1 REQUIRED)
set(IGN_UTILS_VER ${ignition-utils1_VERSION_MAJOR})
find_package(sdformat12 REQUIRED)

find_package(std_msgs REQUIRED)
Expand All @@ -44,6 +46,22 @@ install(
TARGETS Waves
DESTINATION lib)

# Buoyancy
add_library(PolyhedraBuoyancyDrag SHARED
src/PolyhedraBuoyancyDrag.cc
src/PolyhedronVolume.cc
src/ShapeVolume.cc
)
target_link_libraries(PolyhedraBuoyancyDrag PUBLIC
ignition-common${IGN_COMMON_VER}::ignition-common${IGN_COMMON_VER}
ignition-gazebo${IGN_GAZEBO_VER}::core
ignition-math${IGN_MATH_VER}
Waves
)
install(
TARGETS PolyhedraBuoyancyDrag
DESTINATION lib)

# Plugins
list(APPEND VRX_IGN_PLUGINS
SimpleHydrodynamics
Expand All @@ -57,8 +75,9 @@ foreach(PLUGIN ${VRX_IGN_PLUGINS})
ignition-gazebo${IGN_GAZEBO_VER}::core
ignition-plugin${IGN_PLUGIN_VER}::ignition-plugin${IGN_PLUGIN_VER}
ignition-rendering${IGN_RENDERING_VER}::ignition-rendering${IGN_RENDERING_VER}
ignition-utils${IGN_UTILS_VER}::ignition-utils${IGN_UTILS_VER}
Waves
)
)
endforeach()

install(
Expand All @@ -78,5 +97,4 @@ install(DIRECTORY
launch
DESTINATION share/${PROJECT_NAME})


ament_package()
40 changes: 36 additions & 4 deletions vrx_ign/models/wam-v/model.sdf.erb
Original file line number Diff line number Diff line change
Expand Up @@ -69,16 +69,48 @@ end
<topic><%= $model_name%>/right/thruster/joint/cmd_pos</topic>
</plugin>

<!-- Left hull -->
<plugin
filename="libSurface.so"
name="vrx::Surface">
<link_name>base_link</link_name>
<vehicle_length>4.9</vehicle_length>
<vehicle_width>2.4</vehicle_width>
<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>
<size><%= $wavefield_size%> <%= $wavefield_size%></size>
<cell_count><%= $wavefield_cell_count%> <%=$wavefield_cell_count%></cell_count>
<wave>
<model>PMS</model>
<period>5.0</period>
<number>3</number>
<scale>1.1</scale>
<gain>0.3</gain>
<direction>1 0</direction>
<angle>0.4</angle>
<tau>2.0</tau>
<amplitude>0.0</amplitude>
<steepness>0.0</steepness>
</wave>
</wavefield>
</plugin>

<!-- Waves -->
<!-- Right hull -->
<plugin
filename="libSurface.so"
name="vrx::Surface">
<link_name>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>
<size><%= $wavefield_size%> <%= $wavefield_size%></size>
<cell_count><%= $wavefield_cell_count%> <%=$wavefield_cell_count%></cell_count>
Expand All @@ -87,7 +119,7 @@ end
<period>5.0</period>
<number>3</number>
<scale>1.1</scale>
<gain>0.5</gain>
<gain>0.3</gain>
<direction>1 0</direction>
<angle>0.4</angle>
<tau>2.0</tau>
Expand Down
Loading