Plane: Quadplane: never run Z controller if motors are not throttle unlimited

This commit is contained in:
Iampete1 2021-11-17 18:44:08 +00:00 committed by Andrew Tridgell
parent c215fa0745
commit fb1f6b57ad
1 changed files with 3 additions and 0 deletions

View File

@ -884,6 +884,9 @@ void QuadPlane::hold_stabilize(float throttle_in)
// run the multicopter Z controller
void QuadPlane::run_z_controller(void)
{
if (motors->get_spool_state() != AP_Motors::SpoolState::THROTTLE_UNLIMITED ) {
return;
}
const uint32_t now = AP_HAL::millis();
if (tailsitter.in_vtol_transition(now)) {
// never run Z controller in tailsitter transtion