浏览代码

use latest mavlink definitions for MAV_ODID_ARM_STATUS

Roel Schiphorst 3 年之前
父节点
当前提交
661a202b6d
共有 3 个文件被更改,包括 5 次插入5 次删除
  1. 1 1
      RemoteIDModule/DroneCAN.cpp
  2. 1 1
      RemoteIDModule/mavlink.cpp
  3. 3 3
      RemoteIDModule/transport.cpp

+ 1 - 1
RemoteIDModule/DroneCAN.cpp

@@ -92,7 +92,7 @@ void DroneCAN::arm_status_send(void)
     uint8_t buffer[DRONECAN_REMOTEID_ARMSTATUS_MAX_SIZE];
     dronecan_remoteid_ArmStatus arm_status {};
 
-    const uint8_t status = parse_fail==nullptr?MAV_ODID_GOOD_TO_ARM:MAV_ODID_PRE_ARM_FAIL_GENERIC;
+    const uint8_t status = parse_fail==nullptr?MAV_ODID_ARM_STATUS_GOOD_TO_ARM:MAV_ODID_ARM_STATUS_PRE_ARM_FAIL_GENERIC;
     const char *reason = parse_fail==nullptr?"":parse_fail;
 
     arm_status.status = status;

+ 1 - 1
RemoteIDModule/mavlink.cpp

@@ -273,7 +273,7 @@ void MAVLinkSerial::process_packet(mavlink_status_t &status, mavlink_message_t &
 
 void MAVLinkSerial::arm_status_send(void)
 {
-    const uint8_t status = parse_fail==nullptr?MAV_ODID_GOOD_TO_ARM:MAV_ODID_PRE_ARM_FAIL_GENERIC;
+    const uint8_t status = parse_fail==nullptr?MAV_ODID_ARM_STATUS_GOOD_TO_ARM:MAV_ODID_ARM_STATUS_PRE_ARM_FAIL_GENERIC;
     const char *reason = parse_fail==nullptr?"":parse_fail;
     mavlink_msg_open_drone_id_arm_status_send(
         chan,

+ 3 - 3
RemoteIDModule/transport.cpp

@@ -37,11 +37,11 @@ uint8_t Transport::arm_status_check(const char *&reason)
     const uint32_t max_age_other_ms = 22000;
     const uint32_t now_ms = millis();
 
-    uint8_t status = MAV_ODID_PRE_ARM_FAIL_GENERIC;
+    uint8_t status = MAV_ODID_ARM_STATUS_PRE_ARM_FAIL_GENERIC;
 
     //return status OK if we have enabled the force arm option
     if (g.options & OPTIONS_FORCE_ARM_OK) {
-        status = MAV_ODID_GOOD_TO_ARM;
+        status = MAV_ODID_ARM_STATUS_GOOD_TO_ARM;
         return status;
     }
 
@@ -62,7 +62,7 @@ uint8_t Transport::arm_status_check(const char *&reason)
     } else if (system.operator_latitude == 0 && system.operator_longitude == 0) {
         reason = "Bad operator location";
     } else if (reason == nullptr) {
-        status = MAV_ODID_GOOD_TO_ARM;
+        status = MAV_ODID_ARM_STATUS_GOOD_TO_ARM;
     }
 
     return status;