mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-26 01:33:56 -04:00
Plane: Manage quadplane throttle during RC failsafe
This commit is contained in:
parent
9b73c5f1d9
commit
5134af2298
@ -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);
|
||||
|
||||
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)
|
||||
|
@ -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
|
||||
|
Loading…
Reference in New Issue
Block a user