From f4e1424bd1d44455bcf27014543e849c747a9ae0 Mon Sep 17 00:00:00 2001 From: Randy Mackay <rmackay9@yahoo.com> Date: Wed, 30 Jan 2013 00:17:54 +0900 Subject: [PATCH] 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 --- ArduCopter/radio.pde | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/ArduCopter/radio.pde b/ArduCopter/radio.pde index b39f3e642..e057ff99b 100644 --- a/ArduCopter/radio.pde +++ b/ArduCopter/radio.pde @@ -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); } -- GitLab