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
This commit is contained in:
Pierre Kancir 2021-10-12 11:58:44 +02:00 committed by Randy Mackay
parent 5d12b14672
commit f2b952eda0
1 changed files with 1 additions and 1 deletions

View File

@ -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