mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-23 09:08:30 -04:00
HAL_ChibiOS: raised default SPI priority
this was causing transfer errors on the primary IMU of a PH2.1 when fast sampling was enabled
This commit is contained in:
parent
c17338473d
commit
a2eec97325
@ -34,7 +34,9 @@
|
||||
#define APM_STARTUP_PRIORITY 10
|
||||
|
||||
#ifndef APM_SPI_PRIORITY
|
||||
#define APM_SPI_PRIORITY 179
|
||||
// SPI priority needs to be above main priority to ensure fast sampling of IMUs can keep up
|
||||
// with the data rate
|
||||
#define APM_SPI_PRIORITY 181
|
||||
#endif
|
||||
|
||||
#ifndef APM_UAVCAN_PRIORITY
|
||||
|
Loading…
Reference in New Issue
Block a user