From 573cd6db6d88bf607dc5e6636d260db117ad6ca0 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 28 Nov 2020 15:19:14 +1100 Subject: [PATCH] HAL_ChibiOS: adjust MAIN_STACK for more ISR stack we need more stack to deal with interrupt nesting between CAN, system timer and serial interrupts --- libraries/AP_HAL_ChibiOS/hwdef/ZubaxGNSS/hwdef.dat | 2 +- libraries/AP_HAL_ChibiOS/hwdef/f103-periph/hwdef.dat | 4 ++-- libraries/AP_HAL_ChibiOS/hwdef/f303-MatekGPS/hwdef.dat | 2 +- libraries/AP_HAL_ChibiOS/hwdef/f303-periph/hwdef.dat | 6 +++--- libraries/AP_HAL_ChibiOS/hwdef/scripts/chibios_hwdef.py | 5 ++++- 5 files changed, 11 insertions(+), 8 deletions(-) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/ZubaxGNSS/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/ZubaxGNSS/hwdef.dat index f1dbfbd8af..69471fe702 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/ZubaxGNSS/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/ZubaxGNSS/hwdef.dat @@ -119,7 +119,7 @@ define NO_DATAFLASH TRUE define DMA_RESERVE_SIZE 0 define PERIPH_FW TRUE -MAIN_STACK 0x100 +MAIN_STACK 0x200 PROCESS_STACK 0x600 define HAL_DISABLE_LOOP_DELAY diff --git a/libraries/AP_HAL_ChibiOS/hwdef/f103-periph/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/f103-periph/hwdef.dat index c6ba4bb6b8..3122176fc0 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/f103-periph/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/f103-periph/hwdef.dat @@ -82,8 +82,8 @@ define DMA_RESERVE_SIZE 0 define PERIPH_FW TRUE -# MAIN_STACK is stack of initial thread -MAIN_STACK 0x80 +# MAIN_STACK is stack of initial thread and ISRs +MAIN_STACK 0x200 # PROCESS_STACK controls stack for main thread PROCESS_STACK 0x600 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/f303-MatekGPS/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/f303-MatekGPS/hwdef.dat index c2f3e3fb45..3760fb153d 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/f303-MatekGPS/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/f303-MatekGPS/hwdef.dat @@ -58,7 +58,7 @@ define DMA_RESERVE_SIZE 0 define PERIPH_FW TRUE # MAIN_STACK is stack of initial thread -MAIN_STACK 0x80 +MAIN_STACK 0x200 # PROCESS_STACK controls stack for main thread PROCESS_STACK 0x800 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/f303-periph/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/f303-periph/hwdef.dat index 4cbf49f096..9746ff2257 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/f303-periph/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/f303-periph/hwdef.dat @@ -77,8 +77,8 @@ define DMA_RESERVE_SIZE 0 define PERIPH_FW TRUE -# MAIN_STACK is stack of initial thread -MAIN_STACK 0x80 +# MAIN_STACK is stack of initial thread and of ISRs +MAIN_STACK 0x200 # PROCESS_STACK controls stack for main thread PROCESS_STACK 0x800 @@ -107,7 +107,7 @@ define IO_THD_WA_SIZE 256 define HAL_NO_GCS define HAL_NO_LOGGING -define HAL_NO_MONITOR_THREAD +//define HAL_NO_MONITOR_THREAD define HAL_MINIMIZE_FEATURES 0 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/scripts/chibios_hwdef.py b/libraries/AP_HAL_ChibiOS/hwdef/scripts/chibios_hwdef.py index 8e8434ca7f..973b85529a 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/scripts/chibios_hwdef.py +++ b/libraries/AP_HAL_ChibiOS/hwdef/scripts/chibios_hwdef.py @@ -679,10 +679,13 @@ def write_mcu_config(f): else: env_vars['PROCESS_STACK'] = "0x2000" + # 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 + # nesting if get_config('MAIN_STACK', required=False): env_vars['MAIN_STACK'] = get_config('MAIN_STACK') else: - env_vars['MAIN_STACK'] = "0x400" + env_vars['MAIN_STACK'] = "0x600" if get_config('IOMCU_FW', required=False): env_vars['IOMCU_FW'] = get_config('IOMCU_FW')