AP_HAL_CHIBIOS: allow RCIN thread priority to be overridden

Add provision to change Rcin thread priority
-needed to increase priority for some low speed cpu
This commit is contained in:
subashchandar 2023-08-24 11:17:42 +05:30 committed by Peter Barker
parent d59ff8501c
commit 3cfa13c0b2

View File

@ -26,7 +26,6 @@
#define APM_MAIN_PRIORITY 180
#define APM_TIMER_PRIORITY 181
#define APM_RCOUT_PRIORITY 181
#define APM_RCIN_PRIORITY 177
#define APM_LED_PRIORITY 60
#define APM_UART_PRIORITY 60
#define APM_UART_UNBUFFERED_PRIORITY 181
@ -42,6 +41,10 @@
#define APM_MAIN_PRIORITY_BOOST 182
#endif
#ifndef APM_RCIN_PRIORITY
#define APM_RCIN_PRIORITY 177
#endif
#ifndef APM_SPI_PRIORITY
// SPI priority needs to be above main priority to ensure fast sampling of IMUs can keep up
// with the data rate