mirror of https://github.com/ArduPilot/ardupilot
Plane: fixed throttle failsafe with THR_PASS_STAB=1
this prevents using pass-thru throttle when in throttle failsafe
This commit is contained in:
parent
9a100afede
commit
e0a9a8196c
|
@ -1013,7 +1013,8 @@ void Plane::set_servos(void)
|
|||
control_mode == TRAINING ||
|
||||
control_mode == ACRO ||
|
||||
control_mode == FLY_BY_WIRE_A ||
|
||||
control_mode == AUTOTUNE)) {
|
||||
control_mode == AUTOTUNE) &&
|
||||
!failsafe.ch3_counter) {
|
||||
// manual pass through of throttle while in FBWA or
|
||||
// STABILIZE mode with THR_PASS_STAB set
|
||||
channel_throttle->set_radio_out(channel_throttle->get_radio_in());
|
||||
|
|
Loading…
Reference in New Issue