mirror of https://github.com/ArduPilot/ardupilot
AP_Scheduler: remove memoisation in loop_period_s()
This commit is contained in:
parent
a6ac37d0ba
commit
f2242e07db
|
@ -98,11 +98,8 @@ public:
|
||||||
return 1000000UL / _loop_rate_hz;
|
return 1000000UL / _loop_rate_hz;
|
||||||
}
|
}
|
||||||
// get the time-allowed-per-loop:
|
// get the time-allowed-per-loop:
|
||||||
float get_loop_period_s() {
|
float get_loop_period_s() const {
|
||||||
if (is_zero(_loop_period_s)) {
|
return 1.0 / _loop_rate_hz;
|
||||||
_loop_period_s = 1.0 / _loop_rate_hz;
|
|
||||||
}
|
|
||||||
return _loop_period_s;
|
|
||||||
}
|
}
|
||||||
|
|
||||||
static const struct AP_Param::GroupInfo var_info[];
|
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
|
// the other places which take a copy of this at startup and don't
|
||||||
// get refreshed. So, really, don't.
|
// get refreshed. So, really, don't.
|
||||||
AP_Int16 _loop_rate_hz;
|
AP_Int16 _loop_rate_hz;
|
||||||
float _loop_period_s;
|
|
||||||
|
|
||||||
// progmem list of tasks to run
|
// progmem list of tasks to run
|
||||||
const struct Task *_tasks;
|
const struct Task *_tasks;
|
||||||
|
|
Loading…
Reference in New Issue