mirror of https://github.com/ArduPilot/ardupilot
AP_Scheduler: make overtime margin definable
Also warn about overtime on ESP32 which is most likely to hit it.
This commit is contained in:
parent
50dba896ca
commit
6c2daabd21
|
@ -17,6 +17,11 @@ extern const AP_HAL::HAL& hal;
|
|||
// we measure the main loop time
|
||||
//
|
||||
|
||||
// loops over time by this amount or more won't be counted in filtered loop time (and thus loop rate)
|
||||
#ifndef AP_SCHEDULER_OVERTIME_MARGIN_US
|
||||
#define AP_SCHEDULER_OVERTIME_MARGIN_US 10000UL
|
||||
#endif
|
||||
|
||||
// reset - reset all records of loop time to zero
|
||||
void AP::PerfInfo::reset()
|
||||
{
|
||||
|
@ -140,8 +145,16 @@ void AP::PerfInfo::check_loop_time(uint32_t time_in_micros)
|
|||
const uint32_t now = AP_HAL::micros();
|
||||
const uint32_t loop_time_us = now - last_check_us;
|
||||
last_check_us = now;
|
||||
if (loop_time_us < overtime_threshold_micros + 10000UL) {
|
||||
if (loop_time_us < overtime_threshold_micros + AP_SCHEDULER_OVERTIME_MARGIN_US) {
|
||||
filtered_loop_time = 0.99f * filtered_loop_time + 0.01f * loop_time_us * 1.0e-6f;
|
||||
} else {
|
||||
// esp32 is most likely to regularly trigger long loops, might be
|
||||
// helpful for bringup of other boards too
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_ESP32
|
||||
#ifdef SCHEDDEBUG
|
||||
DEV_PRINTF("way overtime: %dus\n", loop_time_us);
|
||||
#endif
|
||||
#endif
|
||||
}
|
||||
}
|
||||
|
||||
|
|
Loading…
Reference in New Issue