Plane: when shutting down motors force outputs to minimum

this fixes issue #20354 where a long spool time can lead to motors
running without control for an extended period of time.
This commit is contained in:
Andrew Tridgell 2022-03-23 09:24:25 +11:00 committed by Randy Mackay
parent 68b4c38180
commit 547b5ab38a

View File

@ -3851,6 +3851,13 @@ float QuadPlane::get_land_airspeed(void)
void QuadPlane::set_desired_spool_state(AP_Motors::DesiredSpoolState state)
{
if (motors->get_desired_spool_state() != state) {
if (state == AP_Motors::DesiredSpoolState::SHUT_DOWN) {
// also request zero throttle, so we avoid the slow ramp down
motors->set_roll(0);
motors->set_pitch(0);
motors->set_yaw(0);
motors->set_throttle(0);
}
motors->set_desired_spool_state(state);
}
}