1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-23 00:05:33 +03:00
betaflight/make/mcu/STM32H7.mk
Dominic Clifton 5213bb5871
Fix unified targets that use OctoSPI. (BF4.4.x) (#12307)
OctoSPI and Memory Mapped Flash support (#11825)

* STM32H730/STM32H750 - Fix use of USE_LP_UART1 instead of USE_LPUART1.

* STM32H723 - Prepare for being able to build for using non-internal-flash
config storage.

* STM32H723 - Prepare for using non-default strings.

* STM32H723 - Disable 'use custom defaults' when using USE_EXST.

* STM32H723 - Disable CUSTOM_DEFAULTS_EXTENDED when EXST is used.

* OCTOSPI - Add initialisation code.

* Add support for RAM_CODE.

* STM32H730 - Add support for RAM_CODE via the .ram_code attribute.

* OCTOSPI - Proof-of-concept for disabling/enabling memory mapped mode on
a running system.

NOTE: The HAL libs are compiled into a memory mapped region, and this cannot be used for OctoSPI access when memory mapped mode is disabled.

* OCTOSPI - Drop HAL support after determining that it's not suitable for
the memory mapped flash use-case.

* OCTOSPI - Sometimes, when disabling memory map mode, the abort fails.
Handle this by disabling the OSPI peripheral first and re-enabling it
afterwards.

* SD/FLASH - Update comments regarding possible solutions to the catch-22
issue with SD/SPI/QUADSPI/OCTOSPI pin configurations.

* OCTOSPI - Use device instance directly.

* OCTOSPI - Prepare W25Q flash driver for octospi support.

* OCTOSPI - Add octospi flash detection.

Note: The method to detect flash chips is similar to the method used for
QUADSPI and as such the code was used as a base. However the initial
OCTOSPI implementation doesn't support the non-memory-mapped use-case so
the un-tested code is gated with `USE_OCTOSPI_EXPERIMENTAL`.

The key differences are:
* uses octospi api not quadspi api.
* flash chip clock speeds should not be changed for memory-mapped flash
chips, bootloader already set it correctly.
* only certain flash chips are capable of memory mapped support.

* W25Q - Ensure w25q128fv_readRegister returns 0 if the receive fails.

* OCTOSPI - Implement octoSpiTransmit1LINE, octoSpiReceive1LINE and
octoSpiReceive4LINES.

* OCTOSPI - Specify device from init.

* OCTOSPI - More fixes and work on init.

Current status is that memory mapped mode is disabled and flash chip is
detected, but w25q128fv_detect should not be calling w25q128fv_reset.

* FLASH - Add comment regarding wasted flash space on targets that only
use one bus type for the flash chip.

* FLASH - Split `detect` into `identify` and `configure`.

* OCTOSPI - Extract flashMemoryMappedModeEnable/Disable to separate
methods.

* FLASH - Reduce size of targets that don't support the use of multiple
flash interfaces.

* Single-flash-chip targets usually only support one type of io
interface.
* Without this, compiler warnings are generated in `flashSpiInit` for
targets that only use flash chip drivers that support quadspi or octospi
that don't even use SPI for flash.

* FLASH - Use MMFLASH_CODE/DATA to conditionally move code/data to RAM.

Only targets compiled to support memory mapped flash chips need the some
specific code in RAM.  Otherwise the code/data should be in the normal
linker section.

* FLASH - W25Q Prepare for memory mapped flash usage.

* Wait/Delay functions must work with interrupts disabled.
* Code used for reading/writing must run from RAM.

* OCTOSPI - Implement remaining required methods.

* OCTOSPI - Fixes for earlier code (not last commit).

* FLASH - W25Q update timeout values from Datasheet Rev L.

* FLASH - Prepare flash driver for use when memory mapped flash is
disabled.

* System - Prepare microsISR for use when memory mapped flash is disabled.

* FLASH - Add support for CONFIG_IN_MEMORY_MAPPED_FLASH.

* Flash - Fix incorrect gating on cli flash commands.

When compiling with USE_FLASH_CHIP and without USE_FLASHFS there were
compiler warnings.

* MMFLASH - Fix release-mode build.

* FLASH - Allow SPI pins to be reconfigured when using CONFIG_IN_MEMORY_MAPPED_FLASH.

MMFLASH only works via QuadSPI/OctoSPI peripherals.

* EXST - Disable the 2GB workaround which is now causing a different
error.

The error we get with 'remove-section' enabled is:

"error in private header data: sorry, cannot handle this file".  The
cause of this new error in the objcopy codebase is an out of memory
condition, somehow the 2GB files and this error are related but the root
cause of both is still unknown.

* OCTOSPI - Add support for STM32H723.

* STM32H723 - Add linker scripts for EXST usage.

* NucleoH723ZG - Add build script to demonstrate OCTOSPI and Memory Mapped
flash support.

* FLASH - WUse the size in bits to set the size of the buffer.

* FLASH - Fix typo in W25N driver defines.

Was using W28N instead of W25N

* OCTOSPI - Fix missing semilcolon when compiling without
USE_FLASH_MEMORY_MAPPED.

* OCTPSPI - Fix missing call to 'memoryMappedModeInit'.

* SPRacingH7RF - Add example build script to allow for testing prior to
unified target / cloud-build support.
2023-02-07 23:20:18 +01:00

370 lines
12 KiB
Makefile

#
# H7 Make file include
#
ifeq ($(DEBUG_HARDFAULTS),H7)
CFLAGS += -DDEBUG_HARDFAULTS
endif
#CMSIS
CMSIS_DIR := $(ROOT)/lib/main/CMSIS
#STDPERIPH
STDPERIPH_DIR = $(ROOT)/lib/main/STM32H7/Drivers/STM32H7xx_HAL_Driver
STDPERIPH_SRC = $(notdir $(wildcard $(STDPERIPH_DIR)/Src/*.c))
EXCLUDES = \
stm32h7xx_hal_cec.c \
stm32h7xx_hal_comp.c \
stm32h7xx_hal_crc.c \
stm32h7xx_hal_crc_ex.c \
stm32h7xx_hal_cryp.c \
stm32h7xx_hal_cryp_ex.c \
stm32h7xx_hal_dcmi.c \
stm32h7xx_hal_dfsdm.c \
stm32h7xx_hal_dma2d.c \
stm32h7xx_hal_dsi.c \
stm32h7xx_hal_eth.c \
stm32h7xx_hal_eth_ex.c \
stm32h7xx_hal_fdcan.c \
stm32h7xx_hal_hash.c \
stm32h7xx_hal_hash_ex.c \
stm32h7xx_hal_hcd.c \
stm32h7xx_hal_hrtim.c \
stm32h7xx_hal_hsem.c \
stm32h7xx_hal_i2s.c \
stm32h7xx_hal_i2s_ex.c \
stm32h7xx_hal_irda.c \
stm32h7xx_hal_iwdg.c \
stm32h7xx_hal_jpeg.c \
stm32h7xx_hal_lptim.c \
stm32h7xx_hal_ltdc.c \
stm32h7xx_hal_ltdc_ex.c \
stm32h7xx_hal_mdios.c \
stm32h7xx_hal_mdma.c \
stm32h7xx_hal_mmc.c \
stm32h7xx_hal_mmc_ex.c \
stm32h7xx_hal_msp_template.c \
stm32h7xx_hal_nand.c \
stm32h7xx_hal_nor.c \
stm32h7xx_hal_opamp.c \
stm32h7xx_hal_opamp_ex.c \
stm32h7xx_hal_ramecc.c \
stm32h7xx_hal_rng.c \
stm32h7xx_hal_rtc.c \
stm32h7xx_hal_sai.c \
stm32h7xx_hal_sai_ex.c \
stm32h7xx_hal_sd_ex.c \
stm32h7xx_hal_sdram.c \
stm32h7xx_hal_smartcard.c \
stm32h7xx_hal_smartcard_ex.c \
stm32h7xx_hal_smbus.c \
stm32h7xx_hal_spdifrx.c \
stm32h7xx_hal_spi.c \
stm32h7xx_hal_sram.c \
stm32h7xx_hal_swpmi.c \
stm32h7xx_hal_usart.c \
stm32h7xx_hal_usart_ex.c \
stm32h7xx_hal_wwdg.c \
stm32h7xx_ll_adc.c \
stm32h7xx_ll_bdma.c \
stm32h7xx_ll_comp.c \
stm32h7xx_ll_crc.c \
stm32h7xx_ll_dac.c \
stm32h7xx_ll_delayblock.c \
stm32h7xx_ll_dma2d.c \
stm32h7xx_ll_exti.c \
stm32h7xx_ll_fmc.c \
stm32h7xx_ll_gpio.c \
stm32h7xx_ll_hrtim.c \
stm32h7xx_ll_i2c.c \
stm32h7xx_ll_lptim.c \
stm32h7xx_ll_lpuart.c \
stm32h7xx_ll_mdma.c \
stm32h7xx_ll_opamp.c \
stm32h7xx_ll_pwr.c \
stm32h7xx_ll_rcc.c \
stm32h7xx_ll_rng.c \
stm32h7xx_ll_rtc.c \
stm32h7xx_ll_swpmi.c \
stm32h7xx_ll_usart.c \
stm32h7xx_ll_utils.c
STDPERIPH_SRC := $(filter-out ${EXCLUDES}, $(STDPERIPH_SRC))
#USB
USBCORE_DIR = $(ROOT)/lib/main/STM32H7/Middlewares/ST/STM32_USB_Device_Library/Core
USBCORE_SRC = $(notdir $(wildcard $(USBCORE_DIR)/Src/*.c))
EXCLUDES = usbd_conf_template.c
USBCORE_SRC := $(filter-out ${EXCLUDES}, $(USBCORE_SRC))
USBCDC_DIR = $(ROOT)/lib/main/STM32H7/Middlewares/ST/STM32_USB_Device_Library/Class/CDC
USBCDC_SRC = $(notdir $(wildcard $(USBCDC_DIR)/Src/*.c))
EXCLUDES = usbd_cdc_if_template.c
USBCDC_SRC := $(filter-out ${EXCLUDES}, $(USBCDC_SRC))
USBHID_DIR = $(ROOT)/lib/main/STM32H7/Middlewares/ST/STM32_USB_Device_Library/Class/HID
USBHID_SRC = $(notdir $(wildcard $(USBHID_DIR)/Src/*.c))
USBMSC_DIR = $(ROOT)/lib/main/STM32H7/Middlewares/ST/STM32_USB_Device_Library/Class/MSC
USBMSC_SRC = $(notdir $(wildcard $(USBMSC_DIR)/Src/*.c))
EXCLUDES = usbd_msc_storage_template.c
USBMSC_SRC := $(filter-out ${EXCLUDES}, $(USBMSC_SRC))
VPATH := $(VPATH):$(USBCDC_DIR)/Src:$(USBCORE_DIR)/Src:$(USBHID_DIR)/Src:$(USBMSC_DIR)/Src
DEVICE_STDPERIPH_SRC := $(STDPERIPH_SRC) \
$(USBCORE_SRC) \
$(USBCDC_SRC) \
$(USBHID_SRC) \
$(USBMSC_SRC)
#CMSIS
VPATH := $(VPATH):$(CMSIS_DIR)/Include:$(CMSIS_DIR)/Device/ST/STM32H7xx
VPATH := $(VPATH):$(STDPERIPH_DIR)/Src
CMSIS_SRC :=
INCLUDE_DIRS := $(INCLUDE_DIRS) \
$(STDPERIPH_DIR)/Inc \
$(USBCORE_DIR)/Inc \
$(USBCDC_DIR)/Inc \
$(USBHID_DIR)/Inc \
$(USBMSC_DIR)/Inc \
$(CMSIS_DIR)/Core/Include \
$(ROOT)/lib/main/STM32H7/Drivers/CMSIS/Device/ST/STM32H7xx/Include \
$(ROOT)/src/main/vcp_hal
ifneq ($(filter SDCARD_SPI,$(FEATURES)),)
INCLUDE_DIRS := $(INCLUDE_DIRS) \
$(FATFS_DIR)
VPATH := $(VPATH):$(FATFS_DIR)
endif
ifneq ($(filter SDCARD_SDIO,$(FEATURES)),)
INCLUDE_DIRS := $(INCLUDE_DIRS) \
$(FATFS_DIR)
VPATH := $(VPATH):$(FATFS_DIR)
endif
#Flags
ARCH_FLAGS = -mthumb -mcpu=cortex-m7 -mfloat-abi=hard -mfpu=fpv5-sp-d16 -fsingle-precision-constant
# Flags that are used in the STM32 libraries
DEVICE_FLAGS = -DUSE_HAL_DRIVER -DUSE_FULL_LL_DRIVER
#
# H743xI : 2M FLASH, 512KB AXI SRAM + 512KB D2 & D3 SRAM (H753xI also)
# H743xG : 1M FLASH, 512KB AXI SRAM + 512KB D2 & D3 SRAM (H753xG also)
# H7A3xI : 2M FLASH, 1MB AXI SRAM + 160KB AHB & SRD SRAM
# H750xB : 128K FLASH, 1M RAM
#
ifeq ($(TARGET),$(filter $(TARGET),$(H743xI_TARGETS)))
DEVICE_FLAGS += -DSTM32H743xx
DEFAULT_LD_SCRIPT = $(LINKER_DIR)/stm32_flash_h743_2m.ld
STARTUP_SRC = startup_stm32h743xx.s
MCU_FLASH_SIZE := 2048
DEVICE_FLAGS += -DMAX_MPU_REGIONS=16
ifeq ($(RAM_BASED),yes)
FIRMWARE_SIZE := 448
# TARGET_FLASH now becomes the amount of RAM memory that is occupied by the firmware
# and the maximum size of the data stored on the external storage device.
MCU_FLASH_SIZE := FIRMWARE_SIZE
DEFAULT_LD_SCRIPT = $(LINKER_DIR)/stm32_ram_h743.ld
endif
else ifeq ($(TARGET),$(filter $(TARGET),$(H7A3xIQ_TARGETS)))
DEVICE_FLAGS += -DSTM32H7A3xxQ
DEFAULT_LD_SCRIPT = $(LINKER_DIR)/stm32_flash_h7a3_2m.ld
STARTUP_SRC = startup_stm32h7a3xx.s
MCU_FLASH_SIZE := 2048
DEVICE_FLAGS += -DMAX_MPU_REGIONS=16
ifeq ($(RAM_BASED),yes)
FIRMWARE_SIZE := 448
# TARGET_FLASH now becomes the amount of RAM memory that is occupied by the firmware
# and the maximum size of the data stored on the external storage device.
MCU_FLASH_SIZE := FIRMWARE_SIZE
DEFAULT_LD_SCRIPT = $(LINKER_DIR)/stm32_flash_h7a3_ram_based.ld
endif
else ifeq ($(TARGET),$(filter $(TARGET),$(H7A3xI_TARGETS)))
DEVICE_FLAGS += -DSTM32H7A3xx
DEFAULT_LD_SCRIPT = $(LINKER_DIR)/stm32_flash_h7a3_2m.ld
STARTUP_SRC = startup_stm32h7a3xx.s
MCU_FLASH_SIZE := 2048
DEVICE_FLAGS += -DMAX_MPU_REGIONS=16
ifeq ($(RAM_BASED),yes)
FIRMWARE_SIZE := 448
# TARGET_FLASH now becomes the amount of RAM memory that is occupied by the firmware
# and the maximum size of the data stored on the external storage device.
MCU_FLASH_SIZE := FIRMWARE_SIZE
DEFAULT_LD_SCRIPT = $(LINKER_DIR)/stm32_flash_h7a3_ram_based.ld
endif
else ifeq ($(TARGET),$(filter $(TARGET),$(H723xG_TARGETS)))
DEVICE_FLAGS += -DSTM32H723xx
DEFAULT_LD_SCRIPT = $(LINKER_DIR)/stm32_flash_h723_1m.ld
STARTUP_SRC = startup_stm32h723xx.s
DEFAULT_TARGET_FLASH := 1024
DEVICE_FLAGS += -DMAX_MPU_REGIONS=16
ifeq ($(TARGET_FLASH),)
MCU_FLASH_SIZE := $(DEFAULT_TARGET_FLASH)
endif
ifeq ($(EXST),yes)
FIRMWARE_SIZE := 1024
# TARGET_FLASH now becomes the amount of MEMORY-MAPPED address space that is occupied by the firmware
# and the maximum size of the data stored on the external flash device.
MCU_FLASH_SIZE := FIRMWARE_SIZE
DEFAULT_LD_SCRIPT = $(LINKER_DIR)/stm32_ram_h723_exst.ld
LD_SCRIPTS = $(LINKER_DIR)/stm32_h723_common.ld $(LINKER_DIR)/stm32_h723_common_post.ld
endif
else ifeq ($(TARGET),$(filter $(TARGET),$(H725xG_TARGETS)))
DEVICE_FLAGS += -DSTM32H725xx
DEFAULT_LD_SCRIPT = $(LINKER_DIR)/stm32_flash_h723_1m.ld
STARTUP_SRC = startup_stm32h723xx.s
MCU_FLASH_SIZE := 1024
DEVICE_FLAGS += -DMAX_MPU_REGIONS=16
else ifeq ($(TARGET),$(filter $(TARGET),$(H730xB_TARGETS)))
DEVICE_FLAGS += -DSTM32H730xx
DEFAULT_LD_SCRIPT = $(LINKER_DIR)/stm32_flash_h730_128m.ld
STARTUP_SRC = startup_stm32h730xx.s
DEFAULT_TARGET_FLASH := 128
DEVICE_FLAGS += -DMAX_MPU_REGIONS=16
ifeq ($(TARGET_FLASH),)
MCU_FLASH_SIZE := $(DEFAULT_TARGET_FLASH)
endif
ifeq ($(EXST),yes)
FIRMWARE_SIZE := 1024
# TARGET_FLASH now becomes the amount of MEMORY-MAPPED address space that is occupied by the firmware
# and the maximum size of the data stored on the external flash device.
MCU_FLASH_SIZE := FIRMWARE_SIZE
DEFAULT_LD_SCRIPT = $(LINKER_DIR)/stm32_ram_h730_exst.ld
LD_SCRIPTS = $(LINKER_DIR)/stm32_h730_common.ld $(LINKER_DIR)/stm32_h730_common_post.ld
endif
else ifeq ($(TARGET),$(filter $(TARGET),$(H750xB_TARGETS)))
DEVICE_FLAGS += -DSTM32H750xx
DEFAULT_LD_SCRIPT = $(LINKER_DIR)/stm32_flash_h750_128k.ld
STARTUP_SRC = startup_stm32h743xx.s
DEFAULT_TARGET_FLASH := 128
ifeq ($(TARGET_FLASH),)
MCU_FLASH_SIZE := $(DEFAULT_TARGET_FLASH)
endif
ifeq ($(EXST),yes)
FIRMWARE_SIZE := 448
# TARGET_FLASH now becomes the amount of RAM memory that is occupied by the firmware
# and the maximum size of the data stored on the external storage device.
MCU_FLASH_SIZE := FIRMWARE_SIZE
DEFAULT_LD_SCRIPT = $(LINKER_DIR)/stm32_ram_h750_exst.ld
endif
ifeq ($(EXST),yes)
# Upper 8 regions are reserved for a boot loader in EXST environment
DEVICE_FLAGS += -DMAX_MPU_REGIONS=8
else
DEVICE_FLAGS += -DMAX_MPU_REGIONS=16
endif
ifneq ($(DEBUG),GDB)
OPTIMISE_DEFAULT := -Os
OPTIMISE_SPEED := -Os
OPTIMISE_SIZE := -Os
LTO_FLAGS := $(OPTIMISATION_BASE) $(OPTIMISE_DEFAULT)
endif
else
$(error Unknown MCU for H7 target)
endif
ifeq ($(LD_SCRIPT),)
LD_SCRIPT = $(DEFAULT_LD_SCRIPT)
endif
ifneq ($(FIRMWARE_SIZE),)
DEVICE_FLAGS += -DFIRMWARE_SIZE=$(FIRMWARE_SIZE)
endif
DEVICE_FLAGS += -DHSE_VALUE=$(HSE_VALUE) -DHSE_STARTUP_TIMEOUT=1000
TARGET_FLAGS = -D$(TARGET)
VCP_SRC = \
vcp_hal/usbd_desc.c \
vcp_hal/usbd_conf_stm32h7xx.c \
vcp_hal/usbd_cdc_hid.c \
vcp_hal/usbd_cdc_interface.c \
drivers/serial_usb_vcp.c \
drivers/usb_io.c
MCU_COMMON_SRC = \
startup/system_stm32h7xx.c \
drivers/system_stm32h7xx.c \
drivers/timer_hal.c \
drivers/timer_stm32h7xx.c \
drivers/serial_uart_hal.c \
drivers/serial_uart_stm32h7xx.c \
drivers/bus_quadspi_hal.c \
drivers/bus_octospi_stm32h7xx.c \
drivers/bus_spi_ll.c \
drivers/dma_stm32h7xx.c \
drivers/dshot_bitbang.c \
drivers/dshot_bitbang_decode.c \
drivers/dshot_bitbang_ll.c \
drivers/light_ws2811strip_hal.c \
drivers/adc_stm32h7xx.c \
drivers/bus_i2c_hal.c \
drivers/bus_i2c_hal_init.c \
drivers/bus_i2c_timing.c \
drivers/pwm_output_dshot_hal.c \
drivers/pwm_output_dshot_shared.c \
drivers/persistent.c \
drivers/transponder_ir_io_hal.c \
drivers/audio_stm32h7xx.c \
drivers/memprot_hal.c \
drivers/memprot_stm32h7xx.c \
#drivers/accgyro/accgyro_mpu.c \
MCU_EXCLUDES = \
drivers/bus_i2c.c \
drivers/timer.c
MSC_SRC = \
drivers/usb_msc_common.c \
drivers/usb_msc_h7xx.c \
msc/usbd_storage.c
ifneq ($(filter SDCARD_SDIO,$(FEATURES)),)
MCU_COMMON_SRC += \
drivers/sdio_h7xx.c
MSC_SRC += \
msc/usbd_storage_sdio.c
endif
ifneq ($(filter SDCARD_SPI,$(FEATURES)),)
MSC_SRC += \
msc/usbd_storage_sd_spi.c
endif
ifneq ($(filter ONBOARDFLASH,$(FEATURES)),)
MSC_SRC += \
msc/usbd_storage_emfat.c \
msc/emfat.c \
msc/emfat_file.c
endif
DSP_LIB := $(ROOT)/lib/main/CMSIS/DSP
DEVICE_FLAGS += -DARM_MATH_MATRIX_CHECK -DARM_MATH_ROUNDING -D__FPU_PRESENT=1 -DUNALIGNED_SUPPORT_DISABLE -DARM_MATH_CM7