mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-09 01:18:29 -04:00
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:
parent
f5d5387358
commit
73ff525a30
@ -270,7 +270,7 @@ void ModeGuided::posvelaccel_control_start()
|
|||||||
|
|
||||||
bool ModeGuided::is_taking_off() const
|
bool ModeGuided::is_taking_off() const
|
||||||
{
|
{
|
||||||
return guided_mode == SubMode::TakeOff;
|
return guided_mode == SubMode::TakeOff && !takeoff_complete;
|
||||||
}
|
}
|
||||||
|
|
||||||
// initialise guided mode's angle controller
|
// initialise guided mode's angle controller
|
||||||
|
Loading…
Reference in New Issue
Block a user