diff --git a/libraries/GCS_MAVLink/GCS.h b/libraries/GCS_MAVLink/GCS.h index b194b604ea..f211d28dfa 100644 --- a/libraries/GCS_MAVLink/GCS.h +++ b/libraries/GCS_MAVLink/GCS.h @@ -511,8 +511,6 @@ protected: static constexpr const float magic_force_arm_value = 2989.0f; static constexpr const float magic_force_disarm_value = 21196.0f; - virtual bool allow_disarm() const { return true; } - void manual_override(RC_Channel *c, int16_t value_in, uint16_t offset, float scaler, const uint32_t tnow, bool reversed = false); /* diff --git a/libraries/GCS_MAVLink/GCS_Common.cpp b/libraries/GCS_MAVLink/GCS_Common.cpp index 6fc73063ff..4adb42ef1e 100644 --- a/libraries/GCS_MAVLink/GCS_Common.cpp +++ b/libraries/GCS_MAVLink/GCS_Common.cpp @@ -3864,13 +3864,9 @@ MAV_RESULT GCS_MAVLINK::handle_command_component_arm_disarm(const mavlink_comman if (!AP::arming().is_armed()) { return MAV_RESULT_ACCEPTED; } - // allow vehicle to disallow disarm. Copter does this if - // the vehicle isn't considered landed. - if (!allow_disarm() && - !is_equal(packet.param2, magic_force_disarm_value)) { - return MAV_RESULT_FAILED; - } - if (AP::arming().disarm(AP_Arming::Method::MAVLINK)) { + const bool forced = is_equal(packet.param2, magic_force_disarm_value); + // note disarm()'s second parameter is "do_disarm_checks" + if (AP::arming().disarm(AP_Arming::Method::MAVLINK, !forced)) { return MAV_RESULT_ACCEPTED; } return MAV_RESULT_FAILED;