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.
This commit is contained in:
David Buzz 2024-05-28 15:31:17 +10:00
parent 2c891c5007
commit 010cfa2f4c
1 changed files with 1 additions and 1 deletions

View File

@ -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;