diff --git a/libraries/AP_HAL_ChibiOS/Scheduler.h b/libraries/AP_HAL_ChibiOS/Scheduler.h index eea99da8da..fa9c6cb817 100644 --- a/libraries/AP_HAL_ChibiOS/Scheduler.h +++ b/libraries/AP_HAL_ChibiOS/Scheduler.h @@ -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: */ diff --git a/libraries/AP_HAL_ChibiOS/UARTDriver.cpp b/libraries/AP_HAL_ChibiOS/UARTDriver.cpp index 529bbf4373..ad6490d1ed 100644 --- a/libraries/AP_HAL_ChibiOS/UARTDriver.cpp +++ b/libraries/AP_HAL_ChibiOS/UARTDriver.cpp @@ -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) :