mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-21 16:18:29 -04:00
HAL_ChibiOS: adjust up uart tx stack size
lowest was showing 80 bytes free, which is too close to the 64 byte level where we trigger an internal error
This commit is contained in:
parent
5e0f175223
commit
3b88a3273b
@ -75,7 +75,7 @@ static const eventmask_t EVT_TRANSMIT_UNBUFFERED = EVENT_MASK(3);
|
||||
#endif
|
||||
|
||||
#ifndef HAL_UART_STACK_SIZE
|
||||
#define HAL_UART_STACK_SIZE 256
|
||||
#define HAL_UART_STACK_SIZE 320
|
||||
#endif
|
||||
|
||||
#ifndef HAL_UART_RX_STACK_SIZE
|
||||
|
Loading…
Reference in New Issue
Block a user