diff --git a/ArduCopter/radio.pde b/ArduCopter/radio.pde index e5ee61600e..d3914d34ff 100644 --- a/ArduCopter/radio.pde +++ b/ArduCopter/radio.pde @@ -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); }