mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 02:18:29 -04:00
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:
parent
68b4c38180
commit
547b5ab38a
@ -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);
|
||||
}
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user