From 04292a280c81d142668f8d08e60ddd3951285003 Mon Sep 17 00:00:00 2001 From: David Buzz Date: Sun, 1 Sep 2024 07:59:34 +1000 Subject: [PATCH] AP_HAL_ESP32: scheduler timing information was lying to us This reverts commit 010cfa2f4c173c72e8df40c17713b80277c55052. AP_HAL_ESP32: scheduler timing information was lying to us, this puts it back so both 'esp32buzz' and 'esp32s3empty' loop rates are "better than before. Still terrible, but an improvement revert of part of pr #27181 --- libraries/AP_HAL_ESP32/Scheduler.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_HAL_ESP32/Scheduler.h b/libraries/AP_HAL_ESP32/Scheduler.h index ec11c0af1a..6709a9af4d 100644 --- a/libraries/AP_HAL_ESP32/Scheduler.h +++ b/libraries/AP_HAL_ESP32/Scheduler.h @@ -70,7 +70,7 @@ public: static const int STORAGE_PRIO = 6; */ static const int SPI_PRIORITY = 24; // if your primary imu is spi, this should be above the i2c value, spi is better. - static const int MAIN_PRIO = 15; // at prio 22, we get 262hz, at prio 24 , we get ~90hz, at prio 15, we get 400hz, does this want to be even lower? + static const int MAIN_PRIO = 24; // cpu0: we want scheduler running at full tilt. static const int I2C_PRIORITY = 5; // if your primary imu is i2c, this should be above the spi value, i2c is not preferred. static const int TIMER_PRIO = 22; // a low priority mere might cause wifi thruput to suffer static const int RCIN_PRIO = 15;