mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-23 17:18:28 -04:00
ArduCopter: bug fix to ppm encoder failsafe
A new radio frame could arrive just as the frame time vs current time check was being executed causing a false positive
This commit is contained in:
parent
defeb76e47
commit
f4e1424bd1
@ -147,7 +147,8 @@ static void read_radio()
|
||||
#endif
|
||||
}else{
|
||||
// turn on throttle failsafe if no update from ppm encoder for 2 seconds
|
||||
if ((millis() - APM_RC.get_last_update() >= RADIO_FS_TIMEOUT_MS) && g.failsafe_throttle && motors.armed() && !ap.failsafe) {
|
||||
uint32_t last_rc_update = APM_RC.get_last_update();
|
||||
if ((millis() - last_rc_update >= RADIO_FS_TIMEOUT_MS) && g.failsafe_throttle && motors.armed() && !ap.failsafe) {
|
||||
Log_Write_Error(ERROR_SUBSYSTEM_RADIO, ERROR_CODE_RADIO_LATE_FRAME);
|
||||
set_failsafe(true);
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user