From 1c9a44c33e8edcc906e32216d1cab1b9afbb5bc9 Mon Sep 17 00:00:00 2001 From: David Buzz Date: Tue, 28 May 2024 15:31:17 +1000 Subject: [PATCH] AP_HAL_ESP32:LOWERING the MAIN_PRIO gets a 400hz loop rate on s3 "empty" board loop_rate: actual: 400.000000Hz, expected: 400Hz loop_rate: actual: 400.000000Hz, expected: 400Hz loop_rate: actual: 400.000000Hz, expected: 400Hz [ setup esp32 build env ] ./waf configure --board=esp32s3empty --debug ./waf copter --debug --disable-scripting --upload after upload: cd build/esp32s3empty/esp-idf_build && ninja monitor && cd - [watch console output for 2 minutes] ctrl-right-square-bracket to stop watching console. --- 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 237f9532ea..ec11c0af1a 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 = 22; // cpu0: we want schuler running at full tilt. + 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 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;