From f2b952eda011d994fd5ecc339c113467477e9079 Mon Sep 17 00:00:00 2001 From: Pierre Kancir Date: Tue, 12 Oct 2021 11:58:44 +0200 Subject: [PATCH] Copter: fix takeoff end report on EXTEND_STATE regression from https://github.com/ArduPilot/ardupilot/pull/18700. thanks to @arduouspilot on discuss to notice this, see https://discuss.ardupilot.org/t/extended-sys-state-never-changes-once-guided-takeoff-is-started/76996/3 --- ArduCopter/mode_guided.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ArduCopter/mode_guided.cpp b/ArduCopter/mode_guided.cpp index 801c347a0f..a1950e3141 100644 --- a/ArduCopter/mode_guided.cpp +++ b/ArduCopter/mode_guided.cpp @@ -270,7 +270,7 @@ void ModeGuided::posvelaccel_control_start() bool ModeGuided::is_taking_off() const { - return guided_mode == SubMode::TakeOff; + return guided_mode == SubMode::TakeOff && !takeoff_complete; } // initialise guided mode's angle controller