AP_Scheduler: remove loop-period argument from load_average
This now comes from a parameter rather than being hard-set in the vehicle code Also adds a method returning the max loop period based on the loop rate
This commit is contained in:
parent
efe70c8d3a
commit
b445313bf1
@ -189,11 +189,12 @@ uint16_t AP_Scheduler::time_available_usec(void)
|
||||
/*
|
||||
calculate load average as a number from 0 to 1
|
||||
*/
|
||||
float AP_Scheduler::load_average(uint32_t tick_time_usec) const
|
||||
float AP_Scheduler::load_average() const
|
||||
{
|
||||
if (_spare_ticks == 0) {
|
||||
return 0.0f;
|
||||
}
|
||||
uint32_t used_time = tick_time_usec - (_spare_micros/_spare_ticks);
|
||||
return used_time / (float)tick_time_usec;
|
||||
const uint32_t loop_us = get_loop_period_us();
|
||||
const uint32_t used_time = loop_us - (_spare_micros/_spare_ticks);
|
||||
return used_time / (float)loop_us;
|
||||
}
|
||||
|
@ -83,13 +83,17 @@ public:
|
||||
// return load average, as a number between 0 and 1. 1 means
|
||||
// 100% load. Calculated from how much spare time we have at the
|
||||
// end of a run()
|
||||
float load_average(uint32_t tick_time_usec) const;
|
||||
float load_average() const;
|
||||
|
||||
// get the configured main loop rate
|
||||
uint16_t get_loop_rate_hz(void) const {
|
||||
return _loop_rate_hz;
|
||||
}
|
||||
|
||||
// get the time-allowed-per-loop:
|
||||
uint32_t get_loop_period_us() const {
|
||||
return 1000000UL / _loop_rate_hz;
|
||||
}
|
||||
|
||||
static const struct AP_Param::GroupInfo var_info[];
|
||||
|
||||
// current running task, or -1 if none. Used to debug stuck tasks
|
||||
|
Loading…
Reference in New Issue
Block a user