From f2242e07dbbb7d2ed2acec0f10679d5ba38ede50 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Thu, 31 Aug 2017 10:45:20 +1000 Subject: [PATCH] AP_Scheduler: remove memoisation in loop_period_s() --- libraries/AP_Scheduler/AP_Scheduler.h | 8 ++------ 1 file changed, 2 insertions(+), 6 deletions(-) diff --git a/libraries/AP_Scheduler/AP_Scheduler.h b/libraries/AP_Scheduler/AP_Scheduler.h index 882d2926ac..2531235450 100644 --- a/libraries/AP_Scheduler/AP_Scheduler.h +++ b/libraries/AP_Scheduler/AP_Scheduler.h @@ -98,11 +98,8 @@ public: return 1000000UL / _loop_rate_hz; } // get the time-allowed-per-loop: - float get_loop_period_s() { - if (is_zero(_loop_period_s)) { - _loop_period_s = 1.0 / _loop_rate_hz; - } - return _loop_period_s; + float get_loop_period_s() const { + return 1.0 / _loop_rate_hz; } static const struct AP_Param::GroupInfo var_info[]; @@ -121,7 +118,6 @@ private: // the other places which take a copy of this at startup and don't // get refreshed. So, really, don't. AP_Int16 _loop_rate_hz; - float _loop_period_s; // progmem list of tasks to run const struct Task *_tasks;