MAVLink Onboard Integration Tutorial
MAVLink is a header-only library, which means that you don't have to compile it for your MCU. You just have to add mavlink/include
to the list of your include directories (which is typically in your Makefile
).
Please note that you can create your own messages and generate the C-code for them. Just extend the default message format xml file.
git
-
You can find a full description of the details of the MAVLink protocol in the wiki.
Connection / Stateless
MAVLink is stateless, but QGroundControl tracks if a system is alive using the heartbeat message. Therefore make sure to send a heartbeat every 60, 30, 10 or 1 second (1 Hz is recommended, but not required). A system will only be considered connected (and the views created for it) once a heartbeat arrives.github
Integration Architecture
As the diagram below shows, integrating MAVLink is non-intrusive. MAVLink does not need to become a central part of the onboard architecture. The provided missionlib handles parameter and mission / waypoint transmission, the autopilot only needs to read off the values from the appropriate data structures.app
MAVLink has a very stable message format, one of the primary reasons so many GCS and autopilots support it. If QGroundControl is used for a non-standard application, the UAS object can be sub-classed and QGroundControl can be fully customized to not only use a custom set of MAVLink messages, but also to handle them in a custom C++ class.less
Quick Integration: Sending data
This approach takes more lines of code per message, but gets you instantly started.ide
/* The default UART header for your MCU */ #include "uart.h" #include <mavlink/v1.0/common/mavlink.h> mavlink_system_t mavlink_system; mavlink_system.sysid = 20; ///< ID 20 for this airplane mavlink_system.compid = MAV_COMP_ID_IMU; ///< The component sending the message is the IMU, it could be also a Linux process // Define the system type, in this case an airplane uint8_t system_type = MAV_TYPE_FIXED_WING; uint8_t autopilot_type = MAV_AUTOPILOT_GENERIC; uint8_t system_mode = MAV_MODE_PREFLIGHT; ///< Booting up uint32_t custom_mode = 0; ///< Custom mode, can be defined by user/adopter uint8_t system_state = MAV_STATE_STANDBY; ///< System ready for flight // Initialize the required buffers mavlink_message_t msg; uint8_t buf[MAVLINK_MAX_PACKET_LEN]; // Pack the message mavlink_msg_heartbeat_pack(mavlink_system.sysid, mavlink_system.compid, &msg, system_type, autopilot_type, system_mode, custom_mode, system_state); // Copy the message to the send buffer uint16_t len = mavlink_msg_to_send_buffer(buf, &msg); // Send the message with the standard UART send function // uart0_send might be named differently depending on // the individual microcontroller / library in use. uart0_send(buf, len);
Receive Function
The function above describes how to send data with/without the convenience functions. The code snippet below shows how to receive data. The runtime is quite low, so we advise to run this function at mainloop rate and empty the UART buffer as fast as possible.oop
#include <mavlink/v1.0/common/mavlink.h> // Example variable, by declaring them static they're persistent // and will thus track the system state static int packet_drops = 0; static int mode = MAV_MODE_UNINIT; /* Defined in mavlink_types.h, which is included by mavlink.h */ /** * @brief Receive communication packets and handle them * * This function decodes packets on the protocol level and also handles * their value by calling the appropriate functions. */ static void communication_receive(void) { mavlink_message_t msg; mavlink_status_t status; // COMMUNICATION THROUGH EXTERNAL UART PORT (XBee serial) while(uart0_char_available()) { uint8_t c = uart0_get_char(); // Try to get a new message if(mavlink_parse_char(MAVLINK_COMM_0, c, &msg, &status)) { // Handle message switch(msg.msgid) { case MAVLINK_MSG_ID_HEARTBEAT: { // E.g. read GCS heartbeat and go into // comm lost mode if timer times out } break; case MAVLINK_MSG_ID_COMMAND_LONG: // EXECUTE ACTION break; default: //Do nothing break; } } // And get the next one } // Update global packet drops counter packet_drops += status.packet_rx_drop_count; // COMMUNICATION THROUGH SECOND UART while(uart1_char_available()) { uint8_t c = uart1_get_char(); // Try to get a new message if(mavlink_parse_char(MAVLINK_COMM_1, c, &msg, &status)) { // Handle message the same way like in for UART0 // you can also consider to write a handle function like // handle_mavlink(mavlink_channel_t chan, mavlink_message_t* msg) // Which handles the messages for both or more UARTS } // And get the next one } // Update global packet drops counter packet_drops += status.packet_rx_drop_count; }
Integration with convenience functions
WITH convenience functions
MAVLink offers convenience functions for easy sending of packets. If you want to use these, you have to provide a specific function in your code. This approach takes less lines of code per message, but requires you to write the adapter header. Please find an example for such an adapter header below. We advise to start off WITHOUT convenience functions, send your first message to the GCS and then add the adapter header if needed.ui
#include "your_mavlink_bridge_header.h" /* You have to #define MAVLINK_USE_CONVENIENCE_FUNCTIONS in your_mavlink_bridge_header, and you have to declare: mavlink_system_t mavlink_system; these two variables will be used internally by the mavlink_msg_xx_send() functions. Please see the section below for an example of such a bridge header. */ #include <mavlink.h> // Define the system type, in this case an airplane int system_type = MAV_FIXED_WING; // Send a heartbeat over UART0 including the system type mavlink_msg_heartbeat_send(MAVLINK_COMM_0, system_type, MAV_AUTOPILOT_GENERIC, MAV_MODE_MANUAL_DISARMED, MAV_STATE_STANDBY);
MAVLink Adapter Header for Convenience Send Functions
This code example was written with a microcontroller in mind, what most external users will want to use. For examples for C++, please have a look at e.g. PX4/Firmware mavlink app.this
SEND C-CODEurl
Define this function, according to your MCU (you can add more than two UARTS). If this function is defined, you then can use the 'mavlink_msg_xx_send(MAVLINK_COMM_x, data1, data2, ..)
' functions to conveniently send data.
spa
your_mavlink_bridge_header.h
/* MAVLink adapter header */ #ifndef YOUR_MAVLINK_BRIDGE_HEADER_H #define YOUR_MAVLINK_BRIDGE_HEADER_H #define MAVLINK_USE_CONVENIENCE_FUNCTIONS #include <mavlink/v1.0/mavlink_types.h> /* Struct that stores the communication settings of this system. you can also define / alter these settings elsewhere, as long as they're included BEFORE mavlink.h. So you can set the mavlink_system.sysid = 100; // System ID, 1-255 mavlink_system.compid = 50; // Component/Subsystem ID, 1-255 Lines also in your main.c, e.g. by reading these parameter from EEPROM. */ mavlink_system_t mavlink_system; mavlink_system.sysid = 100; // System ID, 1-255 mavlink_system.compid = 50; // Component/Subsystem ID, 1-255 /** * @brief Send one char (uint8_t) over a comm channel * * @param chan MAVLink channel to use, usually MAVLINK_COMM_0 = UART0 * @param ch Character to send */ static inline void comm_send_ch(mavlink_channel_t chan, uint8_t ch) { if (chan == MAVLINK_COMM_0) { uart0_transmit(ch); } if (chan == MAVLINK_COMM_1) { uart1_transmit(ch); } } #endif /* YOUR_MAVLINK_BRIDGE_HEADER_H */