From ec5d5b447176e5d96f62a9fb2bb1a15a4048e1fc Mon Sep 17 00:00:00 2001 From: Iampete1 Date: Tue, 7 Sep 2021 01:55:47 +0100 Subject: [PATCH] Copter: check for takeoff before continuing after land --- ArduCopter/mode_auto.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ArduCopter/mode_auto.cpp b/ArduCopter/mode_auto.cpp index 2d310388cc..bc5a95c760 100644 --- a/ArduCopter/mode_auto.cpp +++ b/ArduCopter/mode_auto.cpp @@ -1658,7 +1658,7 @@ 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()) { + if (retval && !mission.continue_after_land_check_for_takeoff() && copter.motors->armed()) { /* we want to stop mission processing on land completion. Disarm now, then return false. This