起因是查看飛控日志時發現地面站上傳的平行航線,在日志看到航線卻并不是平行的。
?然后對比了一下地面站上傳的航點信息跟飛控讀取到的航點信息
?發現經緯度只有前幾位能夠對應上,后幾位都對應不上,兩個點之間相差了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數據
但官網沒有該類型。