From b2fb2f39494817caac9c810485988592769b543e Mon Sep 17 00:00:00 2001 From: Tom Pittenger Date: Tue, 17 May 2016 18:21:21 -0700 Subject: [PATCH] Plane: optimize millis() calls by reusing result --- ArduPlane/altitude.cpp | 5 +++-- 1 file changed, 3 insertions(+), 2 deletions(-) diff --git a/ArduPlane/altitude.cpp b/ArduPlane/altitude.cpp index 93c8608f50..b9acf502fc 100644 --- a/ArduPlane/altitude.cpp +++ b/ArduPlane/altitude.cpp @@ -626,7 +626,8 @@ void Plane::rangefinder_height_update(void) // remember the last correction. Use a low pass filter unless // the old data is more than 5 seconds old - if (millis() - rangefinder_state.last_correction_time_ms > 5000) { + uint32_t now = millis(); + if (now - rangefinder_state.last_correction_time_ms > 5000) { rangefinder_state.correction = correction; rangefinder_state.initial_correction = correction; auto_state.initial_land_slope = auto_state.land_slope; @@ -640,7 +641,7 @@ void Plane::rangefinder_height_update(void) memset(&rangefinder_state, 0, sizeof(rangefinder_state)); } } - rangefinder_state.last_correction_time_ms = millis(); + rangefinder_state.last_correction_time_ms = now; } } #endif