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

Adding viscous drag via hydrodynamics plugin #32

Merged
merged 19 commits into from
Jan 31, 2023
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
2 changes: 2 additions & 0 deletions buoy_description/models/mbari_wec/model.sdf
Original file line number Diff line number Diff line change
Expand Up @@ -6,6 +6,7 @@
<uri>package://buoy_description/models/mbari_wec_base</uri>
</include>

<!-- Electro-Hydraulic PTO Plugin -->
<plugin filename="ElectroHydraulicPTO" name="buoy_gazebo::ElectroHydraulicPTO">
<PrismaticJointName>HydraulicRam</PrismaticJointName>
<PistonArea>1.375</PistonArea>
Expand Down Expand Up @@ -67,6 +68,7 @@
<P2>1212740</P2>
</plugin>

<!-- Adding Friction to PTO -->
<plugin filename="PTOFriction" name="buoy_gazebo::PTOFriction">
<PrismaticJointName>HydraulicRam</PrismaticJointName>
</plugin>
Expand Down
42 changes: 42 additions & 0 deletions buoy_description/models/mbari_wec_base/model.sdf.em
Original file line number Diff line number Diff line change
Expand Up @@ -463,5 +463,47 @@ pto_scale = pto_inner_radius / pto_stl_inner_radius
</axis>
</joint>

<!-- Viscous Drag for Buoy -->
<plugin filename="gz-sim-hydrodynamics-system"
name="gz::sim::systems::Hydrodynamics">
<link_name>Buoy</link_name>
<xUabsU>-430</xUabsU> <!-- Surge Quadratic Drag kg/m -->
<yVabsV>-430</yVabsV> <!-- Sway Quadratic Drag kg/m -->
<zWabsW>-3280</zWabsW> <!-- Heave Quadratic Drag kg/m -->
<kPabsP>-880</kPabsP> <!-- Roll Quadratic Drag kg m^2 -->
<mQabsQ>-880</mQabsQ> <!-- Pitch Quadratic Drag kg m^2 -->
<nRabsR>-50</nRabsR> <!-- Yaw Quadratic Drag kg m^2 -->
<disable_coriolis>true</disable_coriolis>
<disable_added_mass>true</disable_added_mass>
</plugin>

<!-- Viscous Drag for PTO -->
<plugin filename="gz-sim-hydrodynamics-system"
name="gz::sim::systems::Hydrodynamics">
<link_name>PTO</link_name>
<xUabsU>-1140</xUabsU> <!-- Surge Quadratic Drag kg/m -->
<yVabsV>-1140</yVabsV> <!-- Sway Quadratic Drag kg/m -->
<zWabsW>-50</zWabsW> <!-- Heave Quadratic Drag kg/m -->
<kPabsP>-195400</kPabsP> <!-- Roll Quadratic Drag kg m^2 -->
<mQabsQ>-195400</mQabsQ> <!-- Pitch Quadratic Drag kg m^2 -->
<nRabsR>-50</nRabsR> <!-- Yaw Quadratic Drag kg m^2 -->
<disable_coriolis>true</disable_coriolis>
<disable_added_mass>true</disable_added_mass>
</plugin>

<!-- Viscous Drag for Heave Cone -->
<plugin filename="gz-sim-hydrodynamics-system"
name="gz::sim::systems::Hydrodynamics">
<link_name>HeaveCone</link_name>
<xUabsU>-1580</xUabsU> <!-- Surge Quadratic Drag kg/m -->
<yVabsV>-1580</yVabsV> <!-- Sway Quadratic Drag kg/m -->
<zWabsW>-3900</zWabsW> <!-- Vertical Quadratic Drag kg/m: -3200 open, -3900 close -->
<kPabsP>-4620</kPabsP> <!-- Roll Quadratic Drag kg m^2 -->
<mQabsQ>-4620</mQabsQ> <!-- Pitch Quadratic Drag kg m^2 -->
<nRabsR>-50</nRabsR> <!-- Yaw Quadratic Drag kg m^2 -->
<disable_coriolis>true</disable_coriolis>
<disable_added_mass>true</disable_added_mass>
</plugin>

</model>
</sdf>
1 change: 1 addition & 0 deletions buoy_gazebo/worlds/mbari_wec.sdf
Original file line number Diff line number Diff line change
Expand Up @@ -48,6 +48,7 @@
<include merge="true">
<uri>package://buoy_description/models/mbari_wec_ros</uri>
</include>

</model>

</world>
Expand Down
251 changes: 251 additions & 0 deletions buoy_gazebo/worlds/test_viscous_drag.sdf
Original file line number Diff line number Diff line change
@@ -0,0 +1,251 @@
<?xml version="1.0" ?>
<sdf version="1.8">
<world name="test_world">

<physics name="1ms" type="ignored">
<max_step_size>.001</max_step_size>
<real_time_factor>1.0</real_time_factor>
</physics>

<!-- rely on world plugins from server.config -->
<gui fullscreen="0">
<plugin filename="MinimalScene" name="3D View">
<gz-gui>
<title>3D View</title>
<property type="bool" key="showTitleBar">false</property>
<property type="string" key="state">docked</property>
</gz-gui>

<engine>ogre2</engine>
<scene>scene</scene>
<ambient_light>0.4 0.4 0.4</ambient_light>
<background_color>0.8 0.8 0.8</background_color>
<camera_pose>21.5 -0.5 -0.6 0 0.4 3.14</camera_pose>
</plugin>

<!-- Plugins that add functionality to the scene -->
<plugin filename="EntityContextMenuPlugin" name="Entity context menu">
<gz-gui>
<property key="state" type="string">floating</property>
<property key="width" type="double">5</property>
<property key="height" type="double">5</property>
<property key="showTitleBar" type="bool">false</property>
</gz-gui>
</plugin>
<plugin filename="GzSceneManager" name="Scene Manager">
<gz-gui>
<property key="resizable" type="bool">false</property>
<property key="width" type="double">5</property>
<property key="height" type="double">5</property>
<property key="state" type="string">floating</property>
<property key="showTitleBar" type="bool">false</property>
</gz-gui>
</plugin>
<plugin filename="InteractiveViewControl" name="Interactive view control">
<gz-gui>
<property key="resizable" type="bool">false</property>
<property key="width" type="double">5</property>
<property key="height" type="double">5</property>
<property key="state" type="string">floating</property>
<property key="showTitleBar" type="bool">false</property>
</gz-gui>
</plugin>
<plugin filename="CameraTracking" name="Camera Tracking">
<gz-gui>
<property key="resizable" type="bool">false</property>
<property key="width" type="double">5</property>
<property key="height" type="double">5</property>
<property key="state" type="string">floating</property>
<property key="showTitleBar" type="bool">false</property>
</gz-gui>
</plugin>
<plugin filename="MarkerManager" name="Marker manager">
<gz-gui>
<property key="resizable" type="bool">false</property>
<property key="width" type="double">5</property>
<property key="height" type="double">5</property>
<property key="state" type="string">floating</property>
<property key="showTitleBar" type="bool">false</property>
</gz-gui>
</plugin>
<plugin filename="SelectEntities" name="Select Entities">
<gz-gui>
<property key="resizable" type="bool">false</property>
<property key="width" type="double">5</property>
<property key="height" type="double">5</property>
<property key="state" type="string">floating</property>
<property key="showTitleBar" type="bool">false</property>
</gz-gui>
</plugin>
<plugin filename="VisualizationCapabilities" name="Visualization Capabilities">
<gz-gui>
<property key="resizable" type="bool">false</property>
<property key="width" type="double">5</property>
<property key="height" type="double">5</property>
<property key="state" type="string">floating</property>
<property key="showTitleBar" type="bool">false</property>
</gz-gui>
</plugin>

<!-- Translate / rotate -->
<plugin filename="TransformControl" name="Transform control">
<gz-gui>
<property key="resizable" type="bool">false</property>
<property key="width" type="double">250</property>
<property key="height" type="double">50</property>
<property key="state" type="string">floating</property>
<property key="showTitleBar" type="bool">false</property>
<property key="cardBackground" type="string">#777777</property>
</gz-gui>

<!-- disable legacy features used to connect this plugin to GzScene3D -->
<legacy>false</legacy>
</plugin>

<!-- World control -->
<plugin filename="WorldControl" name="World control">
<gz-gui>
<title>World control</title>
<property type="bool" key="showTitleBar">false</property>
<property type="bool" key="resizable">false</property>
<property type="double" key="height">72</property>
<property type="double" key="width">121</property>
<property type="double" key="z">1</property>

<property type="string" key="state">floating</property>
<anchors target="3D View">
<line own="left" target="left"/>
<line own="bottom" target="bottom"/>
</anchors>
</gz-gui>

<play_pause>true</play_pause>
<step>true</step>
<start_paused>true</start_paused>
<use_event>true</use_event>

</plugin>

<!-- World statistics -->
<plugin filename="WorldStats" name="World stats">
<gz-gui>
<title>World stats</title>
<property type="bool" key="showTitleBar">false</property>
<property type="bool" key="resizable">false</property>
<property type="double" key="height">110</property>
<property type="double" key="width">290</property>
<property type="double" key="z">1</property>

<property type="string" key="state">floating</property>
<anchors target="3D View">
<line own="right" target="right"/>
<line own="bottom" target="bottom"/>
</anchors>
</gz-gui>

<sim_time>true</sim_time>
<real_time>true</real_time>
<real_time_factor>true</real_time_factor>
<iterations>true</iterations>
</plugin>

<plugin filename="TransportPlotting" name="Transport Plotting">
<gz-gui>
<property key="state" type="string">docked</property>
</gz-gui>
</plugin>

<plugin filename="TopicViewer" name="Topic Viewer">
<gz-gui>
<property key="state" type="string">docked</property>
</gz-gui>
</plugin>

</gui>

<light name="sun" type="directional">
<cast_shadows>true</cast_shadows>
<pose>0 0 10 0 0 0</pose>
<diffuse>0.8 0.8 0.8 1</diffuse>
<specular>0.2 0.2 0.2 1</specular>
<attenuation>
<range>1000</range>
<constant>0.9</constant>
<linear>0.01</linear>
<quadratic>0.001</quadratic>
</attenuation>
<direction>-0.5 0.1 -0.9</direction>
</light>

<model name="water_plane">
<static>true</static>
<link name="link">
<visual name="water_plane">
<geometry>
<plane>
<size>100 100</size>
<normal>0 0 1</normal>
</plane>
</geometry>
<material>
<ambient>0 0 1 0.5</ambient>
<diffuse>0 0 1 0.5</diffuse>
<specular>0 0 1 0.5</specular>
</material>
</visual>
</link>
</model>

<model name="MBARI_WEC_ROS">
<pose relative_to="world">0 -5 -2 0 0 0</pose>

<include merge="true">
<uri>package://buoy_description/models/mbari_wec_ros</uri>
</include>

<!-- Viscous Drag for Buoy -->
<plugin filename="gz-sim-hydrodynamics-system"
name="gz::sim::systems::Hydrodynamics">
<link_name>Buoy</link_name>
<xUabsU>-430</xUabsU> <!-- Surge Quadratic Drag kg/m -->
<yVabsV>-430</yVabsV> <!-- Sway Quadratic Drag kg/m -->
<zWabsW>-3280</zWabsW> <!-- Heave Quadratic Drag kg/m -->
<kPabsP>-880</kPabsP> <!-- Roll Quadratic Drag kg m^2 -->
<mQabsQ>-880</mQabsQ> <!-- Pitch Quadratic Drag kg m^2 -->
<nRabsR>-50</nRabsR> <!-- Yaw Quadratic Drag kg m^2 -->
<disable_coriolis>true</disable_coriolis>
<disable_added_mass>true</disable_added_mass>
</plugin>

<!-- Viscous Drag for PTO -->
<plugin filename="gz-sim-hydrodynamics-system"
name="gz::sim::systems::Hydrodynamics">
<link_name>PTO</link_name>
<xUabsU>-1140</xUabsU> <!-- Surge Quadratic Drag kg/m -->
<yVabsV>-1140</yVabsV> <!-- Sway Quadratic Drag kg/m -->
<zWabsW>-50</zWabsW> <!-- Heave Quadratic Drag kg/m -->
<kPabsP>-195400</kPabsP> <!-- Roll Quadratic Drag kg m^2 -->
<mQabsQ>-195400</mQabsQ> <!-- Pitch Quadratic Drag kg m^2 -->
<nRabsR>-50</nRabsR> <!-- Yaw Quadratic Drag kg m^2 -->
<disable_coriolis>true</disable_coriolis>
<disable_added_mass>true</disable_added_mass>
</plugin>

<!-- Viscous Drag for Heave Cone -->
<plugin filename="gz-sim-hydrodynamics-system"
name="gz::sim::systems::Hydrodynamics">
<link_name>HeaveCone</link_name>
<xUabsU>-1580</xUabsU> <!-- Surge Quadratic Drag kg/m -->
<yVabsV>-1580</yVabsV> <!-- Sway Quadratic Drag kg/m -->
<zWabsW>-3900</zWabsW> <!-- Vertical Quadratic Drag kg/m: -3200 open, -3900 close -->
<kPabsP>-4620</kPabsP> <!-- Roll Quadratic Drag kg m^2 -->
<mQabsQ>-4620</mQabsQ> <!-- Pitch Quadratic Drag kg m^2 -->
<nRabsR>-50</nRabsR> <!-- Yaw Quadratic Drag kg m^2 -->
<disable_coriolis>true</disable_coriolis>
<disable_added_mass>true</disable_added_mass>
</plugin>

</model>

</world>
</sdf>