AP_HAL_ChibiOS: use HAL_XIP_ENABLED to denote running in external flash

This commit is contained in:
Andy Piper 2023-04-23 17:28:25 +01:00 committed by Andrew Tridgell
parent 5ff472208c
commit 26c59349d5
6 changed files with 18 additions and 5 deletions

View File

@ -236,7 +236,7 @@ void __early_init(void) {
#if !defined(STM32F1)
stm32_gpio_init();
#endif
#if !defined(STM32_QSPI_NO_RESET) && !defined(STM32_OSPI1_NO_RESET) && !defined(STM32_OSPI2_NO_RESET)
#if !HAL_XIP_ENABLED
// if running from external flash then the clocks must not be reset - instead rely on the bootloader to setup
stm32_clock_init();
#endif

View File

@ -584,4 +584,6 @@
#define WSPI_USE_MUTUAL_EXCLUSION TRUE
#endif
/** @} */

View File

@ -43,6 +43,10 @@
#define STM32_DMA_ERROR_HOOK(devp) do {} while(0)
#endif
#if !defined(HAL_XIP_ENABLED)
#define HAL_XIP_ENABLED FALSE
#endif
#if defined(STM32F1)
#include "stm32f1_mcuconf.h"
#elif defined(STM32F3)

View File

@ -641,6 +641,10 @@
#define STM32_WSPI_QUADSPI1_PRESCALER_VALUE (STM32_QSPICLK / HAL_QSPI1_CLK)
#endif
#if HAL_XIP_ENABLED
#define STM32_QSPI_NO_RESET TRUE
#endif
/*
we use a fixed allocation of BDMA streams. We previously dynamically
allocated these, but bugs in the chip make that unreliable. This is

View File

@ -567,6 +567,11 @@
#define STM32_WSPI_USE_OCTOSPI1 FALSE
#endif
#if HAL_XIP_ENABLED
#define STM32_OSPI1_NO_RESET TRUE
#define STM32_OSPI2_NO_RESET TRUE
#endif
#if STM32_WSPI_USE_OCTOSPI1
#define STM32_WSPI_OCTOSPI1_MDMA_CHANNEL STM32_MDMA_CHANNEL_ID_ANY
#define STM32_WSPI_OCTOSPI1_MDMA_PRIORITY 1

View File

@ -1537,10 +1537,8 @@ def write_WSPI_config(f):
# only the bootloader must run the hal lld (and QSPI clock) otherwise it is not possible to
# bootstrap into external flash
for t in list(bytype.keys()) + list(alttype.keys()):
if t.startswith('QUADSPI') and not args.bootloader:
f.write('#define STM32_QSPI_NO_RESET TRUE\n')
if t.startswith('OCTOSPI') and not args.bootloader:
f.write('#define STM32_OSPI1_NO_RESET TRUE\n')
if (t.startswith('QUADSPI') or t.startswith('OCTOSPI')) and not args.bootloader:
f.write('#define HAL_XIP_ENABLED TRUE\n')
if len(wspidev) == 0:
# nothing else to do