mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-04 06:58:39 -04:00
AP_HAL_ChibiOS: reduce stack sizes for rcout, uart_rx and storage.
This commit is contained in:
parent
94de238751
commit
4e61ba2dc8
@ -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 @@
|
||||
#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: */
|
||||
|
@ -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…
Reference in New Issue
Block a user