GCS_MAVLink: canonicalise on success on commanded-to-arm-when-armed

This means the mavlink return value indicates the current arm status of
the vehicle rather than success/failure of transitioning to the armed or
disarmed state (where trying to arm when armed is considered a failure).

MAVLink is a lossy communication mechanism.  It would not be
unreasonable for a GCS to issue a disarm command multiple times to
increase the chances of the command getting through.
This commit is contained in:
Peter Barker 2019-05-06 11:11:56 +10:00 committed by Randy Mackay
parent 8566a17a1d
commit e340873d88
1 changed files with 5 additions and 1 deletions

View File

@ -3966,12 +3966,16 @@ MAV_RESULT GCS_MAVLINK::handle_command_long_packet(const mavlink_command_long_t
if (is_equal(packet.param1,1.0f)) {
// run pre_arm_checks and arm_checks and display failures
const bool do_arming_checks = !is_equal(packet.param2,magic_force_arm_value);
if (AP::arming().arm(AP_Arming::Method::MAVLINK, do_arming_checks)) {
if (AP::arming().is_armed() ||
AP::arming().arm(AP_Arming::Method::MAVLINK, do_arming_checks)) {
return MAV_RESULT_ACCEPTED;
}
return MAV_RESULT_FAILED;
}
if (is_zero(packet.param1)) {
if (!AP::arming().is_armed()) {
return MAV_RESULT_ACCEPTED;
}
if (AP::arming().disarm()) {
return MAV_RESULT_ACCEPTED;
}