MAVLink Linux/QNX/MacOs Integration Tutorial (UDP)

Overview

This program was written to test the udp connection to QGroundControl. It will send the necessary mavlink packets to QGroundControl in order to cause a new UAS object to be created and allow packets to be sent back. The code can be compiled unchanged on Linux, QNX and MacOS. Please find the correct GCC commands at the bottom of the page.

Note: In order for this code to work you must adjust the IP address of the host running qgroundcontrol. The default address is localhost (127.0.0.1), but you can change it by giving a parameter to the process, so that is the address to change.

To get full help, type after you compiled the code:

./mavlink_udp --help

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.

C-Code (MAVLink Version v1.0.0)

mavlink_udp.c
/*******************************************************************************
Copyright (C) 2010 Bryan Godbolt godbolt ( a t ) ualberta.ca
 
This program is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
 
This program is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
 
You should have received a copy of the GNU General Public License
along with this program. If not, see <http://www.gnu.org/licenses/>.
 
****************************************************************************/
/*
This program sends some data to qgroundcontrol using the mavlink protocol. The sent packets
cause qgroundcontrol to respond with heartbeats. Any settings or custom commands sent from
qgroundcontrol are printed by this program along with the heartbeats.
 
 
I compiled this program sucessfully on Ubuntu 10.04 with the following command
 
gcc -I ../../pixhawk/mavlink/include -o udp-server udp-server-test.c
 
the rt library is needed for the clock_gettime on linux
*/
/* These headers are for QNX, but should all be standard on unix/linux */
#include <stdio.h>
#include <errno.h>
#include <string.h>
#include <sys/socket.h>
#include <sys/types.h>
#include <netinet/in.h>
#include <unistd.h>
#include <stdlib.h>
#include <fcntl.h>
#include <time.h>
#if (defined __QNX__) | (defined __QNXNTO__)
/* QNX specific headers */
#include <unix.h>
#else
/* Linux / MacOS POSIX timer headers */
#include <sys/time.h>
#include <time.h>
#include <arpa/inet.h>
#endif
 
/* This assumes you have the mavlink headers on your include path
or in the same folder as this source file */
#include <mavlink.h>
 
 
#define BUFFER_LENGTH 2041 // minimum buffer size that can be used with qnx (I don't know why)
 
uint64_t microsSinceEpoch();
 
int main(int argc, char* argv[])
{
 
char help[] = "--help";
 
 
char target_ip[100];
 
float position[6] = {};
int sock = socket(PF_INET, SOCK_DGRAM, IPPROTO_UDP);
struct sockaddr_in gcAddr;
struct sockaddr_in locAddr;
//struct sockaddr_in fromAddr;
uint8_t buf[BUFFER_LENGTH];
ssize_t recsize;
socklen_t fromlen;
int bytes_sent;
mavlink_message_t msg;
uint16_t len;
int i = 0;
//int success = 0;
unsigned int temp = 0;
 
// Check if --help flag was used
if ((argc == 2) && (strcmp(argv[1], help) == 0))
{
printf("\n");
printf("\tUsage:\n\n");
printf("\t");
printf("%s", argv[0]);
printf(" <ip address of QGroundControl>\n");
printf("\tDefault for localhost: udp-server 127.0.0.1\n\n");
exit(EXIT_FAILURE);
}
 
 
// Change the target ip if parameter was given
strcpy(target_ip, "127.0.0.1");
if (argc == 2)
{
strcpy(target_ip, argv[1]);
}
 
 
memset(&locAddr, 0, sizeof(locAddr));
locAddr.sin_family = AF_INET;
locAddr.sin_addr.s_addr = INADDR_ANY;
locAddr.sin_port = htons(14551);
 
/* Bind the socket to port 14551 - necessary to receive packets from qgroundcontrol */
if (-1 == bind(sock,(struct sockaddr *)&locAddr, sizeof(struct sockaddr)))
{
perror("error bind failed");
close(sock);
exit(EXIT_FAILURE);
}
 
/* Attempt to make it non blocking */
if (fcntl(sock, F_SETFL, O_NONBLOCK | FASYNC) < 0)
{
fprintf(stderr, "error setting nonblocking: %s\n", strerror(errno));
close(sock);
exit(EXIT_FAILURE);
}
 
 
memset(&gcAddr, 0, sizeof(gcAddr));
gcAddr.sin_family = AF_INET;
gcAddr.sin_addr.s_addr = inet_addr(target_ip);
gcAddr.sin_port = htons(14550);
 
 
 
for (;;)
{
 
/*Send Heartbeat */
mavlink_msg_heartbeat_pack(1, 200, &msg, MAV_TYPE_HELICOPTER, MAV_AUTOPILOT_GENERIC, MAV_MODE_GUIDED_ARMED, 0, MAV_STATE_ACTIVE);
len = mavlink_msg_to_send_buffer(buf, &msg);
bytes_sent = sendto(sock, buf, len, 0, (struct sockaddr*)&gcAddr, sizeof(struct sockaddr_in));
 
/* Send Status */
mavlink_msg_sys_status_pack(1, 200, &msg, 0, 0, 0, 500, 11000, -1, -1, 0, 0, 0, 0, 0, 0);
len = mavlink_msg_to_send_buffer(buf, &msg);
bytes_sent = sendto(sock, buf, len, 0, (struct sockaddr*)&gcAddr, sizeof (struct sockaddr_in));
 
/* Send Local Position */
mavlink_msg_local_position_ned_pack(1, 200, &msg, microsSinceEpoch(),
position[0], position[1], position[2],
position[3], position[4], position[5]);
len = mavlink_msg_to_send_buffer(buf, &msg);
bytes_sent = sendto(sock, buf, len, 0, (struct sockaddr*)&gcAddr, sizeof(struct sockaddr_in));
 
/* Send attitude */
mavlink_msg_attitude_pack(1, 200, &msg, microsSinceEpoch(), 1.2, 1.7, 3.14, 0.01, 0.02, 0.03);
len = mavlink_msg_to_send_buffer(buf, &msg);
bytes_sent = sendto(sock, buf, len, 0, (struct sockaddr*)&gcAddr, sizeof(struct sockaddr_in));
 
 
memset(buf, 0, BUFFER_LENGTH);
recsize = recvfrom(sock, (void *)buf, BUFFER_LENGTH, 0, (struct sockaddr *)&gcAddr, &fromlen);
if (recsize > 0)
{
// Something received - print out all bytes and parse packet
mavlink_message_t msg;
mavlink_status_t status;
 
printf("Bytes Received: %d\nDatagram: ", (int)recsize);
for (i = 0; i < recsize; ++i)
{
temp = buf[i];
printf("%02x ", (unsigned char)temp);
if (mavlink_parse_char(MAVLINK_COMM_0, buf[i], &msg, &status))
{
// Packet received
printf("\nReceived packet: SYS: %d, COMP: %d, LEN: %d, MSG ID: %d\n", msg.sysid, msg.compid, msg.len, msg.msgid);
}
}
printf("\n");
}
memset(buf, 0, BUFFER_LENGTH);
sleep(1); // Sleep one second
}
}
 
 
/* QNX timer version */
#if (defined __QNX__) | (defined __QNXNTO__)
uint64_t microsSinceEpoch()
{
 
struct timespec time;
 
uint64_t micros = 0;
 
clock_gettime(CLOCK_REALTIME, &time);
micros = (uint64_t)time.tv_sec * 1000000 + time.tv_nsec/1000;
 
return micros;
}
#else
uint64_t microsSinceEpoch()
{
 
struct timeval tv;
 
uint64_t micros = 0;
 
gettimeofday(&tv, NULL);
micros = ((uint64_t)tv.tv_sec) * 1000000 + tv.tv_usec;
 
return micros;
}
#endif

Compilation

On Ubuntu Linux and Mac OS:
Adjust the relative path to your MAVLink folder, and then compile.

gcc -I ../../include/common -o mavlink_udp mavlink_udp.c

On QNX: Point the include path to the mavlink includes

gcc -I ../../include/common -lsocket -o mavlink_udp mavlink_udp.c

MAVLink Linux/QNX/MacOs Integration Tutorial (UDP)的更多相关文章

  1. MAVLink Onboard Integration Tutorial

    MAVLink Onboard Integration Tutorial MAVLink is a header-only library, which means that you don't ha ...

  2. Swift 3 and OpenGL on Linux and macOS with GLFW

    https://solarianprogrammer.com/2016/11/19/swift-opengl-linux-macos-glfw/ Swift 3 and OpenGL on Linux ...

  3. Vysor破解助手for Linux and macOS

    <Vysor Pro破解助手>提供了Windows下的Vysor破解工具,为了使用Linux及macOS同学的方便,最近整理了Linux及macOS版的Vysor破解助手. Linux版V ...

  4. Vmware中Linux或macOS客户端如何回收硬盘空间

    Vmware对于Windows的客户端,使用GUI操作硬盘回收和整理磁盘即可.对于Linux或macOS客户端,需要在安装Vmware Tools之后,在客户端OS的终端Terminal里输入命令进行 ...

  5. 深蓝词库转换2.5发布——支持微软五笔,支持Linux和macOS和更多命令行功能

    最近利用晚上的时间,对很久没有新版本发布的深蓝词库转换进行了版本升级.本次升级主要包含的功能包括: 一.支持Win10自带的微软五笔输入法用户自定义短语的导入导出. 1.在转换输入法词库列表中选择“W ...

  6. [Linux实践] macOS平台Homebrew更新brew update卡死,完美解决

    [Linux实践] macOS 平台 Homebrew 更新 brew update 卡死,完美解决 版本2020.01.05 摘要: 使用brew install [软件包]安装软件包时,卡在Upd ...

  7. MTU-TCP/IP协议栈-linux kernel-TCP丢包重传-UDP高性能-AI-

    http://view.inews.qq.com/a/20161025A0766200窄带时代的QQQQ是窄带时代极具代表性的产品,在那个网络传输效率比较低的年代,大家还记得Google的首页吗?Go ...

  8. Linux网络编程10——使用UDP实现五子棋对战

    思路 1. 通信 为了同步双方的棋盘,每当一方在棋盘上落子之后,都需要发送给对方一个msg消息,让对方知道落子位置.msg结构体如下: /* 用于发给对方的信息 */ typedef struct t ...

  9. Linux下Netty实现高性能UDP服务(SO_REUSEPORT)

    参考: https://www.jianshu.com/p/61df929aa98b SO_REUSEPORT学习笔记:http://www.blogjava.net/yongboy/archive/ ...

随机推荐

  1. 基于聚类的“图像分割”(python)

    基于聚类的“图像分割” 参考网站: https://zhuanlan.zhihu.com/p/27365576 昨天萌新使用的是PIL这个库,今天发现机器学习也可以这样玩. 视频地址Python机器学 ...

  2. [Alpha]Scrum Meeting#8

    github 本次会议项目由PM召开,时间为4月10日晚上10点30分 时长15分钟 任务表格 人员 昨日工作 下一步工作 木鬼 撰写每日例会报告 撰写每日例会报告 SiMrua 优化模型速度(iss ...

  3. CentOS 7 安装RocketMQ遇到的问题汇总

    1.运行broker时提示内存无法分配 解决办法:http://www.bubuko.com/infodetail-2088958.html

  4. 更换bbr内核

    1:首先yum update -y更新到最新CentOS 7.3 1611cat /etc/redhat-releaseCentOS Linux release 7.3.1611 (Core) 2: ...

  5. Spring Security OAuth 2开发者指南译

    Spring Security OAuth 2开发者指南译 介绍 这是用户指南的支持OAuth 2.0.对于OAuth 1.0,一切都是不同的,所以看到它的用户指南. 本用户指南分为两部分,第一部分为 ...

  6. Spring Boot的filter简单使用

    过滤器(Filter)的注册方法和 Servlet 一样,有两种方式:代码注册或者注解注册 1.代码注册方式 通过代码方式注入过滤器 @Bean     public FilterRegistrati ...

  7. ubuntu工具安装

    smplayer sudo add-apt-repository ppa:rvm/smplayer sudo apt-get update sudo apt-get install smplayer ...

  8. PHP之mb_convert_variables使用

    mb_convert_variables (PHP 4 >= 4.0.6, PHP 5, PHP 7) mb_convert_variables - Convert character code ...

  9. ubuntu关闭时间同步与centos更改时间

    环境:ubuntu 源于一次项目需要修改系统时间,但是每次修改后又被同步回网络时间,找了好久发现是这个原因: NTP即Network Time Protocol(网络时间协议),是一个互联网协议,用于 ...

  10. 开始使用 Vuejs 2.0 ---简单总结1

    Vue.js(读音 /vjuː/, 类似于 view) 是一套构建用户界面的 渐进式框架.与其他重量级框架不同的是,Vuejs 采用自底向上增量开发的设计.Vuejs 的核心库只关注视图层,并且非常容 ...