Auterion for Developers
Latest Developer's Guide
Search
K
Links
Comment on page

Setup (libmav)

These APIs are likely to change in future API versions. Key functionality will remain.

Introduction

Getting sensor data from the system is a key part of every drone app. In Auterion Apps, sensor data is obtained by eavesdropping the MAVLink stream from the vehicle.

Setup

Add libmav

Add Auterion libmav to your project.
  • For C++ projects, you can clone the library as a submodule into your project with git submodule add https://github.com/Auterion/libmav.git
  • For python projects, you can install libmav using pip pip install libmav
Add the mavlink message definitions to your project. The easiest way to do that is to add the mavlink repository as a submodule to your app with git submodule add https://github.com/mavlink/mavlink.git

Setup libmav

You can find documentation about libmav on the libmav github repository
To connect to the drone, use the TCP endpoint at
  • 172.17.0.1:5790 (auterion-api 2+)
  • 127.0.0.1:5790 (auterion-api 1)

C++ Setup

// Load the message set from XML
auto message_set = mav::MessageSet("/path/to/common.xml");
// Create interface for physical network
auto physical = mav::TCPClient("172.17.0.1", 5790);
// Create a network runtime. This starts the receive thread.
auto runtime = mav::NetworkRuntime(message_set, physical);
// Wait for the connection
auto connection = runtime.awaitConnection(2000);
In most cases, you want to have libmav objects as object state variables like so
class MyApp {
private:
std::unique_ptr<mav::MessageSet> _message_set;
std::unique_ptr<mav::TCPClient> _physical;
std::unique_ptr<mav::NetworkRuntim> _runtime;
std::shared_ptr<mav::Connection> _connection;
public:
void reConnectMavlink() {
_message_set = std::make_unique<mav::MessageSet>("path/to/common.xml");
_physical = std::make_unique<mav::TCPClient>("172.17.0.1", 5790);
_runtime = std::make_unique<mav::NetworkRuntime>(*_message_set, *_physical);
_connection = _runtime.awaitConnection(2000);
}
};
This way, you can call the reConnectMavlink() method at a later point in time, to re-bootstrap the connection should the connection to the system drop.

Python setup

In Python, you can connect to the system like so
import libmav
# Create a message set from a mavlink xml file
message_set = libmav.MessageSet('<PATH TO common.xml>')
conn_physical = libmav.TCPClient('172.17.0.1', 5790)
conn_runtime = libmav.NetworkRuntime(message_set, conn_physical)
connection = conn_runtime.await_connection(2000)

Receiving telemetry data

All telemetry data is streamed via MAVLink messages. In order to receive certain telemetry messages, you can either

Synchronously wait until the next message of a specific type arrives

C++:
// infinite loop
while(should_receive_data) {
// blocks until next message of type is received, or timeout (5s)
auto response = connection->receive("BATTERY_STATUS", 5000);
int remaining_battery = response["battery_remaining"];
std::cout << "Battery level: " << remaining_battery << std::endl;
}
In case you need telemetry from multiple messages, and you want to listen to them concurrently, you can achieve this by setting expectations:
C++:
// infinite loop
while(should_receive_data) {
// receive battery and altitude information simultaneously
auto battery_expectation = connection->expect("BATTERY_STATUS");
auto altitude_expectation = connection->expect("ALTITUDE");
// receive or time out. Note, it doesn't matter in which order they arrive.
auto battery = connection->receive(battery_expectation, 5000);
auto altitude = connection->receive(altitude_expectation, 5000);
int remaining_battery = battery["battery_remaining"]
std::cout << "Battery level: " << remaining_battery << std::endl;
}
The same can be done in Python
Python:
# infinite loop
while True:
response = connection.receive('BATTERY_STATUS', 5000)
print('Remaining battery: ' + str(response['battery_remaining'])

Add message callbacks

The telemetry information can also the received using asynchronous message callback. For this, add a callback to the connection like so:
C++:
int battery_message_id = message_set.idForMessage("BATTERY_STATUS");
auto callback_handle = connection->addMessageCallback(
[battery_message_id](const mav::Message& message) {
if (message.id() == battery_message_id) {
int remaining_battery = message["battery_remaining"]
std::cout << "Battery level: " << remaining_battery << std::endl;
}
});