Browse Source

AP_HAL_ChibiOS: reduce stack sizes for rcout, uart_rx and storage.

zr-v5.1
Andy Piper 4 years ago committed by Andrew Tridgell
parent
commit
4e61ba2dc8
  1. 6
      libraries/AP_HAL_ChibiOS/Scheduler.h
  2. 2
      libraries/AP_HAL_ChibiOS/UARTDriver.cpp

6
libraries/AP_HAL_ChibiOS/Scheduler.h

@ -60,7 +60,7 @@ @@ -60,7 +60,7 @@
#endif
#ifndef RCOUT_THD_WA_SIZE
#define RCOUT_THD_WA_SIZE 1024
#define RCOUT_THD_WA_SIZE 512
#endif
#ifndef RCIN_THD_WA_SIZE
@ -72,11 +72,11 @@ @@ -72,11 +72,11 @@
#endif
#ifndef STORAGE_THD_WA_SIZE
#define STORAGE_THD_WA_SIZE 1536
#define STORAGE_THD_WA_SIZE 1024
#endif
#ifndef MONITOR_THD_WA_SIZE
#define MONITOR_THD_WA_SIZE 768
#define MONITOR_THD_WA_SIZE 512
#endif
/* Scheduler implementation: */

2
libraries/AP_HAL_ChibiOS/UARTDriver.cpp

@ -79,7 +79,7 @@ static const eventmask_t EVT_TRANSMIT_UNBUFFERED = EVENT_MASK(3); @@ -79,7 +79,7 @@ static const eventmask_t EVT_TRANSMIT_UNBUFFERED = EVENT_MASK(3);
#endif
#ifndef HAL_UART_RX_STACK_SIZE
#define HAL_UART_RX_STACK_SIZE 1024
#define HAL_UART_RX_STACK_SIZE 768
#endif
UARTDriver::UARTDriver(uint8_t _serial_num) :

Loading…
Cancel
Save