From a45a5f19c79e98768e762eb1178742a3134fc066 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Wed, 30 Nov 2022 20:13:07 +0900 Subject: [PATCH] AP_Scheduler: load_average returns 1 if main loop running slowly --- libraries/AP_Scheduler/AP_Scheduler.cpp | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/libraries/AP_Scheduler/AP_Scheduler.cpp b/libraries/AP_Scheduler/AP_Scheduler.cpp index ddeecf84c4..c33464e17d 100644 --- a/libraries/AP_Scheduler/AP_Scheduler.cpp +++ b/libraries/AP_Scheduler/AP_Scheduler.cpp @@ -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; }