srmainwaring / asv_wave_sim

This package contains plugins that support the simulation of waves and surface vessels in Gazebo.
GNU General Public License v3.0
122 stars 34 forks source link

Update visuals using dynamic textures #37

Closed srmainwaring closed 2 years ago

srmainwaring commented 2 years ago

This PR adds support for using textures to update the visuals rather than vertex buffers.

Details

Overview

There are now two methods that can be used to update the waves visuals. The first is the existing approach that updates the vertex, normal and tangent buffers each frame and is selected using the parameter

<mesh_deformation_method>DYNAMIC_GEOMETRY</mesh_deformation_method>

This method uses PBS materials (i.e. no custom shader) and is the default configuration for the waves model.

The second method updates textures for the displacement and surface derivatives. It is selected using:

<mesh_deformation_method>DYNAMIC_TEXTURE</mesh_deformation_method>

and is the method used in the new model ocean_waves. This approach uses custom shaders which may be configured using the shader parameters in the model. This approach is suitable for tiling large areas of ocean.

Parameters

The visual plugin has new parameters to select the deformation method and the tiling

<plugin
    filename="gazebo_marine1-waves-visual-system"
    name="ignition::gazebo::systems::WavesVisual">
  <static>0</static>
  <mesh_deformation_method>DYNAMIC_TEXTURE</mesh_deformation_method>
  <tiles_x>-10 10</tiles_x>
  <tiles_y>-5 5</tiles_y>
  <wave>...</wave>
</plugin>

The <tiles_x> and <tiles_y> elements specify a range of tiles with the offset being from the origin.

When using a custom shader, the default parameters may be overridden using the parameters listed below:

<plugin
    filename="gazebo_marine1-waves-visual-system"
    name="ignition::gazebo::systems::WavesVisual">
  ...
  <!-- shader program -->
  <shader language="metal">
    <vertex>materials/waves_vs.metal</vertex>
    <fragment>materials/waves_fs.metal</fragment>
  </shader>

  <!-- vertex shader params -->
  <param>
    <shader>vertex</shader>
    <name>world_matrix</name>
  </param>
  <param>
    <shader>vertex</shader>
    <name>worldviewproj_matrix</name>
  </param>
  <param>
    <shader>vertex</shader>
    <name>camera_position</name>
  </param>
  <param>
    <shader>vertex</shader>
    <name>rescale</name>
    <value>0.5</value>
    <type>float</type>
  </param>
  <param>
    <shader>vertex</shader>
    <name>bumpScale</name>
    <value>128 128</value>
    <type>float_array</type>
  </param>
  <param>
    <shader>vertex</shader>
    <name>bumpSpeed</name>
    <value>0.01 0.01</value>
    <type>float_array</type>
  </param>
  <param>
    <shader>vertex</shader>
    <name>t</name>
    <value>TIME</value>
  </param>

  <!-- pixel shader params -->
  <param>
    <shader>fragment</shader>
    <name>deepColor</name>
    <value>0.0 0.05 0.2 1.0</value>
    <type>float_array</type>
  </param>
  <param>
    <shader>fragment</shader>
    <name>shallowColor</name>
    <value>0.0 0.1 0.3 1.0</value>
    <type>float_array</type>
  </param>
  <param>
    <shader>fragment</shader>
    <name>fresnelPower</name>
    <value>5.0</value>
    <type>float</type>
  </param>
  <param>
    <shader>fragment</shader>
    <name>hdrMultiplier</name>
    <value>0.4</value>
    <type>float</type>
  </param>
  <param>
    <shader>fragment</shader>
    <name>bumpMap</name>
    <value>materials/wave_normals.dds</value>
    <type>texture</type>
    <arg>0</arg>
  </param>
  <param>
    <shader>fragment</shader>
    <name>cubeMap</name>
    <value>materials/skybox_lowres.dds</value>
    <type>texture_cube</type>
    <arg>1</arg>
  </param>
</plugin>