起因是查看飞控日志时发现地面站上传的平行航线,在日志看到航线却并不是平行的。

 然后对比了一下地面站上传的航点信息跟飞控读取到的航点信息

 发现经纬度只有前几位能够对应上,后几位都对应不上,两个点之间相差了50公分。地面站工程师认为地面站上传的数据没问题,是飞控解析的问题。

经检测,地面站上传航点任务用的是 MISSION ITEM (39),MISSION ITEM (39),在2020年就已经启用了,都2025年了,为啥还要用已经废弃了5年的消息?搞不懂。

但是该消息为啥会被弃用呢?

让我们一起来看下飞控是怎么解析该消息的。

在上一章我学习到了飞控是在GCS_MAVLINK::handle_mission_item(const mavlink_message_t &msg)函数中进行解析航点任务的。

//libraries\GCS_MAVLink\GCS_common.cpp
void GCS_MAVLINK::handle_mission_item(const mavlink_message_t &msg) ///解析航点的
{mavlink_mission_item_int_t mission_item_int;bool send_mission_item_warning = false;if (msg.msgid == MAVLINK_MSG_ID_MISSION_ITEM) {mavlink_mission_item_t mission_item;mavlink_msg_mission_item_decode(&msg, &mission_item); MAV_MISSION_RESULT ret = AP_Mission::convert_MISSION_ITEM_to_MISSION_ITEM_INT(mission_item, mission_item_int);if (ret != MAV_MISSION_ACCEPTED) {const MAV_MISSION_TYPE type = (MAV_MISSION_TYPE)mission_item_int.mission_type;send_mission_ack(msg, type, ret);return;}send_mission_item_warning = true;} else {mavlink_msg_mission_item_int_decode(&msg, &mission_item_int);//解码函数gcs().send_text(MAV_SEVERITY_CRITICAL,"ss%d %ld,%ld",msg_sum++,mavlink_msg_mission_item_int_get_x(&msg),mavlink_msg_mission_item_int_get_y(&msg));}const uint8_t current = mission_item_int.current;const MAV_MISSION_TYPE type = (MAV_MISSION_TYPE)mission_item_int.mission_type;if (type == MAV_MISSION_TYPE_MISSION && (current == 2 || current == 3)) {struct AP_Mission::Mission_Command cmd = {};MAV_MISSION_RESULT result = AP_Mission::mavlink_int_to_mission_cmd(mission_item_int, cmd);if (result != MAV_MISSION_ACCEPTED) {//decode failedsend_mission_ack(msg, MAV_MISSION_TYPE_MISSION, result);return;}// guided or change-altif (current == 2) {// current = 2 is a flag to tell us this is a "guided mode"// waypoint and not for the missionresult = (handle_guided_request(cmd) ? MAV_MISSION_ACCEPTED: MAV_MISSION_ERROR) ;} else if (current == 3) {//current = 3 is a flag to tell us this is a alt change only// add home alt if neededhandle_change_alt_request(cmd);// verify we received the commandresult = MAV_MISSION_ACCEPTED;}send_mission_ack(msg, MAV_MISSION_TYPE_MISSION, result);return;}// not a guided-mode reqestMissionItemProtocol *prot = gcs().get_prot_for_mission_type(type);if (prot == nullptr) {send_mission_ack(msg, type, MAV_MISSION_UNSUPPORTED);return;}if (send_mission_item_warning) {prot->send_mission_item_warning();}if (!prot->receiving) {send_mission_ack(msg, type, MAV_MISSION_ERROR);return;}prot->handle_mission_item(msg, mission_item_int);
}

 主要看这部分

//libraries\GCS_MAVLink\GCS_common.cpp
//void GCS_MAVLINK::handle_mission_item(const mavlink_message_t &msg)if (msg.msgid == MAVLINK_MSG_ID_MISSION_ITEM) {mavlink_mission_item_t mission_item;mavlink_msg_mission_item_decode(&msg, &mission_item);
//    gcs().send_text(MAV_SEVERITY_CRITICAL,"%d %f,%f",msg_sum++,mavlink_msg_mission_item_get_x(&msg),mavlink_msg_mission_item_get_y(&msg));
//    gcs().send_text(MAV_SEVERITY_CRITICAL, "x:%ld,y:%ld",(int32_t)(1.0e7f*mission_item.x),(int32_t)(1.0e7f*mission_item.y)); //这个跟地面站读取的一致gcs().send_text(MAV_SEVERITY_CRITICAL, "x:%f,y:%f",(mission_item.x),(mission_item.y));MAV_MISSION_RESULT ret = AP_Mission::convert_MISSION_ITEM_to_MISSION_ITEM_INT(mission_item, mission_item_int);if (ret != MAV_MISSION_ACCEPTED) {const MAV_MISSION_TYPE type = (MAV_MISSION_TYPE)mission_item_int.mission_type;send_mission_ack(msg, type, ret);return;}send_mission_item_warning = true;}

 mavlink_msg_mission_item_decode(&msg, &mission_item);是将msg的Mavlink消息解析并存放到mission_item中,mission_item的定义为:

//ardupilot\build\CubeOrange\libraries\GCS_MAVLink\include\mavlink\v2.0\common\mavlink_msg_mission_item.h
typedef struct __mavlink_mission_item_t {float param1; /*<  PARAM1, see MAV_CMD enum*/float param2; /*<  PARAM2, see MAV_CMD enum*/float param3; /*<  PARAM3, see MAV_CMD enum*/float param4; /*<  PARAM4, see MAV_CMD enum*/float x; /*<  PARAM5 / local: X coordinate, global: latitude*/float y; /*<  PARAM6 / local: Y coordinate, global: longitude*/float z; /*<  PARAM7 / local: Z coordinate, global: altitude (relative or absolute, depending on frame).*/uint16_t seq; /*<  Sequence*/uint16_t command; /*<  The scheduled action for the waypoint.*/uint8_t target_system; /*<  System ID*/uint8_t target_component; /*<  Component ID*/uint8_t frame; /*<  The coordinate system of the waypoint.*/uint8_t current; /*<  false:0, true:1*/uint8_t autocontinue; /*<  Autocontinue to next waypoint*/uint8_t mission_type; /*<  Mission type.*/
} mavlink_mission_item_t;

其中的xy就是经纬度,将经纬度单独输出看一下

从输出的数据可以看到,经纬度都有个规律是都只有7个数字,那是因为float数据只有7位精度。

 从飞控读取到的航点信息确实是只有前6位数值是一致的。后面的数据为啥就不一致了呢?

继续看后面飞控的使用

 MAV_MISSION_RESULT ret = AP_Mission::convert_MISSION_ITEM_to_MISSION_ITEM_INT(mission_item, mission_item_int);

mission_item用于这里了,MAV_MISSION_RESULT AP_Mission::convert_MISSION_ITEM_to_MISSION_ITEM_INT函数会将航点任务信息进一步使用。

D:\Ardupilot\4.5.1\4.5\git_ardupilot\ardupilot4.5.1\ardupilot\libraries\AP_Mission\AP_Mission.cpp
MAV_MISSION_RESULT AP_Mission::convert_MISSION_ITEM_to_MISSION_ITEM_INT(const mavlink_mission_item_t &packet,mavlink_mission_item_int_t &mav_cmd)
{// TODO: rename mav_cmd to mission_item_int// TODO: rename packet to mission_itemmav_cmd.param1 = packet.param1;mav_cmd.param2 = packet.param2;mav_cmd.param3 = packet.param3;mav_cmd.param4 = packet.param4;mav_cmd.z = packet.z;mav_cmd.seq = packet.seq;mav_cmd.command = packet.command;mav_cmd.target_system = packet.target_system;mav_cmd.target_component = packet.target_component;mav_cmd.frame = packet.frame;mav_cmd.current = packet.current;mav_cmd.autocontinue = packet.autocontinue;mav_cmd.mission_type = packet.mission_type;/*the strategy for handling both MISSION_ITEM and MISSION_ITEM_INTis to pass the lat/lng in MISSION_ITEM_INT straight through, andfor MISSION_ITEM multiply by 1e7 here. We need an exception forany commands which use the x and y fields not aslatitude/longitude.*/if (!cmd_has_location(packet.command)) {mav_cmd.x = packet.x;mav_cmd.y = packet.y;} else {//these commands use x and y as lat/lon. We need to// multiply by 1e7 to convert to int32_tif (!check_lat(packet.x)) {return MAV_MISSION_INVALID_PARAM5_X;}if (!check_lng(packet.y)) {return MAV_MISSION_INVALID_PARAM6_Y;}mav_cmd.x = packet.x * 1.0e7f;mav_cmd.y = packet.y * 1.0e7f;}return MAV_MISSION_ACCEPTED;
}

可以看到经纬度最终都 *1.0e7,而经纬度都是float数据,这里放大了100万倍,那么精度就丢失了。如:

 就这样精度丢失,最终导致地面站上传的航点跟实际的航点相差50公分!

对于这个bug,官网的解决方法就是直接弃用该MISSION ITEM (39),改成MISSION ITEM INT(73),将经纬度由float改成整型数据,以保障精度问题。

至于怎么保障float的精度问题也有其他方法(仅作为个人意见):

如地面站上传的float数值小于7位:

 

但这样会导致飞控无法做到精准导航,故不可取。

其二是在放大时先保障当前精度后再进行处理

但同样ff数值也只能保障前7位数值,导致飞控无法做到精准导航,故不可取。

 

 

 当然也可以用double数据

但官网没有该类型。

本文来自互联网用户投稿,该文观点仅代表作者本人,不代表本站立场。本站仅提供信息存储空间服务,不拥有所有权,不承担相关法律责任。
如若转载,请注明出处:http://www.pswp.cn/diannao/89179.shtml
繁体地址,请注明出处:http://hk.pswp.cn/diannao/89179.shtml
英文地址,请注明出处:http://en.pswp.cn/diannao/89179.shtml

如若内容造成侵权/违法违规/事实不符,请联系英文站点网进行投诉反馈email:809451989@qq.com,一经查实,立即删除!

相关文章

车载ECU刷写文件格式汇总详解

我是穿拖鞋的汉子&#xff0c;魔都中坚持长期主义的汽车电子工程师。 老规矩&#xff0c;分享一段喜欢的文字&#xff0c;避免自己成为高知识低文化的工程师&#xff1a; 做到欲望极简&#xff0c;了解自己的真实欲望&#xff0c;不受外在潮流的影响&#xff0c;不盲从&#x…

Redis核心知识详解:从全局命令到高级数据结构

一、Redis全局命令详解 1.1 键查看与管理 dbsize&#xff1a;高效获取键总数&#xff08;O(1)操作&#xff09; 127.0.0.1:6379> dbsize (integer) 8 keys&#xff1a;生产环境避免使用&#xff08;O(n)操作&#xff09; # 查找user开头的键&#xff08;不推荐生产使用…

【网络】Linux 内核优化实战 - net.ipv4.tcp_mem

目录 参数结构与含义与缓冲区大小参数的区别内存管理机制详解1. 内存使用状态与触发逻辑2. 与其他参数的协同关系 典型调整场景与配置示例场景 1&#xff1a;高并发低带宽服务&#xff08;如 API 网关&#xff0c;数万连接但单连接流量小&#xff09;场景 2&#xff1a;高带宽低…

插入排序的简单介绍

今天给大家简单介绍一下插入排序。 插入排序&#xff0c;其基本思想是将未排序的数据逐步插入到已排序序列中的合适位置&#xff0c;从而使整个序列逐渐有序。 下面我们看一个排序的过程&#xff08;升序&#xff09;&#xff0c;给定一个int类型的数组&#xff0c;利用插入排…

docker搭建minio和python使用minio

1 准备工作 1.创建目录 [rootk8s-storage tmp]# mkdir -pv minio/{data,conf} mkdir: created directory ‘minio’ mkdir: created directory ‘minio/data’ mkdir: created directory ‘minio/conf’[rootk8s-storage minio]# chmod 777 -R *2.生成https证书 openssl req…

开源代码修复新标杆——月之暗面最新开源编程模型Kimi-Dev-72B本地部署教程,自博弈修复 Bug

一、介绍 Kimi-Dev-72B是由月之暗面&#xff08;Moonshot AI&#xff09;最新开源的AI编程模型&#xff0c;专为软件工程任务设计&#xff0c;并登顶 SWE-bench Verified 基准测试榜首&#xff0c;超越 DeepSeek-R1 等模型&#xff0c;成为当前开源代码模型的 SOTA&#xff1a…

微服务架构之基本设计原则

作为系统架构师&#xff0c;在进行架构设计时需要遵循一系列经过实践验证的核心原则&#xff0c;这些原则贯穿于需求分析、模块划分、技术选型和系统演进的全流程。以下从核心设计原则、架构特性原则、工程实践原则三个维度&#xff0c;结合具体案例展开说明&#xff1a; 一、…

Wpf布局之WrapPanel面板!

文章目录 前言一、引言二、使用步骤 前言 Wpf布局之WrapPanel面板&#xff01; 一、引言 WrapPanel面板以一次一行或一列的方式布置控件&#xff01; 二、使用步骤 WrapPanel面板Orientation属性默认是"Horizontal"&#xff0c;将控件从左向右进行排列&#xff…

QEMU运行RISCV版Ubuntu

宿主机为ubuntu20.04&#xff0c;推荐ubuntu 20.04 risc-v版&#xff0c; 宿主机为ubuntu24.04&#xff0c;推荐ubuntu 24.04 risc-v版&#xff0c; 安装ubuntu 24.04 risc-v基本步骤&#xff1a; 1&#xff0c; sudo apt update sudo apt install opensbi qemu-system-misc…

【LeetCode 热题 100】239. 滑动窗口最大值——(解法一)滑动窗口+暴力解

Problem: 239. 滑动窗口最大值 题目&#xff1a;给你一个整数数组 nums&#xff0c;有一个大小为 k 的滑动窗口从数组的最左侧移动到数组的最右侧。你只可以看到在滑动窗口内的 k 个数字。滑动窗口每次只向右移动一位。返回滑动窗口中的最大值 。 文章目录 整体思路完整代码时空…

攻防世界-MISC-red_green

知识点 1.pngLSB隐写 步骤 方法一&#xff1a;zsteg 打开附件&#xff0c;是一张图片&#xff0c;打开看不懂&#xff08;其实由两种颜色构成&#xff0c;0和1&#xff09;&#xff0c;用zsteg查看&#xff0c;发现隐写了一张jpg图片&#xff0c;使用zsteg提取。打开jpg图片…

归因问答-如何进行自动评估

归因模型函数g的形式化表示 输入&#xff1a;用户问题q 输出&#xff1a;(a, p), 其中a为答案&#xff0c;p为原始文章中支持答案a的段落。 1&#xff09;单样本归因 针对输入问题q&#xff0c;如何评估归因模型g输出中段落p是对答案a的正确归因。 在论文arributed qa中&…

基于vue+View UI的组织机构选择

1、效果 1、代码 <template><Button type"primary" click"modal true">点击选择</Button><div v-if"selectedArr.length > 0"><p>已选择项&#xff1a;</p><div v-for"(item, index) in sel…

人大金仓Kingbase数据库KSQL 常用命令指南

人大金仓Kingbase数据库KSQL 常用命令指南 1. 连接与基本操作 1.1 连接数据库 # 基础语法 ksql -U 用户名 -d 数据库名 -h 主机名 -p 端口号 # 示例 ksql -U system -d testdb -h 127.0.0.1 -p 543211.2 执行SQL脚本 # 基础语法 ksql -U <用户名> -W -f <SQL脚本文…

从萌芽到领航:广州华锐互动的 AR 奋进之路​

在 AR 技术这片充满无限可能的领域中&#xff0c;广州华锐互动数字科技有限公司宛如一颗耀眼的新星&#xff0c;熠熠生辉。广州华锐互动成立于 2008 年&#xff0c;在那个 AR 技术尚处于萌芽阶段、大众认知度还较低的时期&#xff0c;广州华锐互动便凭借着前瞻性的战略眼光和对…

redisson看门狗实现原理

Redisson 看门狗&#xff08;Watch Dog&#xff09;机制实现原理 Redisson 的 Watch Dog 机制是分布式锁的核心组件之一&#xff0c;用于 自动续期 锁的过期时间&#xff0c;防止业务逻辑执行时间超过锁的持有时间&#xff0c;导致锁提前释放而引发并发问题。以下是其实现原理…

C++中explicit详解

文章目录 1. **防止隐式类型转换**示例1&#xff1a;没有使用explicit示例2&#xff1a;使用explicit 2. **防止拷贝初始化**示例1&#xff1a;没有使用explicit示例2&#xff1a;使用explicit 3. **防止隐式类型转换的链式调用**示例1&#xff1a;没有使用explicit示例2&#…

代码部落 20250629 CSP-J复赛 模拟赛

网址&#xff1a;代码部落 一&#xff1a; 相濡以沫 β&#xff08;代码请自写&#xff09; 签到题&#xff0c;如果a[i]<a[i1] a[i]a[i1],反之&#xff0c;直接输出No 二 共同富裕&#xff08;代码请自写&#xff09; 签到题&#xff0c;用sort前缀和 如果最富有的个…

零基础学习RabbitMQ(5)--工作模式(1)

在前面的章节中我们简单介绍过一些RabbitMQ的工作模式&#xff0c;RabbitMQ共提供了七种工作模式进行消息传递&#xff0c;这里我们来详细介绍。 1. Simple(简单模式) P&#xff1a;生产者 C&#xff1a;消费者 特点&#xff1a;一个生产者一个消费者&#xff0c;消息只能被…

Android Liunx ffmpeg交叉编译

本文的交叉编译在window上安装VMware&#xff0c;使用Ubuntu20.4进行的编译。 一、安装NDK&#xff1a; 1、下载解压&#xff1a; 在NDK 下载 | Android NDK | Android Developers下载Liunx平台的NDK。 本人下载的是android-ndk-r27c-linux.zip版本的。 解压android-ndk-r…