AP_Scheduler: use pre-computed loop constants

this prevents changing the loop rate without a reboot. Too many
subsystems rely on a consistent loop rate to allow it to be changed
This commit is contained in:
Andrew Tridgell 2018-01-17 18:20:44 +11:00
parent f2242e07db
commit 8b0e9bcff4
2 changed files with 29 additions and 17 deletions

View File

@ -57,7 +57,6 @@ const AP_Param::GroupInfo AP_Scheduler::var_info[] = {
// constructor // constructor
AP_Scheduler::AP_Scheduler(void) AP_Scheduler::AP_Scheduler(void)
{ {
_loop_rate_hz.set(SCHEDULER_DEFAULT_LOOP_RATE);
AP_Param::setup_object_defaults(this, var_info); AP_Param::setup_object_defaults(this, var_info);
// only allow 50 to 2000 Hz // only allow 50 to 2000 Hz
@ -189,7 +188,7 @@ uint16_t AP_Scheduler::time_available_usec(void)
/* /*
calculate load average as a number from 0 to 1 calculate load average as a number from 0 to 1
*/ */
float AP_Scheduler::load_average() const float AP_Scheduler::load_average()
{ {
if (_spare_ticks == 0) { if (_spare_ticks == 0) {
return 0.0f; return 0.0f;

View File

@ -87,19 +87,28 @@ public:
// return load average, as a number between 0 and 1. 1 means // return load average, as a number between 0 and 1. 1 means
// 100% load. Calculated from how much spare time we have at the // 100% load. Calculated from how much spare time we have at the
// end of a run() // end of a run()
float load_average() const; float load_average();
// get the configured main loop rate // get the active main loop rate
uint16_t get_loop_rate_hz(void) const { uint16_t get_loop_rate_hz(void) {
return _loop_rate_hz; if (_active_loop_rate_hz == 0) {
_active_loop_rate_hz = _loop_rate_hz;
} }
// get the time-allowed-per-loop: return _active_loop_rate_hz;
uint32_t get_loop_period_us() const {
return 1000000UL / _loop_rate_hz;
} }
// get the time-allowed-per-loop: // get the time-allowed-per-loop in microseconds
float get_loop_period_s() const { uint32_t get_loop_period_us() {
return 1.0 / _loop_rate_hz; if (_loop_period_us == 0) {
_loop_period_us = 1000000UL / _loop_rate_hz;
}
return _loop_period_us;
}
// get the time-allowed-per-loop in seconds
float get_loop_period_s() {
if (is_zero(_loop_period_s)) {
_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[];
@ -112,13 +121,17 @@ private:
AP_Int8 _debug; AP_Int8 _debug;
// overall scheduling rate in Hz // overall scheduling rate in Hz
// The value of this variable can be changed with the
// non-initialization. (Ex. Tuning by GDB). However, if you do,
// make sure you update _loop_period_us at the same time. And all
// 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; AP_Int16 _loop_rate_hz;
// loop rate in Hz as set at startup
AP_Int16 _active_loop_rate_hz;
// calculated loop period in usec
uint16_t _loop_period_us;
// calculated loop period in seconds
float _loop_period_s;
// progmem list of tasks to run // progmem list of tasks to run
const struct Task *_tasks; const struct Task *_tasks;