生成c++版本的mavlink库
- 下载mavlink源码
git clone https://github.com/mavlink/mavlink.git --recursive
- 安装python3并安装futures库
pip install futures
- 运行mavklink源码根目录下的mavgenerate.py
python mavgenerate.py
- 生成c++库(只支持mavlink2.0版本)
拷贝整个库到linux系统中,在c++脚本中直接引用
#include "mymavlink/common/mavlink.h"
主程序
调用pack相关的接口打包消息
调用mavlink_msg_to_send_buffer转换消息结构
建立udp连接把消息发送出去
int main()
{
SocketUdp s;
s.setIpPort("192.168.0.101", 8000, "192.168.0.103", 8000);
thread(&SocketUdp::openUdp, &s).detach();
mavlink_message_t msg;
uint8_t buf[1024];
uint16_t len;
for(int i = 0; i < 10; i++)
{
// mavlink_msg_heartbeat_pack(1, 1, &msg, MAV_TYPE_HELICOPTER, MAV_AUTOPILOT_GENERIC, MAV_MODE_GUIDED_ARMED, 0, MAV_STATE_ACTIVE);
mavlink_msg_altitude_pack(1, 1, &msg, 12345, 1.2, 1.7, 3.14, 0.01, 0.02, 0.03);
len = mavlink_msg_to_send_buffer(buf, &msg);
s.sendHexData(buf, len);
sleep(1);
}
return 0;
}
编译运行
g++ practice.cpp -lpthread
./a.out
在windows中使用网络调试助手接收数据
[11:05:07.790]收←◆FD 09 00 00 01 01 01 00 00 00 00 00 00 00 04 00 D8 04 03 CC 41
[11:05:08.790]收←◆FD 09 00 00 02 01 01 00 00 00 00 00 00 00 04 00 D8 04 03 ED DB
[11:05:09.790]收←◆FD 09 00 00 03 01 01 00 00 00 00 00 00 00 04 00 D8 04 03 FD 55
[11:05:10.790]收←◆FD 09 00 00 04 01 01 00 00 00 00 00 00 00 04 00 D8 04 03 BE E7
[11:05:11.792]收←◆FD 09 00 00 05 01 01 00 00 00 00 00 00 00 04 00 D8 04 03 AE 69
[11:05:12.792]收←◆FD 09 00 00 06 01 01 00 00 00 00 00 00 00 04 00 D8 04 03 8F F3
[11:05:13.791]收←◆FD 09 00 00 07 01 01 00 00 00 00 00 00 00 04 00 D8 04 03 9F 7D
[11:05:14.790]收←◆FD 09 00 00 08 01 01 00 00 00 00 00 00 00 04 00 D8 04 03 18 9F
[11:05:15.791]收←◆FD 09 00 00 09 01 01 00 00 00 00 00 00 00 04 00 D8 04 03 08 11
[11:16:10.866]收←◆FD 20 00 00 01 01 01 8D 00 00 39 30 00 00 00 00 00 00 9A 99 99 3F 9A 99 D9 3F C3 F5 48 40 0A D7 23 3C 0A D7 A3 3C 8F C2 F5 3C DA B5
[11:16:11.864]收←◆FD 20 00 00 02 01 01 8D 00 00 39 30 00 00 00 00 00 00 9A 99 99 3F 9A 99 D9 3F C3 F5 48 40 0A D7 23 3C 0A D7 A3 3C 8F C2 F5 3C E8 6A
[11:16:12.867]收←◆FD 20 00 00 03 01 01 8D 00 00 39 30 00 00 00 00 00 00 9A 99 99 3F 9A 99 D9 3F C3 F5 48 40 0A D7 23 3C 0A D7 A3 3C 8F C2 F5 3C 06 20
[11:16:13.868]收←◆FD 20 00 00 04 01 01 8D 00 00 39 30 00 00 00 00 00 00 9A 99 99 3F 9A 99 D9 3F C3 F5 48 40 0A D7 23 3C 0A D7 A3 3C 8F C2 F5 3C 9D DC
[11:16:14.867]收←◆FD 20 00 00 05 01 01 8D 00 00 39 30 00 00 00 00 00 00 9A 99 99 3F 9A 99 D9 3F C3 F5 48 40 0A D7 23 3C 0A D7 A3 3C 8F C2 F5 3C 73 96
[11:16:15.867]收←◆FD 20 00 00 06 01 01 8D 00 00 39 30 00 00 00 00 00 00 9A 99 99 3F 9A 99 D9 3F C3 F5 48 40 0A D7 23 3C 0A D7 A3 3C 8F C2 F5 3C 41 49
[11:16:16.867]收←◆FD 20 00 00 07 01 01 8D 00 00 39 30 00 00 00 00 00 00 9A 99 99 3F 9A 99 D9 3F C3 F5 48 40 0A D7 23 3C 0A D7 A3 3C 8F C2 F5 3C AF 03
[11:16:17.869]收←◆FD 20 00 00 08 01 01 8D 00 00 39 30 00 00 00 00 00 00 9A 99 99 3F 9A 99 D9 3F C3 F5 48 40 0A D7 23 3C 0A D7 A3 3C 8F C2 F5 3C 66 B8
[11:16:18.866]收←◆FD 20 00 00 09 01 01 8D 00 00 39 30 00 00 00 00 00 00 9A 99 99 3F 9A 99 D9 3F C3 F5 48 40 0A D7 23 3C 0A D7 A3 3C 8F C2 F5 3C 88 F2
FD开头的就是mavlink2.0的消息,msgid是三个字节(低, 中, 高)
8D 00 00 是 141
在mavlink中查找#141,altitude是海拔,不是attitude#30(姿态)如下
解析数据
解析heartbeat和altitude数据
使用 mavlink_parse_char 解析每一个字节,它已经做了识别一条报文的头部,尾部,校验的工作
拿到数据类型后再进行消息转换,并解析对应类型的数据
主要代码
while (is_connect)
{
int result = recvfrom(socket_fp, buffer, sizeof(buffer), 0, (sockaddr*)&client_addr, &client_addr_len);
cout << result << endl;
if (result <= 0) {
is_connect = false;
} else {
for (int i=0; i< result; i++) {
printf("%d ", buffer[i]);
}
printf("\n*****\n");
mavlink_message_t msg;
mavlink_status_t status;
for (int i=0; i< result; i++) {
if (mavlink_parse_char(MAVLINK_COMM_0, buffer[i], &msg, &status) == 1) {
switch (msg.msgid) {
case MAVLINK_MSG_ID_HEARTBEAT:
cout << "heartbeat: "<< endl;
mavlink_heartbeat_t heartbeat;
mavlink_msg_heartbeat_decode(&msg, &heartbeat);
cout << "type: " << (int)heartbeat.type << endl;
cout << "autopilot: " << (int)heartbeat.autopilot << endl;
cout << "base_mode: " << (int)heartbeat.base_mode << endl;
cout << "system_status: " << (int)heartbeat.system_status << endl;
cout << "mavlink_version: " << (int)heartbeat.mavlink_version << endl;
break;
case MAVLINK_MSG_ID_ALTITUDE:
cout << "altitude: "<<endl;
mavlink_altitude_t altitude;
mavlink_msg_altitude_decode(&msg, &altitude);
cout << "altitude_monotonic: " << (float)altitude.altitude_monotonic << endl;
cout << "altitude_local: " << (float)altitude.altitude_local << endl;
break;
default:
break;
}
}
}
}
}
结果