mirror of https://github.com/ArduPilot/ardupilot
HAL_ChibiOS: drop default SPI priority to 179
This commit is contained in:
parent
ab748034a2
commit
8286486890
|
@ -33,7 +33,7 @@
|
|||
#define APM_STARTUP_PRIORITY 10
|
||||
|
||||
#ifndef APM_SPI_PRIORITY
|
||||
#define APM_SPI_PRIORITY 181
|
||||
#define APM_SPI_PRIORITY 179
|
||||
#endif
|
||||
|
||||
#ifndef APM_CAN_PRIORITY
|
||||
|
|
Loading…
Reference in New Issue