In this tutorial, you will learn how to install and use MOOS-IvP on your machine.
MOOS is an open-source middleware for inter-process communication (IPC) based on the publish-subscribe pattern. Such middleware are important for complex systems, including robotic systems, where processes (or applications) need to share the data to make decisions better understand the environment with ease. Having independent applications also allow the reuse of such applications in different scenarios without the modification of the source code.
MOOS is cross-platform, however, in this series, we will use a set of extra-tools MOOS-IvP that compile only using GCC or CLang for now. Therefore, Windows users are required to install one of these compilers or use Linux or macOS.
In these series also, it is supposed that a Linux Debian system will be used. The command line instructions provided are for Ubuntu 16.04 but will work on other system through some small adaptations too.
git
andsubversion
: version control systems to manage the code that will be written.sudo apt install git subversion
- C/C++ compiler and other essential tools: compile the source code to executables.
sudo apt install build-essential
- CMake :cross-platform, open-source make system
sudo apt install cmake
- FLTK libraries for the GUI
sudo apt install libfltk1.3-dev
- TIFF libraries to visualize the maps:
sudo apt install libtiff5-dev
It is recommended to get the latest version of MOOS-IvP from the download page :
svn co https://oceanai.mit.edu/svn/moos-ivp-aro/trunk/ moos-ivp
Once the source code has been downloaded, go to the new moos-ivp
directory and launch the build script:
cd moos-ivp
./build.sh
sudo ./build-moos.sh install
sudo ./build-ivp.sh install
To test the success of the installation, the output of which MOOSDB
should be similar to:
$ which MOOSDB
/usr/local/bin/MOOSDB
$ which pMarineViewer
/usr/local/bin/pMarineViewer
MOOS-IvP comes with many example missions to get you started and help understand the logic behind it.
These missions are located in ivp/missions/
.
Let's start with the s1_alpha
mission:
$ cd ivp/missions/s1_alpha
$ ls
alpha.bhv alpha.moos clean.sh launch.sh
The bash
scripts launch.sh
and clean.sh
are optional to run a mission but very useful for advanced use as we will see in the future.
In this example, launch.sh
is used to configure and launch the mission.
The reader is invited to open and read the script to better understand what it does.
The clean.sh
script is used here to clean the generated files and logs.
Mission configuration files have the .moos
extension.
Configuration for MOOS applications go here, but also more general configuration like the host IP and what port to use.
For MOOS to know what IP and port to use, but also what to call the community it is running, the following lines are required
ServerHost = localhost // Can be any valid IP address
ServerPort = 9000 // The port number to use
Community = alpha // The name of the community
On the same machine, multiple communities can coexist as long as ports are different.
When simulating missions, it is useful to be able to run the simulations at higher speed than 1x. The following line is useful for that purpose:
MOOSTimeWarp = 1
For the geodesic projections to work correctly, we set up the latitude and longitude coordinates of the origin of the map:
LatOrigin = 43.825300
LongOrigin = -70.330400
pAntler
is a MOOS app that an launch applications, MOOS or not, in an ordered sequence.
An application configuration block for pAntler
looks like following:
//------------------------------------------
// Antler configuration block
ProcessConfig = ANTLER
{
MSBetweenLaunches = 200
Run = MOOSDB @ NewConsole = false, ExtraProcessParams=db
Run = pLogger @ NewConsole = false
Run = uSimMarine @ NewConsole = false
Run = pMarinePID @ NewConsole = false
Run = pHelmIvP @ NewConsole = false
Run = pMarineViewer @ NewConsole = false, ExtraProcessParams=one
Run = uProcessWatch @ NewConsole = false
Run = pNodeReporter @ NewConsole = false
one = --size=1400x800
db = --event_log=eventlog
}
What pAntler
will do is launch each application listed in the same order with a delay of MSBetweenLaunches
in milliseconds between launches with the option listed as ExtraProcessParams
.
For instance, let's take the first two launches:
MOOSDB --event_log=eventlog alpha.moos
sleep 0.200
pLogger alpha.moos
All MOOS applications can be configured using the ProcessConfig
block.
Here's an example with pHelmIvP
, the heart of MOOS-IvP:
ProcessConfig = pHelmIvP
{
AppTick = 4
CommsTick = 4
behaviors = alpha.bhv
domain = course:0:359:360
domain = speed:0:4:41
}
- The
AppTick
variable sets the beat on which the iteration loop of the application is called, here at least 4 time per second. - The
CommsTick
variable sets the communication frequency with theMOOSDB
to send and receive messages. - The rest of the configuration is specific to each application.
pHelmIvP
requires extra configuration options to operate:domain
defines the domain in which the solver will look for a decision:course:0:359:360
: here the solver will generate 360 points between 0 and 359speed:0:4:41
: here the solver will generate 41 points between 0 and 4
behaviors
sets the behavior file that will considered.
The behavior file is specific to MOOS-IvP and is not required by MOOS.
This file defines the behaviors that will generate the decision functions that will then generate an output in a form of DESIRED_SPEED
and DESIRED_HEADING
for example.
The file usually has some local variable initialization:
initialize DEPLOY = false
initialize RETURN = false
These lines set two variables DEPLOY
and RETURN
and initialize then to false
. (in MOOS, variables are either binary data, floating point or strings, there's no boolean type.)
A behavior configuration block looks like the following:
Behavior=BHV_Waypoint
{
name = waypt_return
pwt = 100
condition = RETURN = true
condition = DEPLOY = true
perpetual = true
updates = RETURN_UPDATE
endflag = RETURN = false
endflag = DEPLOY = false
endflag = MISSION = complete
speed = 2.0
capture_radius = 2.0
slip_radius = 8.0
points = 0,-20
}
To launch the mission, simply call the launch script:
./launch.sh
A pMarineViewer
window will show an aerial view and a vehicle.
The vehicle can be deployed using the DEPLOY
button in the lower right corner.
In this tutorial, you learned about how to install and run a very basic mission. In the upcoming tutorials you will be writing your very first MOOS application.
- MOOS-IvP documentation
- Unmanned Marine Vehicle Autonomy, Sensing and Communications (MIT 2.680 class)
This tutorial is released under an MIT license.