AP_HAL_ChibiOS: adjust stack sizes

This commit is contained in:
Andrew Tridgell 2021-01-07 11:14:55 +11:00
parent 8fb403c569
commit afbdd69165
3 changed files with 4 additions and 4 deletions

View File

@ -54,7 +54,7 @@
#endif
#ifndef TIMER_THD_WA_SIZE
#define TIMER_THD_WA_SIZE 2048
#define TIMER_THD_WA_SIZE 1536
#endif
#ifndef RCIN_THD_WA_SIZE
@ -66,7 +66,7 @@
#endif
#ifndef STORAGE_THD_WA_SIZE
#define STORAGE_THD_WA_SIZE 2048
#define STORAGE_THD_WA_SIZE 1536
#endif
#ifndef MONITOR_THD_WA_SIZE

View File

@ -65,7 +65,7 @@ UARTDriver *UARTDriver::uart_drivers[UART_MAX_DRIVERS];
#endif
#ifndef HAL_UART_STACK_SIZE
#define HAL_UART_STACK_SIZE 2048
#define HAL_UART_STACK_SIZE 1536
#endif
UARTDriver::UARTDriver(uint8_t _serial_num) :

View File

@ -679,7 +679,7 @@ def write_mcu_config(f):
if get_config('PROCESS_STACK', required=False):
env_vars['PROCESS_STACK'] = get_config('PROCESS_STACK')
else:
env_vars['PROCESS_STACK'] = "0x2000"
env_vars['PROCESS_STACK'] = "0x1C00"
# MAIN_STACK is location of initial stack on startup and is also the stack
# used for slow interrupts. It needs to be big enough for maximum interrupt