Copter: bug fix for throttle failsafe

Missing bracket could cause throttle failsafe to be triggered even when
disabled or motors disarmed
This commit is contained in:
Randy Mackay 2014-07-21 19:13:38 +09:00
parent c45f1961f6
commit af28270669

View File

@ -124,8 +124,8 @@ static void read_radio()
}else{
uint32_t elapsed = millis() - last_update;
// turn on throttle failsafe if no update from the RC Radio for 500ms or 2000ms if we are using RC_OVERRIDE
if ((!failsafe.rc_override_active && (elapsed >= FS_RADIO_TIMEOUT_MS)) || (failsafe.rc_override_active && (elapsed >= FS_RADIO_RC_OVERRIDE_TIMEOUT_MS))
&& g.failsafe_throttle && motors.armed() && !failsafe.radio) {
if (((!failsafe.rc_override_active && (elapsed >= FS_RADIO_TIMEOUT_MS)) || (failsafe.rc_override_active && (elapsed >= FS_RADIO_RC_OVERRIDE_TIMEOUT_MS))) &&
(g.failsafe_throttle && motors.armed() && !failsafe.radio)) {
Log_Write_Error(ERROR_SUBSYSTEM_RADIO, ERROR_CODE_RADIO_LATE_FRAME);
set_failsafe_radio(true);
}