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. windows下vim中文乱码处理

    现象:gvim安装后,打开中文utf-8编码的文件中文显示乱码 处理:1.启动gvim8.0,菜单 ”编辑“->"启动设定"在文件最开始处添加如下两行set fileenco ...

  2. Hexo博客系列(三)-将Hexo v3.x个人博客发布到GitLab Pages

    [原文链接]:https://www.tecchen.xyz/blog-hexo-env-03.html 我的个人博客:https://www.tecchen.xyz,博文同步发布到博客园. 由于精力 ...

  3. thinkphp5.0 CURL用post请求接口数据

    //测试 请求接口 public function index(){ $arr = array('a'=>'555','b'=>56454564); $data=$this->pos ...

  4. PHP之string

    string addcslashes() Quote string with slashes in a C style 以 C 语言风格使用反斜线转义字符串中的字符 addslashes() Quot ...

  5. selector.select()和selector.selectedKeys()

    当调用selector.select()时会阻塞: This method performs a blocking selection operation. It returns only after ...

  6. 利用keepalived构建高可用MySQL-HA

    关于MySQL-HA,目前有多种解决方案,比如heartbeat.drbd.mmm.共享存储,但是它们各有优缺点.heartbeat.drbd配置较为复杂,需要自己写脚本才能实现MySQL自动切换,对 ...

  7. 09 jdk1.5的并发容器:ConcurrentHashMap

    一 概述 JDK5中添加了新的concurrent包,相对同步容器而言,并发容器通过一些机制改进了并发性能 因为同步容器将所有对容器状态的访问都串行化了,这样保证了线程的安全性,所以这种方法的代价就是 ...

  8. JQuery Div scrollTop ScrollHeight

    jQuery 里和滚动条有关的概念很多,但是有三个属性和滚动条的拖动有关,就是:scrollTop.scrollLeft.scrollHeight.其中 scrollHeight 属性,互联网上几乎搜 ...

  9. ibatis插入正确但查询不出数据的问题

    现在,使用打印的sql在oracle数据库客户端能查询出结果,但执行ibatis查询语句不行,ibatis插入可以. 解决问题的历程: 1. 去掉sql中的where语句,仍然查找不到,确定不是sql ...

  10. 企业如何选择最佳的SSL

    如果你的企业有意采购SSL,那么本文可以给一个很好的方向.在本文中,我们将先简要介绍SSL定义及其工作原理,并探讨目前各种可用的SSL证书类型以及企业如何选择最佳的SSL. SSL定义 SSL及传输层 ...