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.

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.

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.

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.

Quick Integration: Sending data

This approach takes more lines of code per message, but gets you instantly started.

/* 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.

#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.

#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.

SEND C-CODE

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.

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 */

MAVLink Onboard Integration Tutorial的更多相关文章

  1. MAVLink Linux/QNX/MacOs Integration Tutorial (UDP)

    MAVLink Linux/QNX/MacOs Integration Tutorial (UDP) Overview This program was written to test the udp ...

  2. springmvc4开发rest

    Spring MVC 4 RESTFul Web Services CRUD Example+RestTemplate Created on:  August 11, 2015  | Last upd ...

  3. Gazebo機器人仿真學習探索筆記(七)连接ROS

    中文稍后补充,先上官方原版教程.ROS Kinetic 搭配 Gazebo 7 附件----官方教程 Tutorial: ROS integration overview As of Gazebo 1 ...

  4. Unity 官方教程 学习

    Interface & Essentials Using the Unity Interface 1.Interface Overview https://unity3d.com/cn/lea ...

  5. 【Spring实战】----开篇(包含系列目录链接)

    [Spring实战]----开篇(包含系列目录链接) 置顶2016年11月10日 11:12:56 阅读数:3617 终于还是要对Spring进行解剖,接下来Spring实战篇系列会以应用了Sprin ...

  6. JCaptcha+Memcache的验证码集群实现

    一.问题背景 为了防止垃圾信息发布机器人的自动提交攻击,采用CAPTCHA验证码来保护该模块,提高攻击者的成本. 二.验证码简介 全自动区分计算机和人类的图灵测试(Completely Automat ...

  7. Spring 4 MVC+Apache Tiles 3 Example

    In this post we will integrate Apache Tiles 3 with Spring MVC 4, using annotation-based configuratio ...

  8. Open Daylight integration with OpenStack: a tutorial

    Open Daylight integration with OpenStack: a tutorial How to deploy OpenDaylight and integrate it wit ...

  9. Spring MVC Hibernate MySQL Integration(集成) CRUD Example Tutorial【摘】

    Spring MVC Hibernate MySQL Integration(集成) CRUD Example Tutorial We learned how to integrate Spring ...

随机推荐

  1. 常见的http错误提示

    1xx(临时响应)表示临时响应并需要请求者继续执行操作的状态代码. 代码 说明100 (继续) 请求者应当继续提出请求.服务器返回此代码表示已收到请求的第一部分,正在等待其余部分. 101 (切换协议 ...

  2. 语言模型预训练方法(ELMo、GPT和BERT)——自然语言处理(NLP)

    1. 引言 在介绍论文之前,我将先简单介绍一些相关背景知识.首先是语言模型(Language Model),语言模型简单来说就是一串词序列的概率分布.具体来说,语言模型的作用是为一个长度为m的文本确定 ...

  3. CentOS7.6下模拟iSCSI,Windows来连

    如题,在CentOS7上模拟一个iSCSI设备,然后在Windows Server 2008上连接这个iSCSI设备 第一步,CentOS7上的操作.CentOS7上安装iSCSI模拟器需要3个包,我 ...

  4. 一段关于Unix、Linux和Windows的暗黑史

    "SCO在言语上变得越来越好斗,而且还拒绝展示有关诉讼的任何证据,一切都似乎在表明,SCO只不过是在那里拉虎皮做大旗地狂言乱语.但是,微软 决不会轻易放弃这么可以一个利用这些狂言乱语的好机会 ...

  5. jQuery $(document).ready()和JavaScript window.onload()事件的区别

    一. 在网上查了一下,发现$(document).ready()是在DOM树加载完成时触发,而window.onload()则是在整个页面全部加载完成时触发.下面是一些验证. var start=+n ...

  6. codeblocks 控制台一闪而过

    不要点红的运行,那是调试,点绿色的三角形,那才是运行,不会一闪而过

  7. 用通俗的语言解释 Spring 中的 DI 、IOC 和AOP概念

    DI 所谓依赖,从程序的角度看,就是比如A要调用B的方法,那么A就依赖于B,反正A要用到B,则A依赖于B.所谓倒置,你必须理解如果不倒置,会怎么着,因为A必须要有B,才可以调用B,如果不倒置,意思就是 ...

  8. c++ 网络编程(十一) LINUX下 初步制作基于HTTP的WEB服务器

    原文作者:aircraft 原文链接:https://www.cnblogs.com/DOMLX/p/9663028.html HTTP概要 理解Web服务器端: 编写HTTP(超文本传输协议)服务器 ...

  9. 使用jquery获取url及url参数的方法(转)

    转自:http://www.cnblogs.com/babycool/p/3169058.html 使用jquery获取url以及使用jquery获取url参数是我们经常要用到的操作 1.jquery ...

  10. 如何在CentOS7上安装桌面环境?

    1.安装 GNOME-Desktop 安装GNOME桌面环境 # yum -y groups install "GNOME Desktop" 完成安装后,使用如下命令启动桌面 # ...