MAVLink Linux/QNX/MacOs Integration Tutorial (UDP)
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)的更多相关文章
- MAVLink Onboard Integration Tutorial
MAVLink Onboard Integration Tutorial MAVLink is a header-only library, which means that you don't ha ...
- 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 ...
- Vysor破解助手for Linux and macOS
<Vysor Pro破解助手>提供了Windows下的Vysor破解工具,为了使用Linux及macOS同学的方便,最近整理了Linux及macOS版的Vysor破解助手. Linux版V ...
- Vmware中Linux或macOS客户端如何回收硬盘空间
Vmware对于Windows的客户端,使用GUI操作硬盘回收和整理磁盘即可.对于Linux或macOS客户端,需要在安装Vmware Tools之后,在客户端OS的终端Terminal里输入命令进行 ...
- 深蓝词库转换2.5发布——支持微软五笔,支持Linux和macOS和更多命令行功能
最近利用晚上的时间,对很久没有新版本发布的深蓝词库转换进行了版本升级.本次升级主要包含的功能包括: 一.支持Win10自带的微软五笔输入法用户自定义短语的导入导出. 1.在转换输入法词库列表中选择“W ...
- [Linux实践] macOS平台Homebrew更新brew update卡死,完美解决
[Linux实践] macOS 平台 Homebrew 更新 brew update 卡死,完美解决 版本2020.01.05 摘要: 使用brew install [软件包]安装软件包时,卡在Upd ...
- MTU-TCP/IP协议栈-linux kernel-TCP丢包重传-UDP高性能-AI-
http://view.inews.qq.com/a/20161025A0766200窄带时代的QQQQ是窄带时代极具代表性的产品,在那个网络传输效率比较低的年代,大家还记得Google的首页吗?Go ...
- Linux网络编程10——使用UDP实现五子棋对战
思路 1. 通信 为了同步双方的棋盘,每当一方在棋盘上落子之后,都需要发送给对方一个msg消息,让对方知道落子位置.msg结构体如下: /* 用于发给对方的信息 */ typedef struct t ...
- Linux下Netty实现高性能UDP服务(SO_REUSEPORT)
参考: https://www.jianshu.com/p/61df929aa98b SO_REUSEPORT学习笔记:http://www.blogjava.net/yongboy/archive/ ...
随机推荐
- jenkins发送测试报告邮件
1.安装插件 Email Extension Plugin 2.设置Extended E-mail Notification a."系统管理"--“系统设置”.配置Extende ...
- python 报错: Dog() takes no arguments
后来上网找了一下.发现是 构造方法 __init__ 两边的下划线是双下划线,我写的是单下划线. 读书不认真,该打. 特此记录.
- Java NIO开发需要注意的陷阱(转)
陷阱1:处理事件忘记移除key在select返回值大于0的情况下,循环处理Selector.selectedKeys集合,每处理一个必须从Set中移除 Iterator<SelectionKey ...
- 【WinSCP】WinSCP 5.x使用密钥连接服务器
在WinSCP 4.x中,主页面有一个添加密钥文件的选项,如下图所示 但是在WinSCP 5.x中主界面发生了很大的变化 在主页上没有了载入密钥文件的选项,那么我们应该怎么使用密钥验证呢? WinSC ...
- JavaScript设计模式-16.装饰者模式(上)
<!DOCTYPE html> <html> <head> <meta charset="UTF-8"> <title> ...
- 微服务Kong(七)——CLI参考
KONG提供了一套CLI(命令行界面)命令,您可以通过它来启动.停止和管理您的Kong实例.CLI管理您的本地节点(如在当前机器上). 全局配置 所有命令都采用一组指定的可选标志作为参数: --hel ...
- AngularJS 的常用特性(一)
前言:AngularJS 是一款来自 Google 的前端 JS 框架,该框架已经被应用到了 Google 的多款产品中,这款框架最核心特性有:MVC.模块化.自动化双向数据绑定.语义化标签.依赖注入 ...
- windows 7 做AP
启动脚本: @echo off netsh wlan set hostednetwork mode=allow ssid=<ap-name> key=<password> ne ...
- c++ 沉思录---代理类
一.问题 如何设计一容器能包含彼此不同而又相互关联的类的对象(处于完整的继承层次的类)?因为一般的数组容器都只能包含一种类型的对象. 假设有一个表示不同类型的交通工具的类的派生层次: class Ve ...
- 解析Excel----ExcelHelper
public static class ExcelHelper { /// <summary> /// 获取单元格的值 /// </summary> /// <param ...