mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-23 00:04:02 -04:00
Copter: minor formatting update
This commit is contained in:
parent
07d43534c1
commit
df28db1361
@ -124,10 +124,10 @@ static void read_radio()
|
|||||||
}else{
|
}else{
|
||||||
uint32_t elapsed = millis() - last_update;
|
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
|
// 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))
|
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) {
|
&& g.failsafe_throttle && motors.armed() && !failsafe.radio) {
|
||||||
Log_Write_Error(ERROR_SUBSYSTEM_RADIO, ERROR_CODE_RADIO_LATE_FRAME);
|
Log_Write_Error(ERROR_SUBSYSTEM_RADIO, ERROR_CODE_RADIO_LATE_FRAME);
|
||||||
set_failsafe_radio(true);
|
set_failsafe_radio(true);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
Loading…
Reference in New Issue
Block a user