Skip to content

Examples and tutorials

Marco A. Gutiérrez edited this page Aug 15, 2022 · 13 revisions
  1. Test simulation in Ignition standalone (without MBARI integration)
  2. Test integration with MBARI LRAUV code base
  3. Run missions designed for Ignition integration tests
  4. The Acoustics Subsystem
  5. Performing Range Bearing using a C++ client
  6. Writing your own environmental acoustic model plugin.

Test simulation in Ignition standalone (without MBARI integration)

This repo comes with an empty example world. To run this example world simply source the colcon workspace and run:

. install/setup.bash
ign gazebo buoyant_tethys.sdf

You should see Gazebo Sim with the LRAUV like this:

Gazebo Sim LRAUV sdf

Now, example commands can be sent to move some joints:

LRAUV_example_controller

In order to start the keyboard teoperation:

LRAUV_keyboard_teleop

Test integration with MBARI LRAUV code base

MBARI's code base lives in a separate, private repository. For people with access, here are instructions on setting it up from source and compiling.

Alternatively, you can use the public Docker image (see below).

The integration assumes that this repository is cloned as a sibling of the lrauv-application repository, i.e.:

<workspace>
|-- lrauv
└-- lrauv-application

For quick reference, compilation boils down to running this on the right branch:

make ignition

MBARI public Docker image

A public Docker image is available for people without access to the MBARI codebase. MBARI's image on DockerHub contains Ignition, MBARI's LRAUV code base, and this repository. All the code has been compiled.

docker pull mbari/lrauv-ignition-sim

Note: To update that image, see instructions in MBARI's private lrauv-application repository.

Once inside a container, source the colcon workspaces:

. ~/ign_ws/install/setup.bash
. ~/lrauv_ws/install/setup.bash

This needs to be done for each terminal.

Run the Ignition simulation

For ease of development, the following world is set up to run at a real time factor (RTF) of 0 (as fast as possible) and a step size of 0.02 seconds. That is significantly faster than the default Ignition setting of RTF 1 and step size 0.001 seconds, which will give real time performance and roughly the nominal vehicle speed of 1 m/s.

The RTF and step size can be changed at run time via the GUI by going to the Inspector panel and then Physics Group. Alternatively, they can be changed prior to compilation in the world SDF under <physics><max_step_size> and <physics><real_time_factor>.

Launch the Ignition simulation:

ign gazebo buoyant_tethys.sdf

For verbose debug output, add --verbose 4.

Unpause Ignition by clicking on the triangle play button in the lower-left corner of the GUI, or by pressing the space bar.

Run the MBARI LRAUV application

The MBARI LRAUV Main Vehicle Application (MVA) contains everything needed to control and operate the vehicle in the real world and in simulation.

The MBARI application relies on the Gazebo simulated clock for timekeeping, such that in most cases, both controller and simulation should be synchronized. There may be corner cases that still need to be resolved.

This section assumes you have either compiled the target from source or are using the MBARI public Docker image, which has everything pre-compiled. The paths assume you are using the MBARI public Docker image.

Run the LRAUV Main Vehicle Application:

cd ~/lrauv_ws/src/lrauv-application
bin/LRAUV

This will bring you to a command prompt.

At the LRAUV command prompt (you only need to do this once):

>configset micromodem.loadatstartup 0 bool persist
>restart app

This sets the micromodem to not load at startup. persist means you only need to do this once. It will pause for a bit, you might not be able to type right away.

On the vehicle, an app is always being run. If no missions are specified, then it is running the default. On the real vehicle, the default mission is GoToSurface. (NOTE: we have removed the default app in the MBARI public image until this issue is resolved. Currently, nothing is being run by default. Skip this check.) Verify that it is running the default GoToSurface app:

>show stack
2021-03-03T18:24:46.699Z,1614795886.699 [Default](IMPORTANT): Priority 0: Default:B.GoToSurface

Control commands

Control commands can be issued to overwrite mission controls. For example, the rudder can be held at a constant angle like so:

>maintain control horizontalcontrol.rudderangleaction -15 degree

This overwrites the controller and maintains the rudder at -15 degrees (-0.261799 radians), which is the joint limit.

Unit conversions are automatically done in the MBARI code. Alternatively, you can specify in radians.

>maintain control horizontalcontrol.rudderangleaction -0.2 radian

A thruster command can then be issued to move the vehicle in a circle:

>maintain control SpeedControl.propOmegaAction 300 rpm

Currently, this is the tested and preferred method of control.

A sample list of command variables:

Config/Control-->HorizontalControl.loadAtStartup=1 bool
Config/Control-->HorizontalControl.kdHeading=0.049999 s
Config/Control-->HorizontalControl.kiHeading=0.001000 1/s
Config/Control-->HorizontalControl.kiwpHeading=0.000500 rad/s/m
Config/Control-->HorizontalControl.kpHeading=0.400000 n/a
Config/Control-->HorizontalControl.kwpHeading=0.049999 rad/m
Config/Control-->HorizontalControl.maxHdgAccel=7.499876 arcdeg/s2
Config/Control-->HorizontalControl.maxHdgInt=0.087266 rad
Config/Control-->HorizontalControl.maxHdgRate=11.999932 arcdeg/s
Config/Control-->HorizontalControl.maxKxte=45.000001 arcdeg
Config/Control-->HorizontalControl.rudDeadband=0.500000 arcdeg
Config/Control-->HorizontalControl.rudLimit=15.000000 arcdeg
VerticalControl-->VerticalControl.buoyancyAction=944.986938 cc
VerticalControl-->VerticalControl.depthIntegralInternal=nan rad
VerticalControl-->VerticalControl.depth2buoyIntInternal=nan cc
VerticalControl-->VerticalControl.massIntegralInternal=nan m
VerticalControl-->VerticalControl.elevatorIntegralInternal=nan rad
HorizontalControl-->HorizontalControl.rudderAngleAction=0.000000 rad
SpeedControl-->SpeedControl.propOmegaAction=0.000000 rad/s

Run missions designed for Ignition integration tests

The following are "unit test" missions that test one or two actuators at a time. Run one at a time, in separate runs of Ignition and the Main Vehicle Application (bin/LRAUV):

run RegressionTests/IgnitionTests/Default.xml
run RegressionTests/IgnitionTests/testDepthVBS.xml
run RegressionTests/IgnitionTests/testPitchMass.xml
run RegressionTests/IgnitionTests/testPitchAndDepthMassVBS.xml
run RegressionTests/IgnitionTests/testYoYoCircle.xml
run RegressionTests/IgnitionTests/testScienceSensors.xml
run RegressionTests/IgnitionTests/testThrusterStopAndGo.xml
run RegressionTests/IgnitionTests/testAct.xml 
run RegressionTests/IgnitionTests/testAcTracking.xml
run RegressionTests/IgnitionTests/Startup.xml

Some example behaviors are documented here.

Some parameters can be adjusted - see the mission XML file. For example, to change the commanded depth in the testDepthVBS.xml mission:

load RegressionTests/IgnitionTests/testDepthVBS.xml
set buoy_test_vbs.DepthCmd 20 meter
run

To stop a mission, run

stop

You can automate typing into the command prompt by issuing -x. For example, this will run the yoyo mission and terminate after the mission ends:

bin/LRAUV -x "run RegressionTests/IgnitionTests/testYoYoCircle.xml quitAtEnd"

LRAUV cheat sheet

This contains some most-often used commands for quick reference:

Show general help or for a specific command:

>?
>help report

Show mission currently being run

>show stack

Speed up 100 times faster than real time:

>quick on
# To go back to normal speed
>quick off

To report the value continuously on variable touch:

>report touch <componentName>.<variableName>
# To stop reporting
>report clear

To get the current value of a variable:

>get <componentName>.<variableName>

A sample list of variables in the ExternalSim component:

ExternalSim.latitudeSim=36.803400 arcdeg
ExternalSim.longitudeSim=-121.822200 arcdeg
ExternalSim.eastingSim=605067.311028 m
ExternalSim.northingSim=4073710.248871 m
ExternalSim.utmZoneSim=10 enum
ExternalSim.propThrustSim=-0.000000 N
ExternalSim.propTorqueSim=-0.000000 N-m
ExternalSim.netBuoySim=0.000000 N
ExternalSim.forceXSim=0.000000 N
ExternalSim.forceYSim=0.000000 N
ExternalSim.forceZSim=0.000000 N
ExternalSim.posXSim=0.000000 m
ExternalSim.posYSim=0.000000 m
ExternalSim.posZSim=0.000000 m
ExternalSim.rollSim=0.000000 rad
ExternalSim.pitchSim=0.000000 rad
ExternalSim.headingSim=0.000000 rad
ExternalSim.posXDotSim=0.000000 m
ExternalSim.posYDotSim=0.000000 m
ExternalSim.posZDotSim=0.000000 m
ExternalSim.rateUSim=0.000000 m/s
ExternalSim.rateVSim=0.000000 m/s
ExternalSim.rateWSim=0.000000 m/s
ExternalSim.ratePSim=0.000000 m/s
ExternalSim.rateQSim=0.000000 m/s
ExternalSim.rateRSim=0.000000 m/s
ExternalSim.homingSensorRangeSim=27.335945 m
ExternalSim.homingSensorAzimSim=-1.531450 rad
ExternalSim.homingSensorElevSim=1.073800 rad

To stop a mission:

>stop

To terminate:

>quit

Troubleshoot

After issuing control commands, for example, rudder and thrust, if you then notice that the vehicle gets some commands by itself, such as a non-zero elevator angle, this is because a preloaded mission is being loaded, and you need to wait to issue the control commands after it is done loading. Make sure to use

quick on

to let the system finish loading, before issuing control commands.

How to Send and Receive Data Packets on the Acoustic Subsystem.

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.

In this tutorial we will be exploring how to send and receive data packets. There are two ways of doing this. The first is using the lrauv_ignition_plugins/comms/CommsClient.hh header and the second is directly calling the relevant ignition topics (reading the linked header should also give you a rough idea of how to write your own client).

Using CommsClient

CommsClient is an extremely easy to use method for handling sending of messages, however it needs C++11 or above to be used. The usage is as follows:

#include <lrauv_ignition_plugins/comms/CommsClient.hh>

using namespace tethys;
using AcousticMsg = lrauv_ignition_plugins::msgs::LRAUVAcousticMessage;

// Bind client to address 1
CommsClient client(1, [](const auto msg){
   // Your callback function
   // To get the data call
   msg.data();
   // To get who the message is from
   msg.from();
});

// For sending data

AcousticMsg msg;
// Who to send to
msg.set_to(2);
// From who
msg.set_from(1);
// `LRAUVAcousticMessage_MessageType_Other` means its a data packet
msg.set_type(AcousticMsg::MessageType::LRAUVAcousticMessage_MessageType_Other);
// The data
msg.set_data("test_message");
client1.SendPacket(msg);

An example may be found in the tests here.

Direct method

For this method you will need to understand how ignition-transport works. It is recommended to read this tutorial first.

To get started instantiate a world using ignition:

ign gazebo -v4 acoustic_comms_test.sdf

Two boxes will be spawned. Each of these boxes has an instance of the comms plugin and the range bearing plugin. The boxes publish what they receive on the /comms/external/{address}/rx topic. The comms client will also forward data published from the /comms/external/{address}/txtopic to the relevant client. In a new terminal enter:

ign topic --list

You should see two sets of RX and TX topics. Here is a minimal echo program:

  #include <ignition/transport/Node.hh>
  #include "lrauv_acoustic_message.pb.h"

  int address = 1;
  ignition::transport::Node node;
  ignition::transport::Node::Publisher transmitter;
  
  //////////////////////////////////////////////////
  /// \brief Function called each time a message is recieved by the comms subsystem.
  void cb(const lrauv_ignition_plugins::msgs::LRAUVAcousticMessage &_msg)
  {
    std::cout << msg.from() << ": " << msg.data();

    lrauv_ignition_plugins::msgs::LRAUVAcousticMessage returnMsg;
    // Who to send to
    msg.set_to(msg.from());
    // From who  
    msg.set_from(address);

    // `LRAUVAcousticMessage_MessageType_Other` means its a data packet
    msg.set_type(AcousticMsg::MessageType::LRAUVAcousticMessage_MessageType_Other);

    // The data
    msg.set_data(msg.data);

    // Send the data
    transmitter.Publish(msg);
  }

  int main(int argc, char** argv)
  {
    transmitter = node.Advertise<lrauv_ignition_plugins::msgs::LRAUVAcousticMessage>(
      "/comms/external/" + std::to_string(address) + "/tx");

    node.Subscribe(
      "/comms/external/" + std::to_string(address) + "/rx",
      cb
    );

    while(true) { sleep(1); }
  }