mirror of https://github.com/ArduPilot/ardupilot
HAL_ChibiOS: raise timer thread priority
needs to be above main for guaranteed DShot and oneshot output periods
This commit is contained in:
parent
de66554948
commit
846418e5e9
|
@ -23,7 +23,7 @@
|
||||||
#define CHIBIOS_SCHEDULER_MAX_TIMER_PROCS 8
|
#define CHIBIOS_SCHEDULER_MAX_TIMER_PROCS 8
|
||||||
|
|
||||||
#define APM_MAIN_PRIORITY 180
|
#define APM_MAIN_PRIORITY 180
|
||||||
#define APM_TIMER_PRIORITY 178
|
#define APM_TIMER_PRIORITY 181
|
||||||
#define APM_RCIN_PRIORITY 177
|
#define APM_RCIN_PRIORITY 177
|
||||||
#define APM_UART_PRIORITY 60
|
#define APM_UART_PRIORITY 60
|
||||||
#define APM_STORAGE_PRIORITY 59
|
#define APM_STORAGE_PRIORITY 59
|
||||||
|
|
Loading…
Reference in New Issue