Skip to content

Configuration

Marco A. Gutiérrez edited this page Sep 14, 2022 · 21 revisions
  1. Acoustic communications
  2. The Doppler Velocity Log (DVL) Sensor
  3. Hydrodynamics
  4. Range Bearing
  5. Science Sensors System
  6. Tethys Comm Plugin
  7. World Comm Plugin
  8. Running Multiple Vehicles
  9. Improve Performance on Large Environments: Enable Levels
  10. Gazebo GUI and GUI Plugins
  11. Gazebo plugins

There are three ways of modifying the configuration of the Gazebo Simulation:

  • Through the SDFormat XML file that defines the entire system: this is the main and more detailed way of configuring the simulation. SDFormat is an XML format that describes objects and environments for robot simulators, visualization, control and the one used by Gazebo. You can find more about its specification, API and other documentation topics the SDFormat project website.
  • Through the gazebo transport layer: some of the configuration can be done through the Gazebo messaging system, using the topics and messages. For details regarding these options please have a look at the communications API and the messages section.
  • Through the graphical interface: some of the GUI plugins developed for the LRAUV system offer the user means to modify different configuration aspects through the graphical interface.

Since the GUI plugins are described in the architecture section and are self explanatory, and the communications API and the messages section explain how to use the gazebo transport means for configuration purposes, here the focus is on the details of SDFormat XML file configuration.

The SDFormat file will contain the details of the world to simulate as well as the plugins to load and their specific configuration. In order to load a plugin we only need to use the <plugin> tag accordingly. This is an example loading the physics plugin:

<plugin
  filename="gz-sim-physics-system"
  name="gz::sim::systems::Physics">
</plugin>

You can have a look at some of the world files provided to get familiar to how they are structured here.

Acoustic communications

The Acoustics Subsystem was designed to be very flexible. It consists of a data-bus on which all messages are publicly forwarded, a CommsModel which provides the environmental model that determines how a packet should be forwarded and whether or not the packet should be dropped or garbled. By default the Comms subsystem comes with a SimpleAcousticModel which only delays the transmission of the message based on the position of the transmitter and receiver in water. The comms model however is flexible enough so that we can apply the appropriate delays. New Comms subsytem models can be written, for that you can follow the instructions here.

The following options can be configured through the SDFormat file:

  • <address> : The address parameter. This is a 32 bit unsigned int which reflects the address which belongs to this vehicle. This will also create the topics /comms/external/<address>/rx on which this plugin will publish received messages and /comms/external/<address>/tx which this plugin subscribes to and publishes data.
  • <model_plugin_file> : This is the name of library containing the environmental comms Plugin. The file should be in your $TETHYS_COMMS_MODEL directory [Required].
  • <model_name> : This is the name of the environmental communications model. [Required]
  • <link_name> : The link to which the wireless transponder is attached to. [Required]
  • <external_comms_prefix> : Prefix on which to handle interaction between the application . [Optional, Defaults to /comms/external]
  • <internal_comms_prefix> : Prefix on which to send and listen for internal packets. [Optional, Defaults to /comms/internal]
  • <broadcast> : This defaults to true. When enabled all receivers will receive all packets. If false, then packets will be directed only to specified receivers. [Optional, Defaults to /comms/internal]
  • <timestep> : If defined this will allow the comms client to run at a higher clock resolution than the physics engine. This is useful when dealing with ranging. If the timestep is set larger than the physics engine dt then the engine will default to dt. Note: for consistency it is adviced that the dt is a multiple of timestep. [Optional. Seconds]

All other parameters are forwarded to the specific communication model.

Here is a configuration example of the Acustics Comms Plugin:

<plugin
       filename="AcousticCommsPlugin"
       name="tethys::AcousticCommsPlugin">
       <address>2</address>
       <model_plugin_file>simple_acoustic_model</model_plugin_file>
       <model_name>tethys::SimpleAcousticModel</model_name>
       <link_name>base_link</link_name>
       <timestep>0.00001</timestep>
       ...
</plugin>

The Doppler Velocity Log (DVL) Sensor

The Doppler Velocity Log (DVL) sensor is built as a custom rendering sensor to leverage GPU shaders for speed. By default, this sensor uses an x-forward, y-left, z-up coordinate frame to report all measurements. All acoustic beams' lobes are expected to face downwards. The configuration values that it accepts are the following:

  • <arrangement> describes the arrangement of acoustic beams in the DVL sensor frame. It may include a degrees attribute to signal use of degrees instead of radians for all angles within, defaulting to radians if left unspecified.
  • <arrangement><beam> describes one acoustic beam in the arrangement. May include an id attribute, defaulting to the last specified id plus 1 if left unspecified (or 0 if it's the first).
  • <arrangement><beam><aperture> sets the aperture angle for the acoustic beam's main lobe (modelled as a cone). Defaults to 90 degrees if left unspecified.
  • <arrangement><beam><rotation> sets the rotation angle of the acoustic beam's symmetry axis about the sensor frame z axis. Defaults to 0 degrees if left unspecified.
  • <arrangement><beam><tilt> sets the inclination angle of the acoustic beam's symmetry axis w.r.t. the sensor frame -z axis (ie. rotation about the -y axis). Defaults to 0 degrees if left unspecified.
  • <arrangement><resolution> sets the resolution of the beam arrangement at a 1 m distance. Defaults to 1 cm if left unspecified.
  • <arrangement><visualize> enables visual aids to evaluate acoustic beam arrangements. Beam lobes' are rendered and adjusted in size to match range measurements.
  • <visualize> enables visual aids to validate acoustic beam ranging. Beam shortest reflection paths are depicted.
  • <noise> sets the noise model for range measurements. Defaults to none if left unspecified
  • <type> sets the sensor type, either 'piston' or 'phased_array'. Defaults to unspecified.
  • <minimum_range> sets a lower bound for range measurements. Defaults to 1 cm if left unspecified.
  • <maximum_range> sets an upper bound for range measurements. Defaults to 100 m if left unspecified.
  • <reference_frame> sets a transform from the sensor frame to the reference frame in which all measurements are reported. Defaults to the identity transform.

Note the tethys::DopplerVelocityLogSystem plugin must be loaded for these custom sensors to be picked up and setup:

<plugin
  filename="DopplerVelocityLogSystem"
  name="tethys::DopplerVelocityLogSystem">
</plugin>

The following is an example of the configured DVL:

<sensor type="custom" gazeb:type="dvl">
  <gazebo:dvl>
    <arrangement degrees="true">
      <beam id="1">
        <aperture></aperture>
        <rotation></rotation>
        <tilt></tilt>
      </beam>
      <resolution></resolution>
      <visualize></visualize>
    </arrangement>
    <visualize></visualize>
    <noise type="gaussian">
      <stddev></stddev>
    </noise>
    <minimum_range></minimum_range>
    <maximum_range></maximum_range>
    <reference_frame></reference_frame>
  </gazebo:dvl>
</sensor>

Hydrodynamics

This class provides hydrodynamic behaviour for underwater vehicles. It is based off Brian Bingham's plugin for VRX which in turn is based of fossen's equations described in "Guidance and Control of Ocean Vehicles" 1.

These are the values that can be set via Plugin Parameters:

  • <xDotU> Added mass in surge.
  • <yDotU> Added mass in sway.
  • <zDotW> Added mass in heave.
  • <kDotP> Added mass in roll.
  • <mDotQ> Added mass in pitch.
  • <nDotR> Added mass in yaw.
  • <xU> Linear drag in surge.
  • <xUU> Quadratic drag in surge.
  • <yV> Linear drag in sway.
  • <yVV> Quadratic drag in sway.
  • <zW> Linear drag in heave.
  • <zWW> Quadratic drag in heave.
  • <kP> Linear drag in roll.
  • <kPP> Quadratic drag in roll.
  • <mQ> Linear drag in pitch.
  • <mQQ> Quadratic drag in pitch.
  • <nR> Linear drag in yaw.
  • <nRR> Quadratic drag in yaw.

This is an example of the configured hydrodynamics plugin:

<plugin
  filename="HydrodynamicsPlugin"
  name="tethys::HydrodynamicsPlugin">
  <link_name>base_link</link_name>
  <enable_coriolis>false</enable_coriolis>
  <xDotU>-4.876161</xDotU>
  <yDotV>-126.324739</yDotV>
  <zDotW>-126.324739</zDotW>
  <kDotP>0</kDotP>
  <mDotQ>-33.46</mDotQ>
  <nDotR>-33.46</nDotR>
  <xUU>-6.2282</xUU>
  <xU>0</xU>
  <yVV>-601.27</yVV>
  <yV>0</yV>
  <zWW>-601.27</zWW>
  <zW>0</zW>
  <kPP>-0.1916</kPP>
  <kP>0</kP>
  <mQQ>-632.698957</mQQ>
  <mQ>0</mQ>
  <nRR>-632.698957</nRR>
  <nR>0</nR>
</plugin>

Range Bearing

These are the parameters that can be used to configure the Range Bearing plugin:

  • <address> - Address of the comms node you bind to.
  • <namespace> - The namespace on which this plugin should listen to receive and respond to requests.
  • <processing_delay> - The amount of time which it will take for the transponder to respond.
  • <speed_of_sound> - Speed of sound in the underlying medium.
  • <link_name> - The name of the link which holds the receiver.

This is a configuration example:

<plugin
  filename="RangeBearingPlugin"
  name="tethys::RangeBearingPlugin">
  <address>1</address>
  <processing_delay>0.3</processing_delay>
  <speed_of_sound>1500</speed_of_sound>
  <link_name>acoustic_transponder</link_name>
  <namespace>tethys</namespace>
</plugin>

Science Sensors System

As explained in the architecture section the science sensor system loads up a csv file with data values to feed the different sensors that this plugin offers during simulation. The following option is available through the XML file:

  • <data_path> Indicates the data path to the csv data file that contains the values that are read by the sensors during simulation.

Here is an example of the XMLsection loading this plugin:

<plugin
  filename="ScienceSensorsSystem"
  name="tethys::ScienceSensorsSystem">
  <data_path>data_file.csv</data_path>
</plugin>

You can find some examples of data files in the data directory of the lrauv repository. The following fields can be used by indicating their name in the first line of the csv file:

elapsed_time_second
latitude_degree
longitude_degree
depth_meter
sea_water_temperature_degC
sea_water_salinity_psu
mass_concentration_of_chlorophyll_in_sea_water_ugram_per_liter
eastward_sea_water_velocity_meter_per_sec
northward_sea_water_velocity_meter_per_sec

Alternatively this data can also be loaded through the world config GUI plugin.

Tethys Comm Plugin

These are the parameters that can be used to configure the Tethys Comm plugin:

  • <namespace> - The namespace on which this plugin should use for it's topics.
  • <command_topic> - Topic where it should subscribe to wait for command messages.
  • <state_topic> - Topic on where to publish the full state message.
  • <debug_printout> - 0 means no debug, 1 debug output will be printed.
  • <ocean_density>- A means to set the ocean density that is also reported in the sate message.
<plugin
  filename="TethysCommPlugin"
  name="tethys::TethysCommPlugin">
  <namespace>tethys</namespace>
  <command_topic>tethys/command_topic</command_topic>
  <state_topic>tethys/state_topic</state_topic>
  <debug_printout>0</debug_printout>
  <ocean_density>1025</ocean_density>
</plugin>

World Comm Plugin

These are the parameters that can be used to configure the World Comm Plugin:

  • <init_topic> - Topic on which it will listen to for LRAUVInit messages to spawn new vehicles. Defaults to lrauv/init.

This an example loading the World Comm Plugin:

<plugin
  filename="WorldCommPlugin"
  name="tethys::WorldCommPlugin">
  <init_topic>/lrauv/init</init_topic>
</plugin>

Running Multiple Vehicles

Each instance of bin/LRAUV is tied to a single vehicle. In order to work with multiple vehicles, multiple instances of bin/LRAUV must be spun up.

The first vehicle spun up will be placed at the origin of the world, and the latitude / longitude of the world's origin will be set to coincide with it. Subsequent vehicles will be spawned at positions relative to the initial one, according to their latitude / longitude.

Information about the vehicle is hardcoded on the lrauv-application code, within the Config folder. Here's a recommended setup assuming that you have lrauv-application cloned under ~/lrauv_ws/src:

  1. Copy the lrauv-application folder for each robot to be spawned:

    cp -r ~/lrauv_ws/src/lrauv-application ~/lrauv_ws/src/lrauv-application-2
    cp -r ~/lrauv_ws/src/lrauv-application ~/lrauv_ws/src/lrauv-application-3
    ...
    
  2. Edit the vehicle name (in Config/vehicle.cfg) and initial location (in Config/workSite.cfg) for each instance. For example:

    --- lrauv-application/Config/vehicle.cfg        2021-09-27 16:17:09.816305451 -0700
    +++ lrauv-application-2/Config/vehicle.cfg      2021-09-29 14:53:57.480185748 -0700
    @@ -10,7 +10,7 @@
     ////////////////////////////////////////////////////////////////////
    
     //   Vehicle.name            = "Tethys";
    -   Vehicle.name            = "tethys";  // Use name to match Gazebo default SDF
    +   Vehicle.name            = "daphne";  // Use name to match Gazebo default SDF
        Vehicle.id              = 0 enum;
        Vehicle.kmlColor        = "ff0055ff"; // 4 hex bytes indicating alpha, blue, green, and red
                                            // In this case, orange.
    --- lrauv-application/Config/workSite.cfg       2021-09-27 14:16:43.622409403 -0700
    +++ lrauv-application-2/Config/workSite.cfg     2021-09-29 14:53:06.887476472 -0700
    @@ -14,8 +14,8 @@
     //  initLat        =   36.806966 arcdeg; // Initial latitude
     //  initLon        = -121.824326 arcdeg; // Initial longitude
     // initial position same as for regression tests
    -  initLat       =   36.8034 arcdeg; // Initial latitude
    -  initLon       = -121.8222 arcdeg; // Initial longitude
    +  initLat       =   36.8033 arcdeg; // Initial latitude
    +  initLon       = -121.8223 arcdeg; // Initial longitude
    
       startupScript = "Missions/Startup.xml";  // Mission to run on power-up
       defaultScript = "Missions/Default.xml";  // Mission to run when no other mission is running.

To run simulation, use the empty environment, and start vehicles in order, for example:

  1. gz sim empty_environment.sdf -v 4
  2. ~/lrauv_ws/src/lrauv-application/bin/LRAUV
  3. ~/lrauv_ws/src/lrauv-application-2/bin/LRAUV
  4. Start more bin/LRAUV as needed

Improve Performance on Large Environments: Enable Levels

Some worlds support levels. Levels are turned off by default, which means that all heightmap tiles will be loaded at all times. When levels are enabled, only the tiles containing vehicles (performers) spawned with WorldCommPlugin with an lrauv_init message will be loaded.

For example, loading without levels:

gz sim -v 4 portuguese_ledge.sdf

Portuguese Ledge no levels

And with levels:

gz sim -v 4 portuguese_ledge.sdf --levels

Portuguese Ledge levels

Gazebo GUI and GUI Plugins

Gazebo window look and GUI Plugins config can be done through the XML file. More information on how to configure the GUI and Gazebo GUI plugin can be found here. This is an example for the Control Panel Plugin:

      <plugin filename="ControlPanelPlugin" name="Tethys Controls">
        <gz-gui>
          <title>Tethys controls</title>
          <property type="string" key="state">docked_collapsed</property>
        </gz-gui>
      </plugin>

Reference Axis

It accepts the following property:

  • <fsk> Indicates the model that should show a reference frame attached.

And here is an example:

<plugin filename="ReferenceAxis" name="Reference axis">
  <gz-gui>
    <title>Reference axis</title>
    <property type="string" key="state">docked_collapsed</property>
  </gz-gui>
  <fsk>tethys</fsk>
</plugin>

Gazebo plugins

Some of the plugins currently existing in Gazebo are relevant to the LRAUV Simulation, here is a list of them with the link to the documentation:

Citations

[1] Fossen, Thor I. "Guidance and control of ocean vehicles." University of Trondheim, Norway, Printed by John Wiley & Sons, Chichester, England, ISBN: 0 471 94113 1, Doctors Thesis (1999).