mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
Plane: reset TECS at end of auto VTOL takeoff
This commit is contained in:
parent
04b307aafc
commit
7ee9b437bb
@ -2630,6 +2630,13 @@ bool QuadPlane::verify_vtol_takeoff(const AP_Mission::Mission_Command &cmd)
|
||||
|
||||
plane.complete_auto_takeoff();
|
||||
|
||||
if (plane.control_mode == &plane.mode_auto) {
|
||||
// we reset TECS so that the target height filter is not
|
||||
// constrained by the climb and sink rates from the initial
|
||||
// takeoff height.
|
||||
plane.SpdHgt_Controller->reset();
|
||||
}
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user