Plane: don't special case tilt rotors for motors shutdown

this allows for Q_M_SPOOL_TIME to work correctly for back transition
This commit is contained in:
Andrew Tridgell 2024-02-18 11:28:59 +11:00
parent 8a478abce9
commit 4d2c7f3d64
1 changed files with 3 additions and 5 deletions

View File

@ -1761,10 +1761,8 @@ void SLT_Transition::update()
}
case TRANSITION_DONE:
if (!quadplane.tiltrotor.motors_active()) {
quadplane.set_desired_spool_state(AP_Motors::DesiredSpoolState::SHUT_DOWN);
motors->output();
}
quadplane.set_desired_spool_state(AP_Motors::DesiredSpoolState::SHUT_DOWN);
motors->output();
set_last_fw_pitch();
in_forced_transition = false;
return;
@ -1851,7 +1849,7 @@ void QuadPlane::update(void)
plane.control_mode == &plane.mode_acro ||
plane.control_mode == &plane.mode_training) {
// in manual modes quad motors are always off
if (!tiltrotor.motors_active() && !tailsitter.enabled()) {
if (!tailsitter.enabled()) {
set_desired_spool_state(AP_Motors::DesiredSpoolState::SHUT_DOWN);
motors->output();
}