mirror of https://github.com/ArduPilot/ardupilot
AP_HAL_ESP32: scheduler timing information was lying to us
This reverts commit 010cfa2f4c
.
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
This commit is contained in:
parent
e99b0fd7b9
commit
04292a280c
|
@ -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;
|
||||
|
|
Loading…
Reference in New Issue