MAVLink

Mavlink Communication with the Autopilot and other systems that use the MAVLink protocol

MAVLink can be used to interface with components that use the MAVLink protocol and are connected to Skynode. These can be applications running on AuterionOS, payloads or other devices connected to the Skynode or its flight controller.

If you wish to write a custom application which can send and receive MAVLink to or from the FMU, we recommend using Auterion libmav and connect to the interface outlined below.

MAVLink messages can be received by all MAVLink endpoints in the system, including the autopilot, camera, gimbal and Ground Control Station. Be cautious when interfacing with the system on this level to avoid any undesired behavior.

To connect to the on-board mavlink network, open a TCP connection to 172.17.0.1:5790 (auterion-api 2+) or 127.0.0.1:5790 (auterion-api 1). For MAVSDK use the connection string "tcp://127.0.0.1:5790" or "tcp://172.17.0.1:5790"

When initiating a connection over MAVLink, do not advertise your component as a ground control station (GCS). This could have the side effect of the autopilot mistaking your app as a legitimate ground station, and thus not trigger a failsafe action when connection to your primary ground station fails. When using libmav, in the setup of the HEARTBEAT message, set the "type" field to "MAV_TYPE_ONBOARD_CONTROLLER" or "MAV_TYPE_GENERIC" When using MAVSDK, configure the library to use, set configuration to Mavsdk::Configuration(Mavsdk::Configuration::UsageType::CompanionComputer)

If the Skynode is connected via USB, you can also connect to that port by using IP 10.41.1.1:5790

Do not use TCP connections to connect to MAVLink over a radio link. Only use TCP for on-board communication and development setups with USB cable.

How to use libmav in your App

Use libmav as a submodule in your app. You can also check the README of this Repository to get more information and more examples how to use libmav.

In libmav, the message set is runtime defined and loaded from XML files. Any of the upstream XML files will work. The function also loads dependent XML files recursively.

auto message_set = mav::MessageSet("/path/to/common.xml");

The easiest way to get the mavlink message defintions into your app is to add mavlink as a submodule, and include the message definitions like this:

auto message_set = mav::MessageSet("mavlink/common.xml");

Connect to MAVLink using TCP to port 5790 on 172.17.0.1 like sol

auto phy = std::make_shared<mav::TCPClient>("172.17.0.1", 5790);
auto runtime = std::make_shared<mav::NetworkRuntime>(_message_set, heartbeat, *_phy);
auto connection = _runtime->awaitConnection(1000);

You can use a callback like this to receive messages. This callback receives GLOBAL_POSITION_INT and BATTERY_STATUS messages.

// Look up IDs of messages we're interested in.
auto global_position_int_id = _message_set.idForMessage("GLOBAL_POSITION_INT");
auto battery_status_id = _message_set.idForMessage("BATTERY_STATUS");

// Add a message callback
connection->addMessageCallback([this,
        global_position_int_id, battery_status_id](const mav::Message &message) {
    if (message.id() == global_position_int_id) {
        std::cout << "Received position message" << std::endl;
    } else if (message.id() == battery_status_id) {
        std::cout << "Received battery message" << std::endl;
    }
});

Last updated