Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

use latest mavlink definitions for MAV_ODID_ARM_STATUS #95

Merged
merged 2 commits into from
Mar 24, 2023
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
2 changes: 1 addition & 1 deletion RemoteIDModule/DroneCAN.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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;
Expand Down
2 changes: 1 addition & 1 deletion RemoteIDModule/mavlink.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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,
Expand Down
6 changes: 3 additions & 3 deletions RemoteIDModule/transport.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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;
}

Expand All @@ -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;
Expand Down