mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 00:28:30 -04:00
HAL_ChibiOS: disable RCIN and timer threads for iomcu
This commit is contained in:
parent
92d8ef0e76
commit
d7aaaa35bd
@ -81,6 +81,10 @@ define SERIAL_BUFFERS_SIZE 0
|
||||
define HAL_USE_EMPTY_IO TRUE
|
||||
define PORT_INT_REQUIRED_STACK 64
|
||||
|
||||
# avoid timer and RCIN threads to save memory
|
||||
define HAL_NO_TIMER_THREAD
|
||||
define HAL_NO_RCIN_THREAD
|
||||
|
||||
#defined to turn off undef warnings
|
||||
define __FPU_PRESENT 0
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user