Browse Source

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
zr-v5.1
Andrew Tridgell 4 years ago
parent
commit
3b88a3273b
  1. 2
      libraries/AP_HAL_ChibiOS/UARTDriver.cpp

2
libraries/AP_HAL_ChibiOS/UARTDriver.cpp

@ -75,7 +75,7 @@ static const eventmask_t EVT_TRANSMIT_UNBUFFERED = EVENT_MASK(3); @@ -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…
Cancel
Save