-
Notifications
You must be signed in to change notification settings - Fork 15
Examples and tutorials
- Test simulation in Gazebo standalone (without MBARI integration)
- Test integration with MBARI LRAUV code base
- Run missions designed for Gazebo integration tests
- The Acoustics Subsystem
- Performing Range Bearing using a C++ client
- Writing your own environmental acoustic model plugin.
This repo comes with an empty example world. To run this example world simply source the colcon workspace and run:
. install/setup.bash
gz sim empty_environment.sdf
You will see an empty world. You may want to spawn a vehicle using the gui. First open the "Spawn LRAUVs" panel on the right side:
Click the SPAWN!
button. You should see the following work space:
You should see Gazebo Sim with the LRAUV like this:
Now, example commands can be sent to move some joints:
LRAUV_example_controller
In order to start the keyboard teoperation:
LRAUV_keyboard_teleop
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 gazebo
A public Docker image is available for people without access to the MBARI codebase. MBARI's image on DockerHub contains Gazebo, 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.
⚠️ This section is meant for people with access to MBARI's LRAUV controller. If you aren't in MBARI or aren't a collaborator these instructions won't work.
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 Gazebo 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 Gazebo simulation:
gz sim tethys_at_empty_environment.sdf
For verbose debug output, add --verbose 4
.
Unpause Gazebo by clicking on the triangle play button in the lower-left corner of the GUI, or by pressing the space bar.
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 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
The following are "unit test" missions that test one or two actuators at a time.
Run one at a time, in separate runs of Gazebo 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"
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
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.
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_gazebo_plugins/comms/CommsClient.hh
header and the second is directly calling the relevant gazebo topics (reading the linked header should also give you a rough idea of how to write your own client).
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_gazebo_plugins/comms/CommsClient.hh>
using namespace tethys;
using AcousticMsg = lrauv_gazebo_plugins::msgs::LRAUVAcousticMessage;
using namespace std::literals::chrono_literals;
int main(int _argc, char **_argv)
{
// For sending data
// Bind sender to address 1
constexpr int senderAddress = 1;
CommsClient sender(senderAddress, [](const auto){});
bool messageReceived = false;
std::mutex messageArrivalMutex;
std::condition_variable messageArrival;
// For receiving data
// Bind receiver to address 2
constexpr int receiverAddress = 2;
CommsClient receiver(receiverAddress, [&](const auto msg)
{
// Your callback function
// To get who the message is from
std::cout << "From: " << msg.from() << std::endl;
// To get the data call
std::cout << "Data: " << msg.data() << std::endl;
std::lock_guard<std::mutex> lock(messageArrivalMutex);
messageReceived = true;
messageArrival.notify_all();
});
AcousticMsg msg;
// Who to send to
msg.set_to(receiverAddress);
// From who
msg.set_from(senderAddress);
// Message type
msg.set_type(AcousticMsg::MessageType::LRAUVAcousticMessage_MessageType_Other);
// Adding the data
msg.set_data("test_message");
sender.SendPacket(msg);
using namespace std::literals::chrono_literals;
std::unique_lock<std::mutex> lock(messageArrivalMutex);
if (!messageArrival.wait_for(
lock, 5s, [&] { return messageReceived; }))
{
std::cout << "5s timeout, message not received." << std::endl;
}
}
The tests here also contain related examples.
For this method you will need to understand how gazebo-transport
works. It is recommended to read this tutorial first.
To get started instantiate a world using Gazebo:
gz sim -v4 acoustic_comms_fixture.sdf
Three 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}/tx
topic to the relevant client. In a new terminal enter:
gz topic --list
You should see two sets of RX and TX topics. Here is a minimal echo program:
#include <unistd.h>
#include <gz/transport/Node.hh>
#include "lrauv_gazebo_plugins/lrauv_acoustic_message.pb.h"
int address = 1;
gz::transport::Node node;
gz::transport::Node::Publisher transmitter;
using AcousticMsg = lrauv_gazebo_plugins::msgs::LRAUVAcousticMessage;
//////////////////////////////////////////////////
/// \brief Function called each time a message is recieved by the comms subsystem.
void cb(const lrauv_gazebo_plugins::msgs::LRAUVAcousticMessage &_msg)
{
std::cout << _msg.from() << ": " << _msg.data();
lrauv_gazebo_plugins::msgs::LRAUVAcousticMessage returnMsg;
// Who to send to
returnMsg.set_to(_msg.from());
// From who
returnMsg.set_from(address);
// `LRAUVAcousticMessage_MessageType_Other` means its a data packet
returnMsg.set_type(AcousticMsg::MessageType::LRAUVAcousticMessage_MessageType_Other);
// The data
returnMsg.set_data(_msg.data());
// Send the data
transmitter.Publish(returnMsg);
}
int main(int argc, char** argv)
{
transmitter = node.Advertise<lrauv_gazebo_plugins::msgs::LRAUVAcousticMessage>(
"/comms/external/" + std::to_string(address) + "/tx");
node.Subscribe(
"/comms/external/" + std::to_string(address) + "/rx",
cb
);
while(true) { sleep(1); }
}