From e673bd8909549420ba8c94be633b7183aae48e9a Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Wed, 4 Mar 2020 14:29:14 +1100 Subject: [PATCH] Copter: implement disarm on land based on MIS_OPTIONS only continue with mission if MIS_OPTIONS bit is set --- ArduCopter/mode_auto.cpp | 10 ++++++++++ 1 file changed, 10 insertions(+) diff --git a/ArduCopter/mode_auto.cpp b/ArduCopter/mode_auto.cpp index 36e387cee2..ad3d0aa2fc 100644 --- a/ArduCopter/mode_auto.cpp +++ b/ArduCopter/mode_auto.cpp @@ -1521,6 +1521,16 @@ bool ModeAuto::verify_land() case State::Descending: // rely on THROTTLE_LAND mode to correctly update landing status retval = copter.ap.land_complete && (motors->get_spool_state() == AP_Motors::SpoolState::GROUND_IDLE); + if (retval && !mission.continue_after_land() && copter.motors->armed()) { + /* + we want to stop mission processing on land + completion. Disarm now, then return false. This + leaves mission state machine in the current NAV_LAND + mission item. After disarming the mission will reset + */ + copter.arming.disarm(AP_Arming::Method::LANDED); + retval = false; + } break; default: