Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

ESP32: more accurately calculate loop rate #27967

Merged
merged 2 commits into from
Sep 1, 2024
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
3 changes: 3 additions & 0 deletions libraries/AP_HAL/board/esp32.h
Original file line number Diff line number Diff line change
Expand Up @@ -116,3 +116,6 @@
// other big things..
#define HAL_QUADPLANE_ENABLED 0
#define HAL_GYROFFT_ENABLED 0

// remove once ESP32 isn't so chronically slow
#define AP_SCHEDULER_OVERTIME_MARGIN_US 50000UL
15 changes: 14 additions & 1 deletion libraries/AP_Scheduler/PerfInfo.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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()
{
Expand Down Expand Up @@ -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
}
}

Expand Down
Loading