diff --git a/ArduCopter/radio.pde b/ArduCopter/radio.pde
index b39f3e64222872f882c39c66867f828a97e5a5c4..e057ff99bafd6e0f7efc64d8abf440ec1293198a 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);
         }