Skip to content
Snippets Groups Projects
Commit f4e1424b authored by Randy Mackay's avatar Randy Mackay
Browse files

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
parent defeb76e
No related branches found
No related tags found
No related merge requests found
...@@ -147,7 +147,8 @@ static void read_radio() ...@@ -147,7 +147,8 @@ static void read_radio()
#endif #endif
}else{ }else{
// turn on throttle failsafe if no update from ppm encoder for 2 seconds // 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); Log_Write_Error(ERROR_SUBSYSTEM_RADIO, ERROR_CODE_RADIO_LATE_FRAME);
set_failsafe(true); set_failsafe(true);
} }
......
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment