diff --git a/RemoteIDModule/DroneCAN.cpp b/RemoteIDModule/DroneCAN.cpp index 54690f6..2952f5f 100644 --- a/RemoteIDModule/DroneCAN.cpp +++ b/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; diff --git a/RemoteIDModule/mavlink.cpp b/RemoteIDModule/mavlink.cpp index fd35553..cf6403b 100644 --- a/RemoteIDModule/mavlink.cpp +++ b/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, diff --git a/RemoteIDModule/transport.cpp b/RemoteIDModule/transport.cpp index 3bd1e9a..6b1b3b9 100644 --- a/RemoteIDModule/transport.cpp +++ b/RemoteIDModule/transport.cpp @@ -56,7 +56,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;