From 547b5ab38acc33a727d7e719ce47d90ebe93e889 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Wed, 23 Mar 2022 09:24:25 +1100 Subject: [PATCH] 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. --- ArduPlane/quadplane.cpp | 7 +++++++ 1 file changed, 7 insertions(+) diff --git a/ArduPlane/quadplane.cpp b/ArduPlane/quadplane.cpp index 819fe2b6ba..30f2c399f4 100644 --- a/ArduPlane/quadplane.cpp +++ b/ArduPlane/quadplane.cpp @@ -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); } }