PIXHAWK(ardupilot4.52)NMEA的解析bug

最近在測試過程中發現在橢球高為負的地方,地面站讀取GPS_RAW_INT (24)消息中的alt高度竟然是正值。而消息中定義的alt并不是一個unsigned數據,理論上是帶有正負符號的。

查看gga的原始信息:

$GPGGA,063718.40,3714.8533856,N,11845.9411766,E,4,35,0.5,-0.3237,M,0.000,M,1.4,0002*60

?高程為-0.3237,高程確實為負值。

修改了一下代碼,單獨輸出一下高程進行測。

//AP_GPS.cpp
void AP_GPS::send_mavlink_gps_raw(mavlink_channel_t chan)
{const Location &loc = location(0);float hacc = 0.0f;float vacc = 0.0f;float sacc = 0.0f;float undulation = 0.0;int32_t height_elipsoid_mm = 0;if (get_undulation(0, undulation)) {height_elipsoid_mm = loc.alt*10 - undulation*1000;}horizontal_accuracy(0, hacc);vertical_accuracy(0, vacc);speed_accuracy(0, sacc);gcs().send_text(MAV_SEVERITY_CRITICAL, "remaining=%ld!",loc.alt * 10UL); //單獨輸出高程mavlink_msg_gps_raw_int_send(chan,last_fix_time_ms(0)*(uint64_t)1000,status(0),          //解狀態loc.lat,        // in 1E7 degreesloc.lng,        // in 1E7 degreesloc.alt * 10UL, // in mmget_hdop(0),get_vdop(0),ground_speed(0)*100,  // cm/sground_course(0)*100, // 1/100 degrees,num_sats(0), //搜星數量height_elipsoid_mm,   // Ellipsoid height in mmhacc * 1000,          // one-sigma standard deviation in mmvacc * 1000,          // one-sigma standard deviation in mmsacc * 1000,          // one-sigma standard deviation in mm/s0,                    // TODO one-sigma heading accuracy standard deviationgps_yaw_cdeg(0));
}

更新固件后,將gga輸入,輸出確實變成了正值的:320。

繼續索源,直接到NMEA解析中查看。

//AP_GPS_NMEA.cpp// Processes a just-completed term
// Returns true if new sentence has just passed checksum test and is validated
bool AP_GPS_NMEA::_term_complete()
{// handle the last term in a message/**省略****/
/**省略****/
/**省略****/case _GPS_SENTENCE_GGA + 9: // Altitude (GPGGA)_new_altitude = _parse_decimal_100(_term); //這里將負值改成正值了!//   _new_altitude = _parse_decimal_100("-1.24"); //這里將負值改成正值了!//   gcs().send_text(MAV_SEVERITY_CRITICAL, "now=%s",_term);//    gcs().send_text(MAV_SEVERITY_CRITICAL, "now=%ld",_new_altitude);break;// course and speed//case _GPS_SENTENCE_RMC + 7: // Speed (GPRMC)case _GPS_SENTENCE_VTG + 5: // Speed (VTG)
/**省略****/
}

請注意這個函數!!

?_new_altitude = _parse_decimal_100(_term); //這里將負值改成正值了!

經過測試,當_parse_decimal_100函數輸入"-0.3237",輸出是:320。

但是!當輸入是"-1.24"時,輸出是:-124。

測試結果確實是能區分正負符號的,但是為啥輸入-0.3237時,輸出是正值呢?

繼續看_parse_decimal_100(_term)函數。

//AP_GPS_NMEA.cpp
int32_t AP_GPS_NMEA::_parse_decimal_100(const char *p)
{char *endptr = nullptr;long ret = 100 * strtol(p, &endptr, 10);  //提取到小數點之前的數字int sign = ret < 0 ? -1 : 1;//    gcs().send_text(MAV_SEVERITY_CRITICAL, "ret1=%ld",ret);if (ret >= (long)INT32_MAX) {return INT32_MAX;}if (ret <= (long)INT32_MIN) {return INT32_MIN;}if (endptr == nullptr || *endptr != '.') {return ret;}if (isdigit(endptr[1])) {  //提取小數點后的數字ret += sign * 10 * DIGIT_TO_VAL(endptr[1]);if (isdigit(endptr[2])) {ret += sign * DIGIT_TO_VAL(endptr[2]);if (isdigit(endptr[3])) {ret += sign * (DIGIT_TO_VAL(endptr[3]) >= 5);}}}//   gcs().send_text(MAV_SEVERITY_CRITICAL, "ret2=%ld",ret);return ret;
}

將該函數單獨拎出來進行測試,輸入-0.3237的結果為:

?輸入-1.3237的結果為:

?

問題出現在前端,前端用到了strtol函數?,strtol函數是將字符串轉成長整數,是能夠區分正負符號的,但僅提取小數點之前的數值。

那么問題就來了,當小數點之前的數值為0時,0是不分正負的!

所以就導致了輸入-0.3237,輸出變成了正值的32。

在代碼中可以看到有定義一個sign變量進行正負判斷,那么現在多加一層判斷彌補當小數點之前為0的情況。

//AP_GPS_NMEA.cpp
int32_t AP_GPS_NMEA::_parse_decimal_100(const char *p)
{char *endptr = nullptr;long ret = 100 * strtol(p, &endptr, 10);  //提取到小數點之前的數字int sign = ret < 0 ? -1 : 1;if(ret==0) //優化當數值為-0.1的情況{if(atof(p)<-0.00001)sign=-1;}//    gcs().send_text(MAV_SEVERITY_CRITICAL, "ret1=%ld",ret);if (ret >= (long)INT32_MAX) {return INT32_MAX;}if (ret <= (long)INT32_MIN) {return INT32_MIN;}if (endptr == nullptr || *endptr != '.') {return ret;}if (isdigit(endptr[1])) {  //提取小數點后的數字ret += sign * 10 * DIGIT_TO_VAL(endptr[1]);if (isdigit(endptr[2])) {ret += sign * DIGIT_TO_VAL(endptr[2]);if (isdigit(endptr[3])) {ret += sign * (DIGIT_TO_VAL(endptr[3]) >= 5);}}}//   gcs().send_text(MAV_SEVERITY_CRITICAL, "ret2=%ld",ret);return ret;
}

?再次測試,輸入-0.3237時,能夠正常輸出 -32了

問題解決。?

本文來自互聯網用戶投稿,該文觀點僅代表作者本人,不代表本站立場。本站僅提供信息存儲空間服務,不擁有所有權,不承擔相關法律責任。
如若轉載,請注明出處:http://www.pswp.cn/news/912663.shtml
繁體地址,請注明出處:http://hk.pswp.cn/news/912663.shtml
英文地址,請注明出處:http://en.pswp.cn/news/912663.shtml

如若內容造成侵權/違法違規/事實不符,請聯系多彩編程網進行投訴反饋email:809451989@qq.com,一經查實,立即刪除!

相關文章

Linux容器講解以及對應軟件使用

一、容器基礎知識講解 1.1 微服務的部署策略 部署單體應用意味著運行大型應用的多個相同副本&#xff0c;通常提供若干臺&#xff08;N&#xff09;服務器&#xff08;物理機或虛擬 機&#xff09;&#xff0c;在每臺服務器上運行若干個&#xff08;M&#xff09;應用實例。部…

企業級應用技術-ELK日志分析系統

目錄 #1.1ELK平臺介紹 1.1.1ELK概述 1.1.2Elasticsearch 1.1.3Logstash 1.1.4Kibana #2.1部署ES群集 2.1.1基本配置 2.1.2安裝Elasticsearch 2.1.3安裝Logstash 2.1.4Filebeat 2.1.5安裝Kibana 1.1ELK平臺介紹 1.1.1ELK概述 ELK 是三個開源工具的縮寫&#xff0c;分別是Elas…

Shiro漏洞復現

Shiro簡介 Apache Shiro是一種功能強大且易于使用的Java安全框架&#xff0c;它執行身份驗證、授權、 加密和會話管理&#xff0c;可用于保護任何應用程序的安全。 Shiro提供了應用程序安全性API來執行以下方面&#xff1a; 1.身份驗證&#xff1a;證明用戶身份&#xff0c;通…

VSCode 中使用 Google Test(GTest)框架測試

VSCode 中使用 Google Test&#xff08;GTest&#xff09;框架在 VSCode 中對 C 代碼進行測試的示例&#xff1a; 一、Unbutu x86使用gtest 環境配置 安裝 GTest &#xff1a;在 Ubuntu 系統中&#xff0c;可以通過命令sudo apt-get install libgtest-dev安裝 GTest 庫。對于…

【1.6 漫畫數據庫設計實戰 - 從零開始設計高性能數據庫】

1.6 漫畫數據庫設計實戰 - 從零開始設計高性能數據庫 &#x1f3af; 學習目標 掌握數據庫表結構設計原則理解字段類型選擇與優化學會雪花算法ID生成策略掌握索引設計與優化技巧了解分庫分表設計方案 &#x1f4d6; 故事開始 小明: “老王&#xff0c;我總是不知道怎么設計數…

OSPF虛擬鏈路術語一覽:快速掌握網絡路由

大家好&#xff0c;這里是G-LAB IT實驗室。今天帶大家了解一下OSPF的相關知識&#xff01; 01 OSPF虛擬鏈路術語大全 網絡架構中&#xff0c;OSPF&#xff08;開放式最短路徑優先&#xff09;是一種重要的路由協議。通過其鏈路狀態路由機制&#xff0c;OSPF能夠有效維護和更新…

oracle常用的函數(一) 之 to_char、to_date

文章目錄 前言to_char基本語法格式模型格式模型介紹無FM示例使用FM輸出貨幣負數輸出尖括號 將日期格式化將數字格式化為帶有貨幣符號和千位分隔符的格式總結 to_date語法語法示例 戳這里&#xff0c;第二彈 → oracle常用的函數&#xff08;二&#xff09; 之 nvl、decode、l…

數據庫服務器宕機的處理方法與實戰策略

在當今數字化時代,數據庫作為企業數據存儲與管理的核心,承載著業務運行的關鍵信息。一旦數據庫服務器宕機,將導致業務中斷、數據丟失等嚴重后果,甚至可能給企業帶來巨大的經濟損失和聲譽損害。因此,掌握一套系統、科學的數據庫服務器宕機處理方法尤為重要。本文將從應急響…

如何hack邊緣的kubelet修改Cgroup數值

之前做了一個VPA項目的需求&#xff0c;就是需要不重啟的方式修改容器的Cgroup的值已達到垂直擴縮容的目的&#xff0c;項目中核心的思路如下 上游下發要VPA的結果的值寫入到容器的Annotation里面Kubelet 感知到這個 annoation 的變化我們本地運行一個 Agent&#xff0c;里面運…

熟悉 PyCharm

界面 我們常用的就這個幾個地方&#xff1a; 常用配置 調整字體大小 Ctrl 滾輪調整字體大小 插件推薦 Indent Rainbow 該插件的作用在于能夠對于不同層級縮進的空格標注不同的顏色&#xff1a; 快捷鍵 快捷鍵的 pdf 下載鏈接&#xff1a; Windows 版&#xff1a;https:…

pytorch--模型訓練的一般流程

文章目錄 前言0、數據集準備1、數據集2、dataset3、model4、訓練模型 前言 在pytorch中模型訓練一般分為以下幾個步驟&#xff1a; 0、數據集準備 1、數據集讀取&#xff08;dataset模塊&#xff09; 2、數據集轉換為tensor&#xff08;dataloader模塊&#xff09; 3、定義模型…

智能合同管理實戰:基于區塊鏈的電子簽約技術實現

在數字經濟時代,傳統紙質合同簽署方式已難以滿足企業高效、安全、合規的業務需求。智能合同管理(Smart Contract Management)結合區塊鏈技術,正在重塑電子簽約流程,實現合同全生命周期的自動化、可追溯和防篡改。本文將深入探討基于區塊鏈的電子簽約技術實現,涵蓋核心架構…

設計模式精講 Day 22:模板方法模式(Template Method Pattern)

【設計模式精講 Day 22】模板方法模式&#xff08;Template Method Pattern&#xff09; 文章標簽 設計模式, 模板方法模式, Java開發, 面向對象設計, 軟件架構, 設計模式實戰, Java應用開發 文章簡述 模板方法模式是一種行為型設計模式&#xff0c;它通過定義一個算法的骨架…

如何在pytorch中使用tqdm:優雅實現訓練進度監控

文章目錄 為什么需要進度條&#xff1f;tqdm 簡介基礎用法示例深度學習中的實戰應用1. 數據加載進度監控2. 訓練循環增強版3. 驗證階段集成 高級技巧與最佳實踐1. 自定義進度條樣式2. 嵌套進度條&#xff08;多任務&#xff09;3. 分布式訓練支持4. 與日志系統集成 性能優化建議…

Linux中的xxd命令詳解

xxd 是一個 十六進制轉儲&#xff08;hex dump&#xff09;工具&#xff0c;通常用于將二進制文件轉換為十六進制格式&#xff0c;或者反向轉換&#xff08;十六進制→二進制&#xff09;。它是 vim 的一部分&#xff0c;但在大多數 Linux 系統&#xff08;如 Ubuntu&#xff0…

磐維數據庫panweidb3.1.0單節點多實例安裝

0 說明 業務科室提單需要在某臺主機上部署多個單機磐維數據庫&#xff0c;用于業務測試。以下內容展示如何在單節點安裝多個磐維數據庫實例。 1 部署環境準備 1.1 IP 地址及端口 instipport實例1192.168.131.1717700實例2192.168.131.1727700 在131.17上分別安裝兩個實例&…

轉錄組分析流程(三):功能富集分析

我們的教程主要是以一個具體的例子作為線索,通過對公共數據庫數據bulk-RNA-seq的挖掘,利用生物信息學分析來探索目標基因集作為某種疾病數據預后基因的潛能及其潛在分子機制,同時在單細胞水平分析(對scRNA-seq進行挖掘)預后基因的表達,了解細胞之間的通訊網絡,以期為該疾病…

全面掌握 tkinter:Python GUI 編程的入門與實戰指南

在自動化、工具開發、數據可視化等領域&#xff0c;圖形用戶界面&#xff08;GUI&#xff09;往往是提升用戶體驗的重要方式。作為 Python 官方內置的 GUI 庫&#xff0c;tkinter 以其輕量、跨平臺、易于學習的特性成為初學者和輕量級應用開發者首選。 本文將以深入淺出的方式…

TDH社區開發版安裝教程

&#xff08;注&#xff1a;本文章來源于星環官網安裝手冊&#xff09; 后面放置了視頻和安裝手冊連接 1、硬件及環境要求 Docker17及以上版本&#xff0c;支持Centos&#xff0c;Ubuntu等系統&#xff08;注&#xff1a;這里我使用CentOS-7版本&#xff0c;最佳版本推薦為7.…

Linux基本命令篇 —— grep命令

grep是Linux/Unix系統中一個非常強大的文本搜索工具&#xff0c;它的名字來源于"Global Regular Expression Print"&#xff08;全局正則表達式打印&#xff09;。grep命令用于在文件中搜索包含特定模式的行&#xff0c;并將匹配的行打印出來。 目錄 一、基本語法 二…