Skip to content

Commit

Permalink
Plane: don't special case tilt rotors for motors shutdown
Browse files Browse the repository at this point in the history
this allows for Q_M_SPOOL_TIME to work correctly for back transition
  • Loading branch information
tridge committed Feb 18, 2024
1 parent 1d08662 commit 58beec8
Showing 1 changed file with 3 additions and 5 deletions.
8 changes: 3 additions & 5 deletions ArduPlane/quadplane.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1752,10 +1752,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;
Expand Down Expand Up @@ -1842,7 +1840,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();
}
Expand Down

0 comments on commit 58beec8

Please sign in to comment.