mirror of https://github.com/ArduPilot/ardupilot
AP_Scheduler: load_average returns 1 if main loop running slowly
This commit is contained in:
parent
fb041aa098
commit
7e70b50259
|
@ -308,6 +308,10 @@ uint16_t AP_Scheduler::time_available_usec(void) const
|
|||
*/
|
||||
float AP_Scheduler::load_average()
|
||||
{
|
||||
// return 1 if filtered main loop rate is 5% below the configured rate
|
||||
if (get_filtered_loop_rate_hz() < get_loop_rate_hz() * 0.95) {
|
||||
return 1.0;
|
||||
}
|
||||
if (_spare_ticks == 0) {
|
||||
return 0.0f;
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue