Plane: Manage quadplane throttle during RC failsafe

This commit is contained in:
Michael du Breuil 2019-01-29 17:14:43 -07:00 committed by WickedShell
parent 9b73c5f1d9
commit 5134af2298
2 changed files with 21 additions and 1 deletions

View File

@ -259,7 +259,24 @@ void Plane::control_failsafe()
channel_roll->set_control_in(0);
channel_pitch->set_control_in(0);
channel_rudder->set_control_in(0);
channel_throttle->set_control_in(0);
switch (control_mode) {
case QSTABILIZE:
case QHOVER:
case QLOITER:
case QLAND: // throttle is ignored, but reset anyways
case QRTL: // throttle is ignored, but reset anyways
case QAUTOTUNE:
if (quadplane.available() && quadplane.motors->get_desired_spool_state() > AP_Motors::DESIRED_GROUND_IDLE) {
// set half throttle to avoid descending at maximum rate, still has a slight descent due to throttle deadzone
channel_throttle->set_control_in(channel_throttle->get_range() / 2);
break;
}
FALLTHROUGH;
default:
channel_throttle->set_control_in(0);
break;
}
}
if(g.throttle_fs_enabled == 0)

View File

@ -496,6 +496,9 @@ void Plane::set_mode(enum FlightMode mode, mode_reason_t reason)
// reset steering integrator on mode change
steerController.reset_I();
// update RC failsafe, as mode change may have necessitated changing the failsafe throttle
control_failsafe();
}
// exit_mode - perform any cleanup required when leaving a flight mode