mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-12 19:10:32 +03:00
Adding initial H563 target files in preparation (#13686)
* Adding initial H563 target files in preparation * Start up files * Explicit inclusion of source files for @ledvinap suggestion - adding system_stm32h5xx.c
This commit is contained in:
parent
e0483ada8f
commit
a49c5c3a35
11 changed files with 2439 additions and 3 deletions
2
.github/workflows/ci.yml
vendored
2
.github/workflows/ci.yml
vendored
|
@ -3,7 +3,7 @@
|
|||
|
||||
name: CI
|
||||
|
||||
on:
|
||||
on:
|
||||
workflow_call:
|
||||
inputs:
|
||||
release_build:
|
||||
|
|
5
Makefile
5
Makefile
|
@ -84,7 +84,7 @@ endif
|
|||
include $(MAKE_SCRIPT_DIR)/checks.mk
|
||||
|
||||
# basic target list
|
||||
BASE_TARGETS := $(sort $(notdir $(patsubst %/,%,$(dir $(wildcard $(ROOT)/src/main/target/*/target.mk)))))
|
||||
BASE_TARGETS := $(sort $(notdir $(patsubst %/,%,$(dir $(wildcard $(ROOT)/src/main/target/*/target.mk)))))
|
||||
|
||||
# configure some directories that are relative to wherever ROOT_DIR is located
|
||||
TOOLS_DIR ?= $(ROOT)/tools
|
||||
|
@ -127,7 +127,8 @@ endif
|
|||
# default xtal value
|
||||
HSE_VALUE ?= 8000000
|
||||
|
||||
CI_TARGETS := $(BASE_TARGETS) $(filter CRAZYBEEF4SX1280 CRAZYBEEF4FR IFLIGHT_BLITZ_F722 NUCLEOF446 SPRACINGH7EXTREME SPRACINGH7RF, $(BASE_CONFIGS))
|
||||
CI_EXCLUDED_TARGETS := $(sort $(notdir $(patsubst %/,%,$(dir $(wildcard $(ROOT)/src/main/target/*/.exclude)))))
|
||||
CI_TARGETS := $(filter-out $(CI_EXCLUDED_TARGETS), $(BASE_TARGETS)) $(filter CRAZYBEEF4SX1280 CRAZYBEEF4FR IFLIGHT_BLITZ_F722 NUCLEOF446 SPRACINGH7EXTREME SPRACINGH7RF, $(BASE_CONFIGS))
|
||||
include $(ROOT)/src/main/target/$(TARGET)/target.mk
|
||||
|
||||
REVISION := norevision
|
||||
|
|
200
mk/mcu/STM32H5.mk
Normal file
200
mk/mcu/STM32H5.mk
Normal file
|
@ -0,0 +1,200 @@
|
|||
#
|
||||
# H5 Make file include
|
||||
#
|
||||
|
||||
ifeq ($(DEBUG_HARDFAULTS),H5)
|
||||
CFLAGS += -DDEBUG_HARDFAULTS
|
||||
endif
|
||||
|
||||
#CMSIS
|
||||
CMSIS_DIR := $(ROOT)/lib/main/CMSIS
|
||||
|
||||
#STDPERIPH
|
||||
STDPERIPH_DIR = $(ROOT)/lib/main/STM32H5/Drivers/STM32H5xx_HAL_Driver
|
||||
STDPERIPH_SRC = \
|
||||
stm32h5xx_hal_adc.c \
|
||||
stm32h5xx_hal_adc_ex.c \
|
||||
stm32h5xx_hal.c \
|
||||
stm32h5xx_hal_cordic.c \
|
||||
stm32h5xx_hal_cortex.c \
|
||||
stm32h5xx_hal_dac.c \
|
||||
stm32h5xx_hal_dac_ex.c \
|
||||
stm32h5xx_hal_dcache.c \
|
||||
stm32h5xx_hal_dma.c \
|
||||
stm32h5xx_hal_dma_ex.c \
|
||||
stm32h5xx_hal_dts.c \
|
||||
stm32h5xx_hal_exti.c \
|
||||
stm32h5xx_hal_flash.c \
|
||||
stm32h5xx_hal_flash_ex.c \
|
||||
stm32h5xx_hal_fmac.c \
|
||||
stm32h5xx_hal_gpio.c \
|
||||
stm32h5xx_hal_gtzc.c \
|
||||
stm32h5xx_hal_i2c.c \
|
||||
stm32h5xx_hal_i2c_ex.c \
|
||||
stm32h5xx_hal_i3c.c \
|
||||
stm32h5xx_hal_icache.c \
|
||||
stm32h5xx_hal_otfdec.c \
|
||||
stm32h5xx_hal_pcd.c \
|
||||
stm32h5xx_hal_pcd_ex.c \
|
||||
stm32h5xx_hal_pka.c \
|
||||
stm32h5xx_hal_pssi.c \
|
||||
stm32h5xx_hal_pwr.c \
|
||||
stm32h5xx_hal_pwr_ex.c \
|
||||
stm32h5xx_hal_ramcfg.c \
|
||||
stm32h5xx_hal_rcc.c \
|
||||
stm32h5xx_hal_rcc_ex.c \
|
||||
stm32h5xx_hal_rng_ex.c \
|
||||
stm32h5xx_hal_rtc_ex.c \
|
||||
stm32h5xx_hal_sd.c \
|
||||
stm32h5xx_hal_smbus_ex.c \
|
||||
stm32h5xx_hal_spi_ex.c \
|
||||
stm32h5xx_hal_tim.c \
|
||||
stm32h5xx_hal_tim_ex.c \
|
||||
stm32h5xx_hal_uart.c \
|
||||
stm32h5xx_hal_uart_ex.c \
|
||||
stm32h5xx_hal_xspi.c \
|
||||
stm32h5xx_ll_cordic.c \
|
||||
stm32h5xx_ll_crs.c \
|
||||
stm32h5xx_ll_dlyb.c \
|
||||
stm32h5xx_ll_dma.c \
|
||||
stm32h5xx_ll_fmac.c \
|
||||
stm32h5xx_ll_i3c.c \
|
||||
stm32h5xx_ll_icache.c \
|
||||
stm32h5xx_ll_pka.c \
|
||||
stm32h5xx_ll_sdmmc.c \
|
||||
stm32h5xx_ll_spi.c \
|
||||
stm32h5xx_ll_tim.c \
|
||||
stm32h5xx_ll_ucpd.c \
|
||||
stm32h5xx_ll_usb.c \
|
||||
stm32h5xx_util_i3c.c
|
||||
|
||||
#USB ##TODO - need to work through the USB drivers, new directory: USBX
|
||||
#USBCORE_DIR = $(ROOT)/lib/main/STM32H5/Middlewares/ST/usbx/Common
|
||||
#USBCORE_SRC = $(notdir $(wildcard $(USBCORE_DIR)/Src/*.c))
|
||||
#EXCLUDES =
|
||||
#USBCORE_SRC := $(filter-out ${EXCLUDES}, $(USBCORE_SRC))
|
||||
|
||||
#VPATH := $(VPATH):$(USBCDC_DIR)/Src:$(USBCORE_DIR)/Src:$(USBHID_DIR)/Src:$(USBMSC_DIR)/Src:$(STDPERIPH_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/STM32H5xx
|
||||
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/STM32H5/Drivers/CMSIS/Device/ST/STM32H5xx/Include \
|
||||
$(ROOT)/src/main/drivers/stm32 \
|
||||
$(ROOT)/src/main/drivers/stm32/vcp_hal
|
||||
|
||||
#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
|
||||
|
||||
#
|
||||
# H563xx : 2M FLASH, 640KB SRAM
|
||||
#
|
||||
ifeq ($(TARGET_MCU),STM32H563xx)
|
||||
DEVICE_FLAGS += -DSTM32H563xx
|
||||
DEFAULT_LD_SCRIPT = $(LINKER_DIR)/stm32_flash_h563_2m.ld
|
||||
STARTUP_SRC = startup_stm32h563xx.s
|
||||
MCU_FLASH_SIZE := 2048
|
||||
DEVICE_FLAGS += -DMAX_MPU_REGIONS=16
|
||||
|
||||
# end H563xx
|
||||
|
||||
|
||||
ifneq ($(DEBUG),GDB)
|
||||
OPTIMISE_DEFAULT := -Os
|
||||
OPTIMISE_SPEED := -Os
|
||||
OPTIMISE_SIZE := -Os
|
||||
|
||||
LTO_FLAGS := $(OPTIMISATION_BASE) $(OPTIMISE_DEFAULT)
|
||||
endif
|
||||
|
||||
else
|
||||
$(error Unknown MCU for STM32H5 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 -DSTM32
|
||||
|
||||
VCP_SRC =
|
||||
#VCP_SRC = \
|
||||
drivers/stm32/vcp_hal/usbd_desc.c \
|
||||
drivers/stm32/vcp_hal/usbd_conf_stm32h5xx.c \
|
||||
drivers/stm32/vcp_hal/usbd_cdc_hid.c \
|
||||
drivers/stm32/vcp_hal/usbd_cdc_interface.c \
|
||||
drivers/stm32/serial_usb_vcp.c \
|
||||
drivers/usb_io.c
|
||||
|
||||
MCU_COMMON_SRC = \
|
||||
drivers/bus_i2c_timing.c \
|
||||
drivers/bus_quadspi.c \
|
||||
drivers/dshot_bitbang_decode.c \
|
||||
drivers/pwm_output_dshot_shared.c \
|
||||
drivers/stm32/bus_i2c_hal_init.c \
|
||||
drivers/stm32/bus_i2c_hal.c \
|
||||
drivers/stm32/bus_spi_ll.c \
|
||||
drivers/stm32/bus_quadspi_hal.c \
|
||||
drivers/stm32/debug.c \
|
||||
drivers/stm32/dma_reqmap_mcu.c \
|
||||
drivers/stm32/dshot_bitbang_ll.c \
|
||||
drivers/stm32/dshot_bitbang.c \
|
||||
drivers/stm32/exti.c \
|
||||
drivers/stm32/io_stm32.c \
|
||||
drivers/stm32/light_ws2811strip_hal.c \
|
||||
drivers/stm32/persistent.c \
|
||||
drivers/stm32/pwm_output.c \
|
||||
drivers/stm32/pwm_output_dshot_hal.c \
|
||||
drivers/stm32/rcc_stm32.c \
|
||||
drivers/stm32/serial_uart_hal.c \
|
||||
drivers/stm32/timer_hal.c \
|
||||
drivers/stm32/transponder_ir_io_hal.c \
|
||||
drivers/stm32/camera_control.c \
|
||||
drivers/stm32/system_stm32h5xx.c \
|
||||
startup/system_stm32h5xx.c
|
||||
|
||||
# drivers/stm32/memprot_hal.c \
|
||||
# drivers/stm32/memprot_stm32h5xx.c \
|
||||
# drivers/stm32/serial_uart_stm32h5xx.c \
|
||||
# drivers/stm32/sdio_h5xx.c \
|
||||
# drivers/stm32/timer_stm32h5xx.c \
|
||||
# drivers/stm32/adc_stm32h5xx.c \
|
||||
# drivers/stm32/dma_stm32h5xx.c \
|
||||
|
||||
MCU_EXCLUDES = \
|
||||
drivers/bus_i2c.c
|
||||
|
||||
MSC_SRC =
|
||||
#MSC_SRC = \
|
||||
drivers/stm32/usb_msc_hal.c \
|
||||
drivers/usb_msc_common.c \
|
||||
msc/usbd_storage.c \
|
||||
msc/usbd_storage_emfat.c \
|
||||
msc/emfat.c \
|
||||
msc/emfat_file.c \
|
||||
msc/usbd_storage_sd_spi.c \
|
||||
msc/usbd_storage_sdio.c
|
||||
|
||||
DSP_LIB := $(ROOT)/lib/main/CMSIS/DSP
|
||||
DEVICE_FLAGS += -DARM_MATH_MATRIX_CHECK -DARM_MATH_ROUNDING -DUNALIGNED_SUPPORT_DISABLE -DARM_MATH_CM7
|
268
src/link/stm32_flash_h563_2m.ld
Normal file
268
src/link/stm32_flash_h563_2m.ld
Normal file
|
@ -0,0 +1,268 @@
|
|||
/*
|
||||
*****************************************************************************
|
||||
**
|
||||
** File : stm32_flash_h5x3_2m.ld
|
||||
**
|
||||
** : Linker script for STM32H563ZITx Device from STM32H5 series
|
||||
** 2048Kbytes FLASH
|
||||
** 640Kbytes RAM
|
||||
**
|
||||
** Set heap size, stack size and stack location according
|
||||
** to application requirements.
|
||||
**
|
||||
** Set memory bank area and size if external memory is used
|
||||
**
|
||||
*****************************************************************************
|
||||
*/
|
||||
|
||||
/* Entry Point */
|
||||
ENTRY(Reset_Handler)
|
||||
|
||||
/*
|
||||
0x20000000 to 0x3001FFFF 640K SRAM
|
||||
|
||||
0x08000000 to 0x081FFFFF 2048K full flash,
|
||||
0x08000000 to 0x0801FFFF 128K isr vector, startup code,
|
||||
0x08020000 to 0x0803FFFF 128K config, // FLASH_Sector_1
|
||||
0x08040000 to 0x081FFFFF 1792K firmware,
|
||||
*/
|
||||
|
||||
/* Specify the memory areas */
|
||||
MEMORY
|
||||
{
|
||||
FLASH (rx) : ORIGIN = 0x08000000, LENGTH = 128K
|
||||
FLASH_CONFIG (r) : ORIGIN = 0x08020000, LENGTH = 128K
|
||||
FLASH1 (rx) : ORIGIN = 0x08040000, LENGTH = 1792K
|
||||
|
||||
RAM (rwx) : ORIGIN = 0x20000000, LENGTH = 640K
|
||||
MEMORY_B1 (rx) : ORIGIN = 0x60000000, LENGTH = 0K
|
||||
}
|
||||
|
||||
REGION_ALIAS("STACKRAM", RAM)
|
||||
REGION_ALIAS("FASTRAM", RAM)
|
||||
|
||||
/* Entry Point */
|
||||
ENTRY(Reset_Handler)
|
||||
|
||||
/* Highest address of the user mode stack */
|
||||
_estack = ORIGIN(STACKRAM) + LENGTH(STACKRAM) - 8; /* Reserve 2 x 4bytes for info across reset */
|
||||
|
||||
/* Base address where the config is stored. */
|
||||
__config_start = ORIGIN(FLASH_CONFIG);
|
||||
__config_end = ORIGIN(FLASH_CONFIG) + LENGTH(FLASH_CONFIG);
|
||||
|
||||
/* Generate a link error if heap and stack don't fit into RAM */
|
||||
_Min_Heap_Size = 0; /* required amount of heap */
|
||||
_Min_Stack_Size = 0x800; /* required amount of stack */
|
||||
|
||||
/* Define output sections */
|
||||
SECTIONS
|
||||
{
|
||||
/* The startup code goes first into FLASH */
|
||||
.isr_vector :
|
||||
{
|
||||
. = ALIGN(512);
|
||||
PROVIDE (isr_vector_table_base = .);
|
||||
KEEP(*(.isr_vector)) /* Startup code */
|
||||
. = ALIGN(4);
|
||||
} >FLASH
|
||||
|
||||
/* The program code and other data goes into FLASH */
|
||||
.text :
|
||||
{
|
||||
. = ALIGN(4);
|
||||
*(.text) /* .text sections (code) */
|
||||
*(.text*) /* .text* sections (code) */
|
||||
*(.rodata) /* .rodata sections (constants, strings, etc.) */
|
||||
*(.rodata*) /* .rodata* sections (constants, strings, etc.) */
|
||||
*(.glue_7) /* glue arm to thumb code */
|
||||
*(.glue_7t) /* glue thumb to arm code */
|
||||
*(.eh_frame)
|
||||
|
||||
KEEP (*(.init))
|
||||
KEEP (*(.fini))
|
||||
|
||||
. = ALIGN(4);
|
||||
_etext = .; /* define a global symbols at end of code */
|
||||
} >FLASH1
|
||||
|
||||
.ARM.extab :
|
||||
{
|
||||
*(.ARM.extab* .gnu.linkonce.armextab.*)
|
||||
} >FLASH1
|
||||
|
||||
.ARM :
|
||||
{
|
||||
__exidx_start = .;
|
||||
*(.ARM.exidx*) __exidx_end = .;
|
||||
} >FLASH1
|
||||
|
||||
.pg_registry :
|
||||
{
|
||||
PROVIDE_HIDDEN (__pg_registry_start = .);
|
||||
KEEP (*(.pg_registry))
|
||||
KEEP (*(SORT(.pg_registry.*)))
|
||||
PROVIDE_HIDDEN (__pg_registry_end = .);
|
||||
} >FLASH1
|
||||
|
||||
.pg_resetdata :
|
||||
{
|
||||
PROVIDE_HIDDEN (__pg_resetdata_start = .);
|
||||
KEEP (*(.pg_resetdata))
|
||||
PROVIDE_HIDDEN (__pg_resetdata_end = .);
|
||||
} >FLASH1
|
||||
|
||||
/* used by the startup to initialize data */
|
||||
_sidata = LOADADDR(.data);
|
||||
|
||||
/* Initialized data sections goes into RAM, load LMA copy after code */
|
||||
.data :
|
||||
{
|
||||
. = ALIGN(4);
|
||||
_sdata = .; /* create a global symbol at data start */
|
||||
*(.data) /* .data sections */
|
||||
*(.data*) /* .data* sections */
|
||||
|
||||
. = ALIGN(4);
|
||||
_edata = .; /* define a global symbol at data end */
|
||||
} >RAM AT >FLASH1
|
||||
|
||||
/* Uninitialized data section */
|
||||
. = ALIGN(4);
|
||||
.bss (NOLOAD) :
|
||||
{
|
||||
/* This is used by the startup in order to initialize the .bss secion */
|
||||
_sbss = .; /* define a global symbol at bss start */
|
||||
__bss_start__ = _sbss;
|
||||
*(.bss)
|
||||
*(SORT_BY_ALIGNMENT(.bss*))
|
||||
*(COMMON)
|
||||
|
||||
. = ALIGN(4);
|
||||
_ebss = .; /* define a global symbol at bss end */
|
||||
__bss_end__ = _ebss;
|
||||
} >RAM
|
||||
|
||||
/* Uninitialized data section */
|
||||
. = ALIGN(4);
|
||||
.sram2 (NOLOAD) :
|
||||
{
|
||||
/* This is used by the startup in order to initialize the .sram2 secion */
|
||||
_ssram2 = .; /* define a global symbol at sram2 start */
|
||||
__sram2_start__ = _ssram2;
|
||||
*(.sram2)
|
||||
*(SORT_BY_ALIGNMENT(.sram2*))
|
||||
|
||||
. = ALIGN(4);
|
||||
_esram2 = .; /* define a global symbol at sram2 end */
|
||||
__sram2_end__ = _esram2;
|
||||
} >RAM
|
||||
|
||||
/* used during startup to initialized fastram_data */
|
||||
_sfastram_idata = LOADADDR(.fastram_data);
|
||||
|
||||
/* Initialized FAST_DATA section for unsuspecting developers */
|
||||
.fastram_data :
|
||||
{
|
||||
. = ALIGN(4);
|
||||
_sfastram_data = .; /* create a global symbol at data start */
|
||||
*(.fastram_data) /* .data sections */
|
||||
*(.fastram_data*) /* .data* sections */
|
||||
|
||||
. = ALIGN(4);
|
||||
_efastram_data = .; /* define a global symbol at data end */
|
||||
} >FASTRAM AT >FLASH1
|
||||
|
||||
. = ALIGN(4);
|
||||
.fastram_bss (NOLOAD) :
|
||||
{
|
||||
_sfastram_bss = .;
|
||||
__fastram_bss_start__ = _sfastram_bss;
|
||||
*(.fastram_bss)
|
||||
*(SORT_BY_ALIGNMENT(.fastram_bss*))
|
||||
|
||||
. = ALIGN(4);
|
||||
_efastram_bss = .;
|
||||
__fastram_bss_end__ = _efastram_bss;
|
||||
} >FASTRAM
|
||||
|
||||
/* used during startup to initialized dmaram_data */
|
||||
_sdmaram_idata = LOADADDR(.dmaram_data);
|
||||
|
||||
. = ALIGN(32);
|
||||
.dmaram_data :
|
||||
{
|
||||
PROVIDE(dmaram_start = .);
|
||||
_sdmaram = .;
|
||||
_dmaram_start__ = _sdmaram;
|
||||
_sdmaram_data = .; /* create a global symbol at data start */
|
||||
*(.dmaram_data) /* .data sections */
|
||||
*(.dmaram_data*) /* .data* sections */
|
||||
. = ALIGN(32);
|
||||
_edmaram_data = .; /* define a global symbol at data end */
|
||||
} >RAM AT >FLASH1
|
||||
|
||||
. = ALIGN(32);
|
||||
.dmaram_bss (NOLOAD) :
|
||||
{
|
||||
_sdmaram_bss = .;
|
||||
__dmaram_bss_start__ = _sdmaram_bss;
|
||||
*(.dmaram_bss)
|
||||
*(SORT_BY_ALIGNMENT(.dmaram_bss*))
|
||||
. = ALIGN(32);
|
||||
_edmaram_bss = .;
|
||||
__dmaram_bss_end__ = _edmaram_bss;
|
||||
} >RAM
|
||||
|
||||
. = ALIGN(32);
|
||||
.DMA_RAM (NOLOAD) :
|
||||
{
|
||||
KEEP(*(.DMA_RAM))
|
||||
PROVIDE(dmaram_end = .);
|
||||
_edmaram = .;
|
||||
_dmaram_end__ = _edmaram;
|
||||
} >RAM
|
||||
|
||||
.persistent_data (NOLOAD) :
|
||||
{
|
||||
__persistent_data_start__ = .;
|
||||
*(.persistent_data)
|
||||
. = ALIGN(4);
|
||||
__persistent_data_end__ = .;
|
||||
} >RAM
|
||||
|
||||
|
||||
/* User_heap_stack section, used to check that there is enough RAM left */
|
||||
_heap_stack_end = ORIGIN(STACKRAM)+LENGTH(STACKRAM) - 8; /* 8 bytes to allow for alignment */
|
||||
_heap_stack_begin = _heap_stack_end - _Min_Stack_Size - _Min_Heap_Size;
|
||||
. = _heap_stack_begin;
|
||||
._user_heap_stack :
|
||||
{
|
||||
. = ALIGN(4);
|
||||
PROVIDE ( end = . );
|
||||
PROVIDE ( _end = . );
|
||||
. = . + _Min_Heap_Size;
|
||||
. = . + _Min_Stack_Size;
|
||||
. = ALIGN(4);
|
||||
} >STACKRAM = 0xa5
|
||||
|
||||
/* MEMORY_bank1 section, code must be located here explicitly */
|
||||
/* Example: extern int foo(void) __attribute__ ((section (".mb1text"))); */
|
||||
.memory_b1_text :
|
||||
{
|
||||
*(.mb1text) /* .mb1text sections (code) */
|
||||
*(.mb1text*) /* .mb1text* sections (code) */
|
||||
*(.mb1rodata) /* read-only data (constants) */
|
||||
*(.mb1rodata*)
|
||||
} >MEMORY_B1
|
||||
|
||||
/* Remove information from the standard libraries */
|
||||
/DISCARD/ :
|
||||
{
|
||||
libc.a ( * )
|
||||
libm.a ( * )
|
||||
libgcc.a ( * )
|
||||
}
|
||||
|
||||
.ARM.attributes 0 : { *(.ARM.attributes) }
|
||||
}
|
116
src/main/drivers/stm32/system_stm32h5xx.c
Normal file
116
src/main/drivers/stm32/system_stm32h5xx.c
Normal file
|
@ -0,0 +1,116 @@
|
|||
/*
|
||||
* This file is part of Betaflight.
|
||||
*
|
||||
* Betaflight is free software. You can redistribute this software
|
||||
* and/or modify this software under the terms of the GNU General
|
||||
* Public License as published by the Free Software Foundation,
|
||||
* either version 3 of the License, or (at your option) any later
|
||||
* version.
|
||||
*
|
||||
* Betaflight is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
|
||||
*
|
||||
* See the GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public
|
||||
* License along with this software.
|
||||
*
|
||||
* If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#include <string.h>
|
||||
#include <stdbool.h>
|
||||
#include <stdint.h>
|
||||
#include <stdlib.h>
|
||||
|
||||
#include "platform.h"
|
||||
|
||||
#include "drivers/accgyro/accgyro_mpu.h"
|
||||
#include "drivers/exti.h"
|
||||
#include "drivers/nvic.h"
|
||||
#include "drivers/persistent.h"
|
||||
#include "drivers/system.h"
|
||||
|
||||
bool isMPUSoftReset(void)
|
||||
{
|
||||
if (cachedRccCsrValue & RCC_CSR_SFTRSTF)
|
||||
return true;
|
||||
else
|
||||
return false;
|
||||
}
|
||||
|
||||
void systemInit(void)
|
||||
{
|
||||
memProtReset();
|
||||
memProtConfigure(mpuRegions, mpuRegionCount);
|
||||
|
||||
// Configure NVIC preempt/priority groups
|
||||
HAL_NVIC_SetPriorityGrouping(NVIC_PRIORITY_GROUPING);
|
||||
|
||||
// cache RCC->RSR value to use it in isMPUSoftReset() and others
|
||||
cachedRccCsrValue = RCC->CSR;
|
||||
|
||||
// Init cycle counter
|
||||
cycleCounterInit();
|
||||
}
|
||||
|
||||
void systemReset(void)
|
||||
{
|
||||
__disable_irq();
|
||||
NVIC_SystemReset();
|
||||
}
|
||||
|
||||
void systemResetToBootloader(bootloaderRequestType_e requestType)
|
||||
{
|
||||
switch (requestType) {
|
||||
case BOOTLOADER_REQUEST_ROM:
|
||||
default:
|
||||
persistentObjectWrite(PERSISTENT_OBJECT_RESET_REASON, RESET_BOOTLOADER_REQUEST_ROM);
|
||||
|
||||
break;
|
||||
}
|
||||
|
||||
__disable_irq();
|
||||
NVIC_SystemReset();
|
||||
}
|
||||
|
||||
#define SYSMEMBOOT_VECTOR_TABLE ((uint32_t *)0x1fff0000)
|
||||
#define SYSMEMBOOT_LOADER ((uint32_t *)0x1fff0000)
|
||||
|
||||
typedef void *(*bootJumpPtr)(void);
|
||||
|
||||
typedef void resetHandler_t(void);
|
||||
|
||||
typedef struct isrVector_s {
|
||||
__I uint32_t stackEnd;
|
||||
resetHandler_t *resetHandler;
|
||||
} isrVector_t;
|
||||
|
||||
void systemJumpToBootloader(void)
|
||||
{
|
||||
//DeInit all used peripherals
|
||||
HAL_RCC_DeInit();
|
||||
|
||||
//Disable all system timers and set to default values
|
||||
SysTick->CTRL = 0;
|
||||
SysTick->LOAD = 0;
|
||||
SysTick->VAL = 0;
|
||||
|
||||
//Disable all interrupts
|
||||
__disable_irq();
|
||||
|
||||
//remap system memory
|
||||
__HAL_SYSCFG_REMAPMEMORY_SYSTEMFLASH();
|
||||
|
||||
//default bootloader call stack routine
|
||||
uint32_t bootStack = SYSMEMBOOT_VECTOR_TABLE[0];
|
||||
|
||||
bootJumpPtr SysMemBootJump = (bootJumpPtr)SYSMEMBOOT_VECTOR_TABLE[1];
|
||||
|
||||
__set_MSP(bootStack); //Set the main stack pointer to its default values
|
||||
|
||||
SysMemBootJump();
|
||||
|
||||
while (1);
|
||||
}
|
701
src/main/startup/startup_stm32h563xx.s
Normal file
701
src/main/startup/startup_stm32h563xx.s
Normal file
|
@ -0,0 +1,701 @@
|
|||
/**
|
||||
******************************************************************************
|
||||
* @file startup_stm32h563xx.s
|
||||
* @author MCD Application Team
|
||||
* @brief STM32H563xx devices vector table GCC toolchain.
|
||||
* This module performs:
|
||||
* - Set the initial SP
|
||||
* - Set the initial PC == Reset_Handler,
|
||||
* - Set the vector table entries with the exceptions ISR address,
|
||||
* - Configure the clock system
|
||||
* - Branches to main in the C library (which eventually
|
||||
* calls main()).
|
||||
******************************************************************************
|
||||
* @attention
|
||||
*
|
||||
* Copyright (c) 2023 STMicroelectronics.
|
||||
* All rights reserved.
|
||||
*
|
||||
* This software is licensed under terms that can be found in the LICENSE file
|
||||
* in the root directory of this software component.
|
||||
* If no LICENSE file comes with this software, it is provided AS-IS.
|
||||
*
|
||||
******************************************************************************
|
||||
*/
|
||||
|
||||
.syntax unified
|
||||
.cpu cortex-m33
|
||||
.fpu softvfp
|
||||
.thumb
|
||||
|
||||
.global g_pfnVectors
|
||||
.global Default_Handler
|
||||
|
||||
/* start address for the initialization values of the .data section.
|
||||
defined in linker script */
|
||||
.word _sidata
|
||||
/* start address for the .data section. defined in linker script */
|
||||
.word _sdata
|
||||
/* end address for the .data section. defined in linker script */
|
||||
.word _edata
|
||||
/* start address for the .bss section. defined in linker script */
|
||||
.word _sbss
|
||||
/* end address for the .bss section. defined in linker script */
|
||||
.word _ebss
|
||||
|
||||
/**
|
||||
* @brief This is the code that gets called when the processor first
|
||||
* starts execution following a reset event. Only the absolutely
|
||||
* necessary set is performed, after which the application
|
||||
* supplied main() routine is called.
|
||||
* @param None
|
||||
* @retval : None
|
||||
*/
|
||||
|
||||
.section .text.Reset_Handler
|
||||
.weak Reset_Handler
|
||||
.type Reset_Handler, %function
|
||||
Reset_Handler:
|
||||
ldr r0, =_estack
|
||||
mov sp, r0 /* set stack pointer */
|
||||
|
||||
bl persistentObjectInit
|
||||
/* Call the clock system initialization function.*/
|
||||
bl SystemInit
|
||||
|
||||
/* Copy the data segment initializers from flash to SRAM */
|
||||
ldr r0, =_sdata
|
||||
ldr r1, =_edata
|
||||
ldr r2, =_sidata
|
||||
movs r3, #0
|
||||
b LoopCopyDataInit
|
||||
|
||||
CopyDataInit:
|
||||
ldr r4, [r2, r3]
|
||||
str r4, [r0, r3]
|
||||
adds r3, r3, #4
|
||||
|
||||
LoopCopyDataInit:
|
||||
adds r4, r0, r3
|
||||
cmp r4, r1
|
||||
bcc CopyDataInit
|
||||
|
||||
/* Zero fill the bss segment. */
|
||||
ldr r2, =_sbss
|
||||
ldr r4, =_ebss
|
||||
movs r3, #0
|
||||
b LoopFillZerobss
|
||||
|
||||
FillZerobss:
|
||||
str r3, [r2]
|
||||
adds r2, r2, #4
|
||||
|
||||
LoopFillZerobss:
|
||||
cmp r2, r4
|
||||
bcc FillZerobss
|
||||
|
||||
|
||||
/* Call static constructors */
|
||||
/* bl __libc_init_array */
|
||||
/* Call the application's entry point.*/
|
||||
bl main
|
||||
bx lr
|
||||
|
||||
LoopForever:
|
||||
b LoopForever
|
||||
|
||||
.size Reset_Handler, .-Reset_Handler
|
||||
|
||||
/**
|
||||
* @brief This is the code that gets called when the processor receives an
|
||||
* unexpected interrupt. This simply enters an infinite loop, preserving
|
||||
* the system state for examination by a debugger.
|
||||
*
|
||||
* @param None
|
||||
* @retval : None
|
||||
*/
|
||||
.section .text.Default_Handler,"ax",%progbits
|
||||
Default_Handler:
|
||||
Infinite_Loop:
|
||||
b Infinite_Loop
|
||||
.size Default_Handler, .-Default_Handler
|
||||
|
||||
/******************************************************************************
|
||||
*
|
||||
* The STM32H563xx vector table. Note that the proper constructs
|
||||
* must be placed on this to ensure that it ends up at physical address
|
||||
* 0x0000.0000.
|
||||
*
|
||||
******************************************************************************/
|
||||
.section .isr_vector,"a",%progbits
|
||||
.type g_pfnVectors, %object
|
||||
|
||||
g_pfnVectors:
|
||||
.word _estack
|
||||
.word Reset_Handler
|
||||
.word NMI_Handler
|
||||
.word HardFault_Handler
|
||||
.word MemManage_Handler
|
||||
.word BusFault_Handler
|
||||
.word UsageFault_Handler
|
||||
.word SecureFault_Handler
|
||||
.word 0
|
||||
.word 0
|
||||
.word 0
|
||||
.word SVC_Handler
|
||||
.word DebugMon_Handler
|
||||
.word 0
|
||||
.word PendSV_Handler
|
||||
.word SysTick_Handler
|
||||
.word WWDG_IRQHandler
|
||||
.word PVD_AVD_IRQHandler
|
||||
.word RTC_IRQHandler
|
||||
.word RTC_S_IRQHandler
|
||||
.word TAMP_IRQHandler
|
||||
.word RAMCFG_IRQHandler
|
||||
.word FLASH_IRQHandler
|
||||
.word FLASH_S_IRQHandler
|
||||
.word GTZC_IRQHandler
|
||||
.word RCC_IRQHandler
|
||||
.word RCC_S_IRQHandler
|
||||
.word EXTI0_IRQHandler
|
||||
.word EXTI1_IRQHandler
|
||||
.word EXTI2_IRQHandler
|
||||
.word EXTI3_IRQHandler
|
||||
.word EXTI4_IRQHandler
|
||||
.word EXTI5_IRQHandler
|
||||
.word EXTI6_IRQHandler
|
||||
.word EXTI7_IRQHandler
|
||||
.word EXTI8_IRQHandler
|
||||
.word EXTI9_IRQHandler
|
||||
.word EXTI10_IRQHandler
|
||||
.word EXTI11_IRQHandler
|
||||
.word EXTI12_IRQHandler
|
||||
.word EXTI13_IRQHandler
|
||||
.word EXTI14_IRQHandler
|
||||
.word EXTI15_IRQHandler
|
||||
.word GPDMA1_Channel0_IRQHandler
|
||||
.word GPDMA1_Channel1_IRQHandler
|
||||
.word GPDMA1_Channel2_IRQHandler
|
||||
.word GPDMA1_Channel3_IRQHandler
|
||||
.word GPDMA1_Channel4_IRQHandler
|
||||
.word GPDMA1_Channel5_IRQHandler
|
||||
.word GPDMA1_Channel6_IRQHandler
|
||||
.word GPDMA1_Channel7_IRQHandler
|
||||
.word IWDG_IRQHandler
|
||||
.word 0
|
||||
.word ADC1_IRQHandler
|
||||
.word DAC1_IRQHandler
|
||||
.word FDCAN1_IT0_IRQHandler
|
||||
.word FDCAN1_IT1_IRQHandler
|
||||
.word TIM1_BRK_IRQHandler
|
||||
.word TIM1_UP_IRQHandler
|
||||
.word TIM1_TRG_COM_IRQHandler
|
||||
.word TIM1_CC_IRQHandler
|
||||
.word TIM2_IRQHandler
|
||||
.word TIM3_IRQHandler
|
||||
.word TIM4_IRQHandler
|
||||
.word TIM5_IRQHandler
|
||||
.word TIM6_IRQHandler
|
||||
.word TIM7_IRQHandler
|
||||
.word I2C1_EV_IRQHandler
|
||||
.word I2C1_ER_IRQHandler
|
||||
.word I2C2_EV_IRQHandler
|
||||
.word I2C2_ER_IRQHandler
|
||||
.word SPI1_IRQHandler
|
||||
.word SPI2_IRQHandler
|
||||
.word SPI3_IRQHandler
|
||||
.word USART1_IRQHandler
|
||||
.word USART2_IRQHandler
|
||||
.word USART3_IRQHandler
|
||||
.word UART4_IRQHandler
|
||||
.word UART5_IRQHandler
|
||||
.word LPUART1_IRQHandler
|
||||
.word LPTIM1_IRQHandler
|
||||
.word TIM8_BRK_IRQHandler
|
||||
.word TIM8_UP_IRQHandler
|
||||
.word TIM8_TRG_COM_IRQHandler
|
||||
.word TIM8_CC_IRQHandler
|
||||
.word ADC2_IRQHandler
|
||||
.word LPTIM2_IRQHandler
|
||||
.word TIM15_IRQHandler
|
||||
.word TIM16_IRQHandler
|
||||
.word TIM17_IRQHandler
|
||||
.word USB_DRD_FS_IRQHandler
|
||||
.word CRS_IRQHandler
|
||||
.word UCPD1_IRQHandler
|
||||
.word FMC_IRQHandler
|
||||
.word OCTOSPI1_IRQHandler
|
||||
.word SDMMC1_IRQHandler
|
||||
.word I2C3_EV_IRQHandler
|
||||
.word I2C3_ER_IRQHandler
|
||||
.word SPI4_IRQHandler
|
||||
.word SPI5_IRQHandler
|
||||
.word SPI6_IRQHandler
|
||||
.word USART6_IRQHandler
|
||||
.word USART10_IRQHandler
|
||||
.word USART11_IRQHandler
|
||||
.word SAI1_IRQHandler
|
||||
.word SAI2_IRQHandler
|
||||
.word GPDMA2_Channel0_IRQHandler
|
||||
.word GPDMA2_Channel1_IRQHandler
|
||||
.word GPDMA2_Channel2_IRQHandler
|
||||
.word GPDMA2_Channel3_IRQHandler
|
||||
.word GPDMA2_Channel4_IRQHandler
|
||||
.word GPDMA2_Channel5_IRQHandler
|
||||
.word GPDMA2_Channel6_IRQHandler
|
||||
.word GPDMA2_Channel7_IRQHandler
|
||||
.word UART7_IRQHandler
|
||||
.word UART8_IRQHandler
|
||||
.word UART9_IRQHandler
|
||||
.word UART12_IRQHandler
|
||||
.word SDMMC2_IRQHandler
|
||||
.word FPU_IRQHandler
|
||||
.word ICACHE_IRQHandler
|
||||
.word DCACHE1_IRQHandler
|
||||
.word ETH_IRQHandler
|
||||
.word ETH_WKUP_IRQHandler
|
||||
.word DCMI_PSSI_IRQHandler
|
||||
.word FDCAN2_IT0_IRQHandler
|
||||
.word FDCAN2_IT1_IRQHandler
|
||||
.word CORDIC_IRQHandler
|
||||
.word FMAC_IRQHandler
|
||||
.word DTS_IRQHandler
|
||||
.word RNG_IRQHandler
|
||||
.word 0
|
||||
.word 0
|
||||
.word HASH_IRQHandler
|
||||
.word 0
|
||||
.word CEC_IRQHandler
|
||||
.word TIM12_IRQHandler
|
||||
.word TIM13_IRQHandler
|
||||
.word TIM14_IRQHandler
|
||||
.word I3C1_EV_IRQHandler
|
||||
.word I3C1_ER_IRQHandler
|
||||
.word I2C4_EV_IRQHandler
|
||||
.word I2C4_ER_IRQHandler
|
||||
.word LPTIM3_IRQHandler
|
||||
.word LPTIM4_IRQHandler
|
||||
.word LPTIM5_IRQHandler
|
||||
.word LPTIM6_IRQHandler
|
||||
|
||||
.size g_pfnVectors, .-g_pfnVectors
|
||||
|
||||
/*******************************************************************************
|
||||
*
|
||||
* Provide weak aliases for each Exception handler to the Default_Handler.
|
||||
* As they are weak aliases, any function with the same name will override
|
||||
* this definition.
|
||||
*
|
||||
*******************************************************************************/
|
||||
|
||||
.weak NMI_Handler
|
||||
.thumb_set NMI_Handler,Default_Handler
|
||||
|
||||
.weak HardFault_Handler
|
||||
.thumb_set HardFault_Handler,Default_Handler
|
||||
|
||||
.weak MemManage_Handler
|
||||
.thumb_set MemManage_Handler,Default_Handler
|
||||
|
||||
.weak BusFault_Handler
|
||||
.thumb_set BusFault_Handler,Default_Handler
|
||||
|
||||
.weak UsageFault_Handler
|
||||
.thumb_set UsageFault_Handler,Default_Handler
|
||||
|
||||
.weak SecureFault_Handler
|
||||
.thumb_set SecureFault_Handler,Default_Handler
|
||||
|
||||
.weak SVC_Handler
|
||||
.thumb_set SVC_Handler,Default_Handler
|
||||
|
||||
.weak DebugMon_Handler
|
||||
.thumb_set DebugMon_Handler,Default_Handler
|
||||
|
||||
.weak PendSV_Handler
|
||||
.thumb_set PendSV_Handler,Default_Handler
|
||||
|
||||
.weak SysTick_Handler
|
||||
.thumb_set SysTick_Handler,Default_Handler
|
||||
|
||||
.weak WWDG_IRQHandler
|
||||
.thumb_set WWDG_IRQHandler,Default_Handler
|
||||
|
||||
.weak PVD_AVD_IRQHandler
|
||||
.thumb_set PVD_AVD_IRQHandler,Default_Handler
|
||||
|
||||
.weak RTC_IRQHandler
|
||||
.thumb_set RTC_IRQHandler,Default_Handler
|
||||
|
||||
.weak RTC_S_IRQHandler
|
||||
.thumb_set RTC_S_IRQHandler,Default_Handler
|
||||
|
||||
.weak TAMP_IRQHandler
|
||||
.thumb_set TAMP_IRQHandler,Default_Handler
|
||||
|
||||
.weak RAMCFG_IRQHandler
|
||||
.thumb_set RAMCFG_IRQHandler,Default_Handler
|
||||
|
||||
.weak FLASH_IRQHandler
|
||||
.thumb_set FLASH_IRQHandler,Default_Handler
|
||||
|
||||
.weak FLASH_S_IRQHandler
|
||||
.thumb_set FLASH_S_IRQHandler,Default_Handler
|
||||
|
||||
.weak GTZC_IRQHandler
|
||||
.thumb_set GTZC_IRQHandler,Default_Handler
|
||||
|
||||
.weak RCC_IRQHandler
|
||||
.thumb_set RCC_IRQHandler,Default_Handler
|
||||
|
||||
.weak RCC_S_IRQHandler
|
||||
.thumb_set RCC_S_IRQHandler,Default_Handler
|
||||
|
||||
.weak EXTI0_IRQHandler
|
||||
.thumb_set EXTI0_IRQHandler,Default_Handler
|
||||
|
||||
.weak EXTI1_IRQHandler
|
||||
.thumb_set EXTI1_IRQHandler,Default_Handler
|
||||
|
||||
.weak EXTI2_IRQHandler
|
||||
.thumb_set EXTI2_IRQHandler,Default_Handler
|
||||
|
||||
.weak EXTI3_IRQHandler
|
||||
.thumb_set EXTI3_IRQHandler,Default_Handler
|
||||
|
||||
.weak EXTI4_IRQHandler
|
||||
.thumb_set EXTI4_IRQHandler,Default_Handler
|
||||
|
||||
.weak EXTI5_IRQHandler
|
||||
.thumb_set EXTI5_IRQHandler,Default_Handler
|
||||
|
||||
.weak EXTI6_IRQHandler
|
||||
.thumb_set EXTI6_IRQHandler,Default_Handler
|
||||
|
||||
.weak EXTI7_IRQHandler
|
||||
.thumb_set EXTI7_IRQHandler,Default_Handler
|
||||
|
||||
.weak EXTI8_IRQHandler
|
||||
.thumb_set EXTI8_IRQHandler,Default_Handler
|
||||
|
||||
.weak EXTI9_IRQHandler
|
||||
.thumb_set EXTI9_IRQHandler,Default_Handler
|
||||
|
||||
.weak EXTI10_IRQHandler
|
||||
.thumb_set EXTI10_IRQHandler,Default_Handler
|
||||
|
||||
.weak EXTI11_IRQHandler
|
||||
.thumb_set EXTI11_IRQHandler,Default_Handler
|
||||
|
||||
.weak EXTI12_IRQHandler
|
||||
.thumb_set EXTI12_IRQHandler,Default_Handler
|
||||
|
||||
.weak EXTI13_IRQHandler
|
||||
.thumb_set EXTI13_IRQHandler,Default_Handler
|
||||
|
||||
.weak EXTI14_IRQHandler
|
||||
.thumb_set EXTI14_IRQHandler,Default_Handler
|
||||
|
||||
.weak EXTI15_IRQHandler
|
||||
.thumb_set EXTI15_IRQHandler,Default_Handler
|
||||
|
||||
.weak GPDMA1_Channel0_IRQHandler
|
||||
.thumb_set GPDMA1_Channel0_IRQHandler,Default_Handler
|
||||
|
||||
.weak GPDMA1_Channel1_IRQHandler
|
||||
.thumb_set GPDMA1_Channel1_IRQHandler,Default_Handler
|
||||
|
||||
.weak GPDMA1_Channel2_IRQHandler
|
||||
.thumb_set GPDMA1_Channel2_IRQHandler,Default_Handler
|
||||
|
||||
.weak GPDMA1_Channel3_IRQHandler
|
||||
.thumb_set GPDMA1_Channel3_IRQHandler,Default_Handler
|
||||
|
||||
.weak GPDMA1_Channel4_IRQHandler
|
||||
.thumb_set GPDMA1_Channel4_IRQHandler,Default_Handler
|
||||
|
||||
.weak GPDMA1_Channel5_IRQHandler
|
||||
.thumb_set GPDMA1_Channel5_IRQHandler,Default_Handler
|
||||
|
||||
.weak GPDMA1_Channel6_IRQHandler
|
||||
.thumb_set GPDMA1_Channel6_IRQHandler,Default_Handler
|
||||
|
||||
.weak GPDMA1_Channel7_IRQHandler
|
||||
.thumb_set GPDMA1_Channel7_IRQHandler,Default_Handler
|
||||
|
||||
.weak IWDG_IRQHandler
|
||||
.thumb_set IWDG_IRQHandler,Default_Handler
|
||||
|
||||
.weak ADC1_IRQHandler
|
||||
.thumb_set ADC1_IRQHandler,Default_Handler
|
||||
|
||||
.weak DAC1_IRQHandler
|
||||
.thumb_set DAC1_IRQHandler,Default_Handler
|
||||
|
||||
.weak FDCAN1_IT0_IRQHandler
|
||||
.thumb_set FDCAN1_IT0_IRQHandler,Default_Handler
|
||||
|
||||
.weak FDCAN1_IT1_IRQHandler
|
||||
.thumb_set FDCAN1_IT1_IRQHandler,Default_Handler
|
||||
|
||||
.weak TIM1_BRK_IRQHandler
|
||||
.thumb_set TIM1_BRK_IRQHandler,Default_Handler
|
||||
|
||||
.weak TIM1_UP_IRQHandler
|
||||
.thumb_set TIM1_UP_IRQHandler,Default_Handler
|
||||
|
||||
.weak TIM1_TRG_COM_IRQHandler
|
||||
.thumb_set TIM1_TRG_COM_IRQHandler,Default_Handler
|
||||
|
||||
.weak TIM1_CC_IRQHandler
|
||||
.thumb_set TIM1_CC_IRQHandler,Default_Handler
|
||||
|
||||
.weak TIM2_IRQHandler
|
||||
.thumb_set TIM2_IRQHandler,Default_Handler
|
||||
|
||||
.weak TIM3_IRQHandler
|
||||
.thumb_set TIM3_IRQHandler,Default_Handler
|
||||
|
||||
.weak TIM4_IRQHandler
|
||||
.thumb_set TIM4_IRQHandler,Default_Handler
|
||||
|
||||
.weak TIM5_IRQHandler
|
||||
.thumb_set TIM5_IRQHandler,Default_Handler
|
||||
|
||||
.weak TIM6_IRQHandler
|
||||
.thumb_set TIM6_IRQHandler,Default_Handler
|
||||
|
||||
.weak TIM7_IRQHandler
|
||||
.thumb_set TIM7_IRQHandler,Default_Handler
|
||||
|
||||
.weak I2C1_EV_IRQHandler
|
||||
.thumb_set I2C1_EV_IRQHandler,Default_Handler
|
||||
|
||||
.weak I2C1_ER_IRQHandler
|
||||
.thumb_set I2C1_ER_IRQHandler,Default_Handler
|
||||
|
||||
.weak I2C2_EV_IRQHandler
|
||||
.thumb_set I2C2_EV_IRQHandler,Default_Handler
|
||||
|
||||
.weak I2C2_ER_IRQHandler
|
||||
.thumb_set I2C2_ER_IRQHandler,Default_Handler
|
||||
|
||||
.weak SPI1_IRQHandler
|
||||
.thumb_set SPI1_IRQHandler,Default_Handler
|
||||
|
||||
.weak SPI2_IRQHandler
|
||||
.thumb_set SPI2_IRQHandler,Default_Handler
|
||||
|
||||
.weak SPI3_IRQHandler
|
||||
.thumb_set SPI3_IRQHandler,Default_Handler
|
||||
|
||||
.weak USART1_IRQHandler
|
||||
.thumb_set USART1_IRQHandler,Default_Handler
|
||||
|
||||
.weak USART2_IRQHandler
|
||||
.thumb_set USART2_IRQHandler,Default_Handler
|
||||
|
||||
.weak USART3_IRQHandler
|
||||
.thumb_set USART3_IRQHandler,Default_Handler
|
||||
|
||||
.weak UART4_IRQHandler
|
||||
.thumb_set UART4_IRQHandler,Default_Handler
|
||||
|
||||
.weak UART5_IRQHandler
|
||||
.thumb_set UART5_IRQHandler,Default_Handler
|
||||
|
||||
.weak LPUART1_IRQHandler
|
||||
.thumb_set LPUART1_IRQHandler,Default_Handler
|
||||
|
||||
.weak LPTIM1_IRQHandler
|
||||
.thumb_set LPTIM1_IRQHandler,Default_Handler
|
||||
|
||||
.weak TIM8_BRK_IRQHandler
|
||||
.thumb_set TIM8_BRK_IRQHandler,Default_Handler
|
||||
|
||||
.weak TIM8_UP_IRQHandler
|
||||
.thumb_set TIM8_UP_IRQHandler,Default_Handler
|
||||
|
||||
.weak TIM8_TRG_COM_IRQHandler
|
||||
.thumb_set TIM8_TRG_COM_IRQHandler,Default_Handler
|
||||
|
||||
.weak TIM8_CC_IRQHandler
|
||||
.thumb_set TIM8_CC_IRQHandler,Default_Handler
|
||||
|
||||
.weak ADC2_IRQHandler
|
||||
.thumb_set ADC2_IRQHandler,Default_Handler
|
||||
|
||||
.weak LPTIM2_IRQHandler
|
||||
.thumb_set LPTIM2_IRQHandler,Default_Handler
|
||||
|
||||
.weak TIM15_IRQHandler
|
||||
.thumb_set TIM15_IRQHandler,Default_Handler
|
||||
|
||||
.weak TIM16_IRQHandler
|
||||
.thumb_set TIM16_IRQHandler,Default_Handler
|
||||
|
||||
.weak TIM17_IRQHandler
|
||||
.thumb_set TIM17_IRQHandler,Default_Handler
|
||||
|
||||
.weak USB_DRD_FS_IRQHandler
|
||||
.thumb_set USB_DRD_FS_IRQHandler,Default_Handler
|
||||
|
||||
.weak CRS_IRQHandler
|
||||
.thumb_set CRS_IRQHandler,Default_Handler
|
||||
|
||||
.weak UCPD1_IRQHandler
|
||||
.thumb_set UCPD1_IRQHandler,Default_Handler
|
||||
|
||||
.weak FMC_IRQHandler
|
||||
.thumb_set FMC_IRQHandler,Default_Handler
|
||||
|
||||
.weak OCTOSPI1_IRQHandler
|
||||
.thumb_set OCTOSPI1_IRQHandler,Default_Handler
|
||||
|
||||
.weak SDMMC1_IRQHandler
|
||||
.thumb_set SDMMC1_IRQHandler,Default_Handler
|
||||
|
||||
.weak I2C3_EV_IRQHandler
|
||||
.thumb_set I2C3_EV_IRQHandler,Default_Handler
|
||||
|
||||
.weak I2C3_ER_IRQHandler
|
||||
.thumb_set I2C3_ER_IRQHandler,Default_Handler
|
||||
|
||||
.weak SPI4_IRQHandler
|
||||
.thumb_set SPI4_IRQHandler,Default_Handler
|
||||
|
||||
.weak SPI5_IRQHandler
|
||||
.thumb_set SPI5_IRQHandler,Default_Handler
|
||||
|
||||
.weak SPI6_IRQHandler
|
||||
.thumb_set SPI6_IRQHandler,Default_Handler
|
||||
|
||||
.weak USART6_IRQHandler
|
||||
.thumb_set USART6_IRQHandler,Default_Handler
|
||||
|
||||
.weak USART10_IRQHandler
|
||||
.thumb_set USART10_IRQHandler,Default_Handler
|
||||
|
||||
.weak USART11_IRQHandler
|
||||
.thumb_set USART11_IRQHandler,Default_Handler
|
||||
|
||||
.weak SAI1_IRQHandler
|
||||
.thumb_set SAI1_IRQHandler,Default_Handler
|
||||
|
||||
.weak SAI2_IRQHandler
|
||||
.thumb_set SAI2_IRQHandler,Default_Handler
|
||||
|
||||
.weak GPDMA2_Channel0_IRQHandler
|
||||
.thumb_set GPDMA2_Channel0_IRQHandler,Default_Handler
|
||||
|
||||
.weak GPDMA2_Channel1_IRQHandler
|
||||
.thumb_set GPDMA2_Channel1_IRQHandler,Default_Handler
|
||||
|
||||
.weak GPDMA2_Channel2_IRQHandler
|
||||
.thumb_set GPDMA2_Channel2_IRQHandler,Default_Handler
|
||||
|
||||
.weak GPDMA2_Channel3_IRQHandler
|
||||
.thumb_set GPDMA2_Channel3_IRQHandler,Default_Handler
|
||||
|
||||
.weak GPDMA2_Channel4_IRQHandler
|
||||
.thumb_set GPDMA2_Channel4_IRQHandler,Default_Handler
|
||||
|
||||
.weak GPDMA2_Channel5_IRQHandler
|
||||
.thumb_set GPDMA2_Channel5_IRQHandler,Default_Handler
|
||||
|
||||
.weak GPDMA2_Channel6_IRQHandler
|
||||
.thumb_set GPDMA2_Channel6_IRQHandler,Default_Handler
|
||||
|
||||
.weak GPDMA2_Channel7_IRQHandler
|
||||
.thumb_set GPDMA2_Channel7_IRQHandler,Default_Handler
|
||||
|
||||
.weak UART7_IRQHandler
|
||||
.thumb_set UART7_IRQHandler,Default_Handler
|
||||
|
||||
.weak UART8_IRQHandler
|
||||
.thumb_set UART8_IRQHandler,Default_Handler
|
||||
|
||||
.weak UART9_IRQHandler
|
||||
.thumb_set UART9_IRQHandler,Default_Handler
|
||||
|
||||
.weak UART12_IRQHandler
|
||||
.thumb_set UART12_IRQHandler,Default_Handler
|
||||
|
||||
.weak SDMMC2_IRQHandler
|
||||
.thumb_set SDMMC2_IRQHandler,Default_Handler
|
||||
|
||||
.weak FPU_IRQHandler
|
||||
.thumb_set FPU_IRQHandler,Default_Handler
|
||||
|
||||
.weak ICACHE_IRQHandler
|
||||
.thumb_set ICACHE_IRQHandler,Default_Handler
|
||||
|
||||
.weak DCACHE1_IRQHandler
|
||||
.thumb_set DCACHE1_IRQHandler,Default_Handler
|
||||
|
||||
.weak ETH_IRQHandler
|
||||
.thumb_set ETH_IRQHandler,Default_Handler
|
||||
|
||||
.weak ETH_WKUP_IRQHandler
|
||||
.thumb_set ETH_WKUP_IRQHandler,Default_Handler
|
||||
|
||||
.weak DCMI_PSSI_IRQHandler
|
||||
.thumb_set DCMI_PSSI_IRQHandler,Default_Handler
|
||||
|
||||
.weak FDCAN2_IT0_IRQHandler
|
||||
.thumb_set FDCAN2_IT0_IRQHandler,Default_Handler
|
||||
|
||||
.weak FDCAN2_IT1_IRQHandler
|
||||
.thumb_set FDCAN2_IT1_IRQHandler,Default_Handler
|
||||
|
||||
.weak CORDIC_IRQHandler
|
||||
.thumb_set CORDIC_IRQHandler,Default_Handler
|
||||
|
||||
.weak FMAC_IRQHandler
|
||||
.thumb_set FMAC_IRQHandler,Default_Handler
|
||||
|
||||
.weak DTS_IRQHandler
|
||||
.thumb_set DTS_IRQHandler,Default_Handler
|
||||
|
||||
.weak RNG_IRQHandler
|
||||
.thumb_set RNG_IRQHandler,Default_Handler
|
||||
|
||||
.weak HASH_IRQHandler
|
||||
.thumb_set HASH_IRQHandler,Default_Handler
|
||||
|
||||
.weak CEC_IRQHandler
|
||||
.thumb_set CEC_IRQHandler,Default_Handler
|
||||
|
||||
.weak TIM12_IRQHandler
|
||||
.thumb_set TIM12_IRQHandler,Default_Handler
|
||||
|
||||
.weak TIM13_IRQHandler
|
||||
.thumb_set TIM13_IRQHandler,Default_Handler
|
||||
|
||||
.weak TIM14_IRQHandler
|
||||
.thumb_set TIM14_IRQHandler,Default_Handler
|
||||
|
||||
.weak I3C1_EV_IRQHandler
|
||||
.thumb_set I3C1_EV_IRQHandler,Default_Handler
|
||||
|
||||
.weak I3C1_ER_IRQHandler
|
||||
.thumb_set I3C1_ER_IRQHandler,Default_Handler
|
||||
|
||||
.weak I2C4_EV_IRQHandler
|
||||
.thumb_set I2C4_EV_IRQHandler,Default_Handler
|
||||
|
||||
.weak I2C4_ER_IRQHandler
|
||||
.thumb_set I2C4_ER_IRQHandler,Default_Handler
|
||||
|
||||
.weak LPTIM3_IRQHandler
|
||||
.thumb_set LPTIM3_IRQHandler,Default_Handler
|
||||
|
||||
.weak LPTIM4_IRQHandler
|
||||
.thumb_set LPTIM4_IRQHandler,Default_Handler
|
||||
|
||||
.weak LPTIM5_IRQHandler
|
||||
.thumb_set LPTIM5_IRQHandler,Default_Handler
|
||||
|
||||
.weak LPTIM6_IRQHandler
|
||||
.thumb_set LPTIM6_IRQHandler,Default_Handler
|
488
src/main/startup/stm32h5xx_hal_conf.h
Normal file
488
src/main/startup/stm32h5xx_hal_conf.h
Normal file
|
@ -0,0 +1,488 @@
|
|||
/**
|
||||
**********************************************************************************************************************
|
||||
* @file stm32h5xx_hal_conf_template.h
|
||||
* @author MCD Application Team
|
||||
* @brief HAL configuration template file.
|
||||
* This file should be copied to the application folder and renamed
|
||||
* to stm32h5xx_hal_conf.h.
|
||||
**********************************************************************************************************************
|
||||
* @attention
|
||||
*
|
||||
* Copyright (c) 2023 STMicroelectronics.
|
||||
* All rights reserved.
|
||||
*
|
||||
* This software is licensed under terms that can be found in the LICENSE file
|
||||
* in the root directory of this software component.
|
||||
* If no LICENSE file comes with this software, it is provided AS-IS.
|
||||
*
|
||||
**********************************************************************************************************************
|
||||
*/
|
||||
|
||||
/* Define to prevent recursive inclusion -----------------------------------------------------------------------------*/
|
||||
#ifndef STM32H5xx_HAL_CONF_H
|
||||
#define STM32H5xx_HAL_CONF_H
|
||||
|
||||
#ifdef __cplusplus
|
||||
extern "C" {
|
||||
#endif
|
||||
|
||||
/* Exported types ----------------------------------------------------------------------------------------------------*/
|
||||
/* Exported constants ------------------------------------------------------------------------------------------------*/
|
||||
|
||||
/* ########################################### Module Selection ##################################################### */
|
||||
/**
|
||||
* @brief This is the list of modules to be used in the HAL driver
|
||||
*/
|
||||
#define HAL_MODULE_ENABLED
|
||||
#define HAL_ADC_MODULE_ENABLED
|
||||
//#define HAL_CEC_MODULE_ENABLED
|
||||
//#define HAL_COMP_MODULE_ENABLED
|
||||
//#define HAL_CORDIC_MODULE_ENABLED
|
||||
#define HAL_CORTEX_MODULE_ENABLED
|
||||
//#define HAL_CRC_MODULE_ENABLED
|
||||
//#define HAL_CRYP_MODULE_ENABLED
|
||||
#define HAL_DAC_MODULE_ENABLED
|
||||
//#define HAL_DCACHE_MODULE_ENABLED
|
||||
//#define HAL_DCMI_MODULE_ENABLED
|
||||
#define HAL_DMA_MODULE_ENABLED
|
||||
//#define HAL_DTS_MODULE_ENABLED
|
||||
//#define HAL_EXTI_MODULE_ENABLED
|
||||
//#define HAL_ETH_MODULE_ENABLED
|
||||
//#define HAL_FDCAN_MODULE_ENABLED
|
||||
#define HAL_FLASH_MODULE_ENABLED
|
||||
//#define HAL_FMAC_MODULE_ENABLED
|
||||
#define HAL_GPIO_MODULE_ENABLED
|
||||
//#define HAL_GTZC_MODULE_ENABLED
|
||||
//#define HAL_HASH_MODULE_ENABLED
|
||||
//#define HAL_HCD_MODULE_ENABLED
|
||||
#define HAL_I2C_MODULE_ENABLED
|
||||
//#define HAL_I2S_MODULE_ENABLED
|
||||
//#define HAL_I3C_MODULE_ENABLED
|
||||
//#define HAL_ICACHE_MODULE_ENABLED
|
||||
//#define HAL_IRDA_MODULE_ENABLED
|
||||
//#define HAL_IWDG_MODULE_ENABLED
|
||||
//#define HAL_LPTIM_MODULE_ENABLED
|
||||
//#define HAL_MMC_MODULE_ENABLED
|
||||
//#define HAL_NAND_MODULE_ENABLED
|
||||
//#define HAL_NOR_MODULE_ENABLED
|
||||
//#define HAL_OTFDEC_MODULE_ENABLED
|
||||
//#define HAL_OPAMP_MODULE_ENABLED
|
||||
#define HAL_PCD_MODULE_ENABLED
|
||||
//#define HAL_PKA_MODULE_ENABLED
|
||||
//#define HAL_PSSI_MODULE_ENABLED
|
||||
#define HAL_PWR_MODULE_ENABLED
|
||||
//#define HAL_RAMCFG_MODULE_ENABLED
|
||||
#define HAL_RCC_MODULE_ENABLED
|
||||
//#define HAL_RNG_MODULE_ENABLED
|
||||
#define HAL_RTC_MODULE_ENABLED
|
||||
//#define HAL_SAI_MODULE_ENABLED
|
||||
#define HAL_SD_MODULE_ENABLED
|
||||
//#define HAL_SDRAM_MODULE_ENABLED
|
||||
//#define HAL_SMARTCARD_MODULE_ENABLED
|
||||
//#define HAL_SMBUS_MODULE_ENABLED
|
||||
//#define HAL_SPI_MODULE_ENABLED
|
||||
//#define HAL_SRAM_MODULE_ENABLED
|
||||
#define HAL_TIM_MODULE_ENABLED
|
||||
#define HAL_UART_MODULE_ENABLED
|
||||
#define HAL_USART_MODULE_ENABLED
|
||||
//#define HAL_WWDG_MODULE_ENABLED
|
||||
//#define HAL_XSPI_MODULE_ENABLED
|
||||
|
||||
/* ####################################### Oscillator Values adaptation ##############################################*/
|
||||
/**
|
||||
* @brief Adjust the value of External High Speed oscillator (HSE) used in your application.
|
||||
* This value is used by the RCC HAL module to compute the system frequency
|
||||
* (when HSE is used as system clock source, directly or through the PLL).
|
||||
*/
|
||||
#if !defined (HSE_VALUE)
|
||||
#define HSE_VALUE 25000000UL /*!< Value of the External oscillator in Hz */
|
||||
#endif /* HSE_VALUE */
|
||||
|
||||
#if !defined (HSE_STARTUP_TIMEOUT)
|
||||
#define HSE_STARTUP_TIMEOUT 100UL /*!< Time out for HSE start up, in ms */
|
||||
#endif /* HSE_STARTUP_TIMEOUT */
|
||||
|
||||
/**
|
||||
* @brief Internal Core Speed oscillator (CSI) value.
|
||||
* This value is used by the RCC HAL module to compute the system frequency
|
||||
* (when CSI is used as system clock source, directly or through the PLL).
|
||||
*/
|
||||
#if !defined (CSI_VALUE)
|
||||
#define CSI_VALUE 4000000UL /*!< Value of the Internal oscillator in Hz*/
|
||||
#endif /* CSI_VALUE */
|
||||
|
||||
/**
|
||||
* @brief Internal High Speed oscillator (HSI) value.
|
||||
* This value is used by the RCC HAL module to compute the system frequency
|
||||
* (when HSI is used as system clock source, directly or through the PLL).
|
||||
*/
|
||||
#if !defined (HSI_VALUE)
|
||||
#define HSI_VALUE 64000000UL /*!< Value of the Internal oscillator in Hz*/
|
||||
#endif /* HSI_VALUE */
|
||||
|
||||
/**
|
||||
* @brief Internal High Speed oscillator (HSI48) value for USB FS, SDMMC and RNG.
|
||||
* This internal oscillator is mainly dedicated to provide a high precision clock to
|
||||
* the USB peripheral by means of a special Clock Recovery System (CRS) circuitry.
|
||||
* When the CRS is not used, the HSI48 RC oscillator runs on it default frequency
|
||||
* which is subject to manufacturing process variations.
|
||||
*/
|
||||
#if !defined (HSI48_VALUE)
|
||||
#define HSI48_VALUE 48000000UL /*!< Value of the Internal High Speed oscillator for USB FS/SDMMC/RNG in Hz.
|
||||
The real value my vary depending on manufacturing process variations.*/
|
||||
#endif /* HSI48_VALUE */
|
||||
|
||||
/**
|
||||
* @brief Internal Low Speed oscillator (LSI) value.
|
||||
*/
|
||||
#if !defined (LSI_VALUE)
|
||||
#define LSI_VALUE 32000UL /*!< LSI Typical Value in Hz*/
|
||||
#endif /* LSI_VALUE */ /*!< Value of the Internal Low Speed oscillator in Hz
|
||||
The real value may vary depending on the variations
|
||||
in voltage and temperature.*/
|
||||
|
||||
#if !defined (LSI_STARTUP_TIME)
|
||||
#define LSI_STARTUP_TIME 130UL /*!< Time out for LSI start up, in us */
|
||||
#endif /* LSI_STARTUP_TIME */
|
||||
|
||||
/**
|
||||
* @brief External Low Speed oscillator (LSE) value.
|
||||
* This value is used by the UART, RTC HAL module to compute the system frequency
|
||||
*/
|
||||
#if !defined (LSE_VALUE)
|
||||
#define LSE_VALUE 32768UL /*!< Value of the External oscillator in Hz*/
|
||||
#endif /* LSE_VALUE */
|
||||
|
||||
#if !defined (LSE_STARTUP_TIMEOUT)
|
||||
#define LSE_STARTUP_TIMEOUT 5000UL /*!< Time out for LSE start up, in ms */
|
||||
#endif /* LSE_STARTUP_TIMEOUT */
|
||||
|
||||
|
||||
/**
|
||||
* @brief External clock source for SPI/SAI peripheral
|
||||
* This value is used by the SPI/SAI HAL module to compute the SPI/SAI clock source
|
||||
* frequency, this source is inserted directly through I2S_CKIN pad.
|
||||
*/
|
||||
#if !defined (EXTERNAL_CLOCK_VALUE)
|
||||
#define EXTERNAL_CLOCK_VALUE 12288000UL /*!< Value of the External clock in Hz*/
|
||||
#endif /* EXTERNAL_CLOCK_VALUE */
|
||||
|
||||
/* Tip: To avoid modifying this file each time you need to use different HSE,
|
||||
=== you can define the HSE value in your toolchain compiler preprocessor. */
|
||||
|
||||
/* ############################################ System Configuration ################################################ */
|
||||
/**
|
||||
* @brief This is the HAL system configuration section
|
||||
*/
|
||||
#define VDD_VALUE 3300UL /*!< Value of VDD in mv */
|
||||
#define TICK_INT_PRIORITY ((1UL<<__NVIC_PRIO_BITS) - 1UL) /*!< tick interrupt priority (lowest by default) */
|
||||
#define USE_RTOS 0U
|
||||
#define PREFETCH_ENABLE 0U /*!< Enable prefetch */
|
||||
|
||||
/* ############################################ Assert Selection #################################################### */
|
||||
/**
|
||||
* @brief Uncomment the line below to expanse the "assert_param" macro in the
|
||||
* HAL drivers code
|
||||
*/
|
||||
/* #define USE_FULL_ASSERT 1U */
|
||||
|
||||
/* ############################################ Register callback feature configuration ############################# */
|
||||
/**
|
||||
* @brief Set below the peripheral configuration to "1U" to add the support
|
||||
* of HAL callback registration/unregistration feature for the HAL
|
||||
* driver(s). This allows user application to provide specific callback
|
||||
* functions thanks to HAL_PPP_RegisterCallback() rather than overwriting
|
||||
* the default weak callback functions (see each stm32h5xx_hal_ppp.h file
|
||||
* for possible callback identifiers defined in HAL_PPP_CallbackIDTypeDef
|
||||
* for each PPP peripheral).
|
||||
*/
|
||||
#define USE_HAL_ADC_REGISTER_CALLBACKS 0U /* ADC register callback disabled */
|
||||
#define USE_HAL_CEC_REGISTER_CALLBACKS 0U /* CEC register callback disabled */
|
||||
#define USE_HAL_COMP_REGISTER_CALLBACKS 0U /* COMP register callback disabled */
|
||||
#define USE_HAL_CORDIC_REGISTER_CALLBACKS 0U /* CORDIC register callback disabled */
|
||||
#define USE_HAL_CRYP_REGISTER_CALLBACKS 0U /* CRYP register callback disabled */
|
||||
#define USE_HAL_DAC_REGISTER_CALLBACKS 0U /* DAC register callback disabled */
|
||||
#define USE_HAL_DCMI_REGISTER_CALLBACKS 0U /* DCMI register callback disabled */
|
||||
#define USE_HAL_DTS_REGISTER_CALLBACKS 0U /* DTS register callback disabled */
|
||||
#define USE_HAL_ETH_REGISTER_CALLBACKS 0U /* ETH register callback disabled */
|
||||
#define USE_HAL_FDCAN_REGISTER_CALLBACKS 0U /* FDCAN register callback disabled */
|
||||
#define USE_HAL_FMAC_REGISTER_CALLBACKS 0U /* FMAC register callback disabled */
|
||||
#define USE_HAL_NOR_REGISTER_CALLBACKS 0U /* NOR register callback disabled */
|
||||
#define USE_HAL_HASH_REGISTER_CALLBACKS 0U /* HASH register callback disabled */
|
||||
#define USE_HAL_HCD_REGISTER_CALLBACKS 0U /* HCD register callback disabled */
|
||||
#define USE_HAL_I2C_REGISTER_CALLBACKS 0U /* I2C register callback disabled */
|
||||
#define USE_HAL_I2S_REGISTER_CALLBACKS 0U /* I2S register callback disabled */
|
||||
#define USE_HAL_I3C_REGISTER_CALLBACKS 0U /* I3C register callback disabled */
|
||||
#define USE_HAL_IRDA_REGISTER_CALLBACKS 0U /* IRDA register callback disabled */
|
||||
#define USE_HAL_IWDG_REGISTER_CALLBACKS 0U /* IWDG register callback disabled */
|
||||
#define USE_HAL_LPTIM_REGISTER_CALLBACKS 0U /* LPTIM register callback disabled */
|
||||
#define USE_HAL_MMC_REGISTER_CALLBACKS 0U /* MMC register callback disabled */
|
||||
#define USE_HAL_NAND_REGISTER_CALLBACKS 0U /* NAND register callback disabled */
|
||||
#define USE_HAL_OPAMP_REGISTER_CALLBACKS 0U /* OTFDEC register callback disabled */
|
||||
#define USE_HAL_OTFDEC_REGISTER_CALLBACKS 0U /* OPAMP register callback disabled */
|
||||
#define USE_HAL_PCD_REGISTER_CALLBACKS 0U /* PCD register callback disabled */
|
||||
#define USE_HAL_PKA_REGISTER_CALLBACKS 0U /* PKA register callback disabled */
|
||||
#define USE_HAL_RAMCFG_REGISTER_CALLBACKS 0U /* RAMCFG register callback disabled */
|
||||
#define USE_HAL_RNG_REGISTER_CALLBACKS 0U /* RNG register callback disabled */
|
||||
#define USE_HAL_RTC_REGISTER_CALLBACKS 0U /* RTC register callback disabled */
|
||||
#define USE_HAL_SAI_REGISTER_CALLBACKS 0U /* SAI register callback disabled */
|
||||
#define USE_HAL_SD_REGISTER_CALLBACKS 0U /* SD register callback disabled */
|
||||
#define USE_HAL_SDRAM_REGISTER_CALLBACKS 0U /* SDRAM register callback disabled */
|
||||
#define USE_HAL_SMARTCARD_REGISTER_CALLBACKS 0U /* SMARTCARD register callback disabled */
|
||||
#define USE_HAL_SMBUS_REGISTER_CALLBACKS 0U /* SMBUS register callback disabled */
|
||||
#define USE_HAL_SPI_REGISTER_CALLBACKS 0U /* SPI register callback disabled */
|
||||
#define USE_HAL_SRAM_REGISTER_CALLBACKS 0U /* SRAM register callback disabled */
|
||||
#define USE_HAL_TIM_REGISTER_CALLBACKS 0U /* TIM register callback disabled */
|
||||
#define USE_HAL_UART_REGISTER_CALLBACKS 0U /* UART register callback disabled */
|
||||
#define USE_HAL_USART_REGISTER_CALLBACKS 0U /* USART register callback disabled */
|
||||
#define USE_HAL_WWDG_REGISTER_CALLBACKS 0U /* WWDG register callback disabled */
|
||||
#define USE_HAL_XSPI_REGISTER_CALLBACKS 0U /* XSPI register callback disabled */
|
||||
|
||||
/* ############################################ SPI peripheral configuration ######################################## */
|
||||
|
||||
/* CRC FEATURE: Use to activate CRC feature inside HAL SPI Driver
|
||||
* Activated: CRC code is present inside driver
|
||||
* Deactivated: CRC code cleaned from driver
|
||||
*/
|
||||
#define USE_SPI_CRC 1U
|
||||
|
||||
|
||||
/* Includes ----------------------------------------------------------------------------------------------------------*/
|
||||
/**
|
||||
* @brief Include module's header file
|
||||
*/
|
||||
|
||||
#ifdef HAL_RCC_MODULE_ENABLED
|
||||
#include "stm32h5xx_hal_rcc.h"
|
||||
#endif /* HAL_RCC_MODULE_ENABLED */
|
||||
|
||||
#ifdef HAL_GPIO_MODULE_ENABLED
|
||||
#include "stm32h5xx_hal_gpio.h"
|
||||
#endif /* HAL_GPIO_MODULE_ENABLED */
|
||||
|
||||
#ifdef HAL_ICACHE_MODULE_ENABLED
|
||||
#include "stm32h5xx_hal_icache.h"
|
||||
#endif /* HAL_ICACHE_MODULE_ENABLED */
|
||||
|
||||
#ifdef HAL_DCACHE_MODULE_ENABLED
|
||||
#include "stm32h5xx_hal_dcache.h"
|
||||
#endif /* HAL_DCACHE_MODULE_ENABLED */
|
||||
|
||||
#ifdef HAL_GTZC_MODULE_ENABLED
|
||||
#include "stm32h5xx_hal_gtzc.h"
|
||||
#endif /* HAL_GTZC_MODULE_ENABLED */
|
||||
|
||||
#ifdef HAL_DMA_MODULE_ENABLED
|
||||
#include "stm32h5xx_hal_dma.h"
|
||||
#endif /* HAL_DMA_MODULE_ENABLED */
|
||||
|
||||
#ifdef HAL_DTS_MODULE_ENABLED
|
||||
#include "stm32h5xx_hal_dts.h"
|
||||
#endif /* HAL_DTS_MODULE_ENABLED */
|
||||
|
||||
#ifdef HAL_CORTEX_MODULE_ENABLED
|
||||
#include "stm32h5xx_hal_cortex.h"
|
||||
#endif /* HAL_CORTEX_MODULE_ENABLED */
|
||||
|
||||
#ifdef HAL_PKA_MODULE_ENABLED
|
||||
#include "stm32h5xx_hal_pka.h"
|
||||
#endif /* HAL_PKA_MODULE_ENABLED */
|
||||
|
||||
#ifdef HAL_ADC_MODULE_ENABLED
|
||||
#include "stm32h5xx_hal_adc.h"
|
||||
#endif /* HAL_ADC_MODULE_ENABLED */
|
||||
|
||||
#ifdef HAL_CRC_MODULE_ENABLED
|
||||
#include "stm32h5xx_hal_crc.h"
|
||||
#endif /* HAL_CRC_MODULE_ENABLED */
|
||||
|
||||
#ifdef HAL_CRYP_MODULE_ENABLED
|
||||
#include "stm32h5xx_hal_cryp.h"
|
||||
#endif /* HAL_CRYP_MODULE_ENABLED */
|
||||
|
||||
#ifdef HAL_DAC_MODULE_ENABLED
|
||||
#include "stm32h5xx_hal_dac.h"
|
||||
#endif /* HAL_DAC_MODULE_ENABLED */
|
||||
|
||||
#ifdef HAL_FLASH_MODULE_ENABLED
|
||||
#include "stm32h5xx_hal_flash.h"
|
||||
#endif /* HAL_FLASH_MODULE_ENABLED */
|
||||
|
||||
#ifdef HAL_HASH_MODULE_ENABLED
|
||||
#include "stm32h5xx_hal_hash.h"
|
||||
#endif /* HAL_HASH_MODULE_ENABLED */
|
||||
|
||||
#ifdef HAL_SRAM_MODULE_ENABLED
|
||||
#include "stm32h5xx_hal_sram.h"
|
||||
#endif /* HAL_SRAM_MODULE_ENABLED */
|
||||
|
||||
#ifdef HAL_SDRAM_MODULE_ENABLED
|
||||
#include "stm32h5xx_hal_sdram.h"
|
||||
#endif /* HAL_SDRAM_MODULE_ENABLED */
|
||||
|
||||
#ifdef HAL_MMC_MODULE_ENABLED
|
||||
#include "stm32h5xx_hal_mmc.h"
|
||||
#endif /* HAL_MMC_MODULE_ENABLED */
|
||||
|
||||
#ifdef HAL_NOR_MODULE_ENABLED
|
||||
#include "stm32h5xx_hal_nor.h"
|
||||
#endif /* HAL_NOR_MODULE_ENABLED */
|
||||
|
||||
#ifdef HAL_NAND_MODULE_ENABLED
|
||||
#include "stm32h5xx_hal_nand.h"
|
||||
#endif /* HAL_NAND_MODULE_ENABLED */
|
||||
|
||||
#ifdef HAL_I2C_MODULE_ENABLED
|
||||
#include "stm32h5xx_hal_i2c.h"
|
||||
#endif /* HAL_I2C_MODULE_ENABLED */
|
||||
|
||||
#ifdef HAL_I2S_MODULE_ENABLED
|
||||
#include "stm32h5xx_hal_i2s.h"
|
||||
#endif /* HAL_I2S_MODULE_ENABLED */
|
||||
|
||||
#ifdef HAL_I3C_MODULE_ENABLED
|
||||
#include "stm32h5xx_hal_i3c.h"
|
||||
#endif /* HAL_I3C_MODULE_ENABLED */
|
||||
|
||||
#ifdef HAL_IWDG_MODULE_ENABLED
|
||||
#include "stm32h5xx_hal_iwdg.h"
|
||||
#endif /* HAL_IWDG_MODULE_ENABLED */
|
||||
|
||||
#ifdef HAL_LPTIM_MODULE_ENABLED
|
||||
#include "stm32h5xx_hal_lptim.h"
|
||||
#endif /* HAL_LPTIM_MODULE_ENABLED */
|
||||
|
||||
#ifdef HAL_PWR_MODULE_ENABLED
|
||||
#include "stm32h5xx_hal_pwr.h"
|
||||
#endif /* HAL_PWR_MODULE_ENABLED */
|
||||
|
||||
#ifdef HAL_XSPI_MODULE_ENABLED
|
||||
#include "stm32h5xx_hal_xspi.h"
|
||||
#endif /* HAL_XSPI_MODULE_ENABLED */
|
||||
|
||||
#ifdef HAL_RNG_MODULE_ENABLED
|
||||
#include "stm32h5xx_hal_rng.h"
|
||||
#endif /* HAL_RNG_MODULE_ENABLED */
|
||||
|
||||
#ifdef HAL_RTC_MODULE_ENABLED
|
||||
#include "stm32h5xx_hal_rtc.h"
|
||||
#endif /* HAL_RTC_MODULE_ENABLED */
|
||||
|
||||
#ifdef HAL_SAI_MODULE_ENABLED
|
||||
#include "stm32h5xx_hal_sai.h"
|
||||
#endif /* HAL_SAI_MODULE_ENABLED */
|
||||
|
||||
#ifdef HAL_SD_MODULE_ENABLED
|
||||
#include "stm32h5xx_hal_sd.h"
|
||||
#endif /* HAL_SD_MODULE_ENABLED */
|
||||
|
||||
#ifdef HAL_SMBUS_MODULE_ENABLED
|
||||
#include "stm32h5xx_hal_smbus.h"
|
||||
#endif /* HAL_SMBUS_MODULE_ENABLED */
|
||||
|
||||
#ifdef HAL_SPI_MODULE_ENABLED
|
||||
#include "stm32h5xx_hal_spi.h"
|
||||
#endif /* HAL_SPI_MODULE_ENABLED */
|
||||
|
||||
#ifdef HAL_TIM_MODULE_ENABLED
|
||||
#include "stm32h5xx_hal_tim.h"
|
||||
#endif /* HAL_TIM_MODULE_ENABLED */
|
||||
|
||||
#ifdef HAL_UART_MODULE_ENABLED
|
||||
#include "stm32h5xx_hal_uart.h"
|
||||
#endif /* HAL_UART_MODULE_ENABLED */
|
||||
|
||||
#ifdef HAL_USART_MODULE_ENABLED
|
||||
#include "stm32h5xx_hal_usart.h"
|
||||
#endif /* HAL_USART_MODULE_ENABLED */
|
||||
|
||||
#ifdef HAL_IRDA_MODULE_ENABLED
|
||||
#include "stm32h5xx_hal_irda.h"
|
||||
#endif /* HAL_IRDA_MODULE_ENABLED */
|
||||
|
||||
#ifdef HAL_SMARTCARD_MODULE_ENABLED
|
||||
#include "stm32h5xx_hal_smartcard.h"
|
||||
#endif /* HAL_SMARTCARD_MODULE_ENABLED */
|
||||
|
||||
#ifdef HAL_WWDG_MODULE_ENABLED
|
||||
#include "stm32h5xx_hal_wwdg.h"
|
||||
#endif /* HAL_WWDG_MODULE_ENABLED */
|
||||
|
||||
#ifdef HAL_PCD_MODULE_ENABLED
|
||||
#include "stm32h5xx_hal_pcd.h"
|
||||
#endif /* HAL_PCD_MODULE_ENABLED */
|
||||
|
||||
#ifdef HAL_HCD_MODULE_ENABLED
|
||||
#include "stm32h5xx_hal_hcd.h"
|
||||
#endif /* HAL_HCD_MODULE_ENABLED */
|
||||
|
||||
#ifdef HAL_COMP_MODULE_ENABLED
|
||||
#include "stm32h5xx_hal_comp.h"
|
||||
#endif /* HAL_COMP_MODULE_ENABLED */
|
||||
|
||||
#ifdef HAL_CORDIC_MODULE_ENABLED
|
||||
#include "stm32h5xx_hal_cordic.h"
|
||||
#endif /* HAL_CORDIC_MODULE_ENABLED */
|
||||
|
||||
#ifdef HAL_DCMI_MODULE_ENABLED
|
||||
#include "stm32h5xx_hal_dcmi.h"
|
||||
#endif /* HAL_DCMI_MODULE_ENABLED */
|
||||
|
||||
#ifdef HAL_EXTI_MODULE_ENABLED
|
||||
#include "stm32h5xx_hal_exti.h"
|
||||
#endif /* HAL_EXTI_MODULE_ENABLED */
|
||||
|
||||
#ifdef HAL_ETH_MODULE_ENABLED
|
||||
#include "stm32h5xx_hal_eth.h"
|
||||
#endif /* HAL_ETH_MODULE_ENABLED */
|
||||
|
||||
#ifdef HAL_FDCAN_MODULE_ENABLED
|
||||
#include "stm32h5xx_hal_fdcan.h"
|
||||
#endif /* HAL_FDCAN_MODULE_ENABLED */
|
||||
|
||||
#ifdef HAL_CEC_MODULE_ENABLED
|
||||
#include "stm32h5xx_hal_cec.h"
|
||||
#endif /* HAL_CEC_MODULE_ENABLED */
|
||||
|
||||
#ifdef HAL_FMAC_MODULE_ENABLED
|
||||
#include "stm32h5xx_hal_fmac.h"
|
||||
#endif /* HAL_FMAC_MODULE_ENABLED */
|
||||
|
||||
#ifdef HAL_OPAMP_MODULE_ENABLED
|
||||
#include "stm32h5xx_hal_opamp.h"
|
||||
#endif /* HAL_OPAMP_MODULE_ENABLED */
|
||||
|
||||
#ifdef HAL_OTFDEC_MODULE_ENABLED
|
||||
#include "stm32h5xx_hal_otfdec.h"
|
||||
#endif /* HAL_OTFDEC_MODULE_ENABLED */
|
||||
|
||||
#ifdef HAL_PSSI_MODULE_ENABLED
|
||||
#include "stm32h5xx_hal_pssi.h"
|
||||
#endif /* HAL_PSSI_MODULE_ENABLED */
|
||||
|
||||
#ifdef HAL_RAMCFG_MODULE_ENABLED
|
||||
#include "stm32h5xx_hal_ramcfg.h"
|
||||
#endif /* HAL_RAMCFG_MODULE_ENABLED */
|
||||
|
||||
/* Exported macro ----------------------------------------------------------------------------------------------------*/
|
||||
#ifdef USE_FULL_ASSERT
|
||||
/**
|
||||
* @brief The assert_param macro is used for function's parameters check.
|
||||
* @param expr: If expr is false, it calls assert_failed function
|
||||
* which reports the name of the source file and the source
|
||||
* line number of the call that failed.
|
||||
* If expr is true, it returns no value.
|
||||
* @retval None
|
||||
*/
|
||||
#define assert_param(expr) ((expr) ? (void)0U : assert_failed((uint8_t *)__FILE__, __LINE__))
|
||||
/* Exported functions ----------------------------------------------------------------------------------------------- */
|
||||
void assert_failed(uint8_t *file, uint32_t line);
|
||||
#else
|
||||
#define assert_param(expr) ((void)0U)
|
||||
#endif /* USE_FULL_ASSERT */
|
||||
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif /* STM32H5xx_HAL_CONF_H */
|
406
src/main/startup/system_stm32h5xx.c
Normal file
406
src/main/startup/system_stm32h5xx.c
Normal file
|
@ -0,0 +1,406 @@
|
|||
/**
|
||||
******************************************************************************
|
||||
* @file system_stm32h5xx.c
|
||||
* @author MCD Application Team
|
||||
* @brief CMSIS Cortex-M33 Device Peripheral Access Layer System Source File
|
||||
*
|
||||
******************************************************************************
|
||||
* @attention
|
||||
*
|
||||
* Copyright (c) 2023 STMicroelectronics.
|
||||
* All rights reserved.
|
||||
*
|
||||
* This software is licensed under terms that can be found in the LICENSE file
|
||||
* in the root directory of this software component.
|
||||
* If no LICENSE file comes with this software, it is provided AS-IS.
|
||||
*
|
||||
******************************************************************************
|
||||
* This file provides two functions and one global variable to be called from
|
||||
* user application:
|
||||
* - SystemInit(): This function is called at startup just after reset and
|
||||
* before branch to main program. This call is made inside
|
||||
* the "startup_stm32h5xx.s" file.
|
||||
*
|
||||
* - SystemCoreClock variable: Contains the core clock (HCLK), it can be used
|
||||
* by the user application to setup the SysTick
|
||||
* timer or configure other parameters.
|
||||
*
|
||||
* - SystemCoreClockUpdate(): Updates the variable SystemCoreClock and must
|
||||
* be called whenever the core clock is changed
|
||||
* during program execution.
|
||||
*
|
||||
* After each device reset the HSI (64 MHz) is used as system clock source.
|
||||
* Then SystemInit() function is called, in "startup_stm32h5xx.s" file, to
|
||||
* configure the system clock before to branch to main program.
|
||||
*
|
||||
* This file configures the system clock as follows:
|
||||
*=============================================================================
|
||||
*-----------------------------------------------------------------------------
|
||||
* System Clock source | HSI
|
||||
*-----------------------------------------------------------------------------
|
||||
* SYSCLK(Hz) | 64000000
|
||||
*-----------------------------------------------------------------------------
|
||||
* HCLK(Hz) | 64000000
|
||||
*-----------------------------------------------------------------------------
|
||||
* AHB Prescaler | 1
|
||||
*-----------------------------------------------------------------------------
|
||||
* APB1 Prescaler | 1
|
||||
*-----------------------------------------------------------------------------
|
||||
* APB2 Prescaler | 1
|
||||
*-----------------------------------------------------------------------------
|
||||
* APB3 Prescaler | 1
|
||||
*-----------------------------------------------------------------------------
|
||||
* HSI Division factor | 1
|
||||
*-----------------------------------------------------------------------------
|
||||
* PLL1_SRC | No clock
|
||||
*-----------------------------------------------------------------------------
|
||||
* PLL1_M | Prescaler disabled
|
||||
*-----------------------------------------------------------------------------
|
||||
* PLL1_N | 129
|
||||
*-----------------------------------------------------------------------------
|
||||
* PLL1_P | 2
|
||||
*-----------------------------------------------------------------------------
|
||||
* PLL1_Q | 2
|
||||
*-----------------------------------------------------------------------------
|
||||
* PLL1_R | 2
|
||||
*-----------------------------------------------------------------------------
|
||||
* PLL1_FRACN | 0
|
||||
*-----------------------------------------------------------------------------
|
||||
* PLL2_SRC | No clock
|
||||
*-----------------------------------------------------------------------------
|
||||
* PLL2_M | Prescaler disabled
|
||||
*-----------------------------------------------------------------------------
|
||||
* PLL2_N | 129
|
||||
*-----------------------------------------------------------------------------
|
||||
* PLL2_P | 2
|
||||
*-----------------------------------------------------------------------------
|
||||
* PLL2_Q | 2
|
||||
*-----------------------------------------------------------------------------
|
||||
* PLL2_R | 2
|
||||
*-----------------------------------------------------------------------------
|
||||
* PLL2_FRACN | 0
|
||||
*-----------------------------------------------------------------------------
|
||||
* PLL3_SRC | No clock
|
||||
*-----------------------------------------------------------------------------
|
||||
* PLL3_M | Prescaler disabled
|
||||
*-----------------------------------------------------------------------------
|
||||
* PLL3_N | 129
|
||||
*-----------------------------------------------------------------------------
|
||||
* PLL3_P | 2
|
||||
*-----------------------------------------------------------------------------
|
||||
* PLL3_Q | 2
|
||||
*-----------------------------------------------------------------------------
|
||||
* PLL3_R | 2
|
||||
*-----------------------------------------------------------------------------
|
||||
* PLL3_FRACN | 0
|
||||
*-----------------------------------------------------------------------------
|
||||
*=============================================================================
|
||||
*/
|
||||
|
||||
/** @addtogroup CMSIS
|
||||
* @{
|
||||
*/
|
||||
|
||||
/** @addtogroup STM32H5xx_system
|
||||
* @{
|
||||
*/
|
||||
|
||||
/** @addtogroup STM32H5xx_System_Private_Includes
|
||||
* @{
|
||||
*/
|
||||
|
||||
#include <string.h>
|
||||
|
||||
#include "stm32h5xx.h"
|
||||
#include "drivers/system.h"
|
||||
#include "platform.h"
|
||||
#include "drivers/persistent.h"
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/** @addtogroup STM32H5xx_System_Private_TypesDefinitions
|
||||
* @{
|
||||
*/
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/** @addtogroup STM32H5xx_System_Private_Defines
|
||||
* @{
|
||||
*/
|
||||
|
||||
#if !defined (HSE_VALUE)
|
||||
#define HSE_VALUE (25000000UL) /*!< Value of the External oscillator in Hz */
|
||||
#endif /* HSE_VALUE */
|
||||
|
||||
#if !defined (CSI_VALUE)
|
||||
#define CSI_VALUE (4000000UL) /*!< Value of the Internal oscillator in Hz*/
|
||||
#endif /* CSI_VALUE */
|
||||
|
||||
#if !defined (HSI_VALUE)
|
||||
#define HSI_VALUE (64000000UL) /*!< Value of the Internal oscillator in Hz */
|
||||
#endif /* HSI_VALUE */
|
||||
|
||||
/************************* Miscellaneous Configuration ************************/
|
||||
/*!< Uncomment the following line if you need to relocate your vector Table in
|
||||
Internal SRAM. */
|
||||
/* #define VECT_TAB_SRAM */
|
||||
#define VECT_TAB_OFFSET 0x00U /*!< Vector Table base offset field.
|
||||
This value must be a multiple of 0x200. */
|
||||
/******************************************************************************/
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/** @addtogroup STM32H5xx_System_Private_Macros
|
||||
* @{
|
||||
*/
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/** @addtogroup STM32H5xx_System_Private_Variables
|
||||
* @{
|
||||
*/
|
||||
/* The SystemCoreClock variable is updated in three ways:
|
||||
1) by calling CMSIS function SystemCoreClockUpdate()
|
||||
2) by calling HAL API function HAL_RCC_GetHCLKFreq()
|
||||
3) each time HAL_RCC_ClockConfig() is called to configure the system clock frequency
|
||||
Note: If you use this function to configure the system clock; then there
|
||||
is no need to call the 2 first functions listed above, since SystemCoreClock
|
||||
variable is updated automatically.
|
||||
*/
|
||||
uint32_t SystemCoreClock = 64000000U;
|
||||
|
||||
const uint8_t AHBPrescTable[16] = {0U, 0U, 0U, 0U, 0U, 0U, 0U, 0U, 1U, 2U, 3U, 4U, 6U, 7U, 8U, 9U};
|
||||
const uint8_t APBPrescTable[8] = {0U, 0U, 0U, 0U, 1U, 2U, 3U, 4U};
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/** @addtogroup STM32H5xx_System_Private_FunctionPrototypes
|
||||
* @{
|
||||
*/
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/** @addtogroup STM32H5xx_System_Private_Functions
|
||||
* @{
|
||||
*/
|
||||
|
||||
/**
|
||||
* @brief Setup the microcontroller system.
|
||||
* @param None
|
||||
* @retval None
|
||||
*/
|
||||
|
||||
void SystemInit(void)
|
||||
{
|
||||
uint32_t reg_opsr;
|
||||
|
||||
/* FPU settings ------------------------------------------------------------*/
|
||||
#if (__FPU_PRESENT == 1) && (__FPU_USED == 1)
|
||||
SCB->CPACR |= ((3UL << 20U)|(3UL << 22U)); /* set CP10 and CP11 Full Access */
|
||||
#endif
|
||||
|
||||
/* Reset the RCC clock configuration to the default reset state ------------*/
|
||||
/* Set HSION bit */
|
||||
RCC->CR = RCC_CR_HSION;
|
||||
|
||||
/* Reset CFGR register */
|
||||
RCC->CFGR1 = 0U;
|
||||
RCC->CFGR2 = 0U;
|
||||
|
||||
/* Reset HSEON, HSECSSON, HSEBYP, HSEEXT, HSIDIV, HSIKERON, CSION, CSIKERON, HSI48 and PLLxON bits */
|
||||
#if defined(RCC_CR_PLL3ON)
|
||||
RCC->CR &= ~(RCC_CR_HSEON | RCC_CR_HSECSSON | RCC_CR_HSEBYP | RCC_CR_HSEEXT | RCC_CR_HSIDIV | RCC_CR_HSIKERON | \
|
||||
RCC_CR_CSION | RCC_CR_CSIKERON |RCC_CR_HSI48ON | RCC_CR_PLL1ON | RCC_CR_PLL2ON | RCC_CR_PLL3ON);
|
||||
#else
|
||||
RCC->CR &= ~(RCC_CR_HSEON | RCC_CR_HSECSSON | RCC_CR_HSEBYP | RCC_CR_HSEEXT | RCC_CR_HSIDIV | RCC_CR_HSIKERON | \
|
||||
RCC_CR_CSION | RCC_CR_CSIKERON |RCC_CR_HSI48ON | RCC_CR_PLL1ON | RCC_CR_PLL2ON);
|
||||
#endif
|
||||
|
||||
/* Reset PLLxCFGR register */
|
||||
RCC->PLL1CFGR = 0U;
|
||||
RCC->PLL2CFGR = 0U;
|
||||
#if defined(RCC_CR_PLL3ON)
|
||||
RCC->PLL3CFGR = 0U;
|
||||
#endif /* RCC_CR_PLL3ON */
|
||||
|
||||
/* Reset PLL1DIVR register */
|
||||
RCC->PLL1DIVR = 0x01010280U;
|
||||
/* Reset PLL1FRACR register */
|
||||
RCC->PLL1FRACR = 0x00000000U;
|
||||
/* Reset PLL2DIVR register */
|
||||
RCC->PLL2DIVR = 0x01010280U;
|
||||
/* Reset PLL2FRACR register */
|
||||
RCC->PLL2FRACR = 0x00000000U;
|
||||
#if defined(RCC_CR_PLL3ON)
|
||||
/* Reset PLL3DIVR register */
|
||||
RCC->PLL3DIVR = 0x01010280U;
|
||||
/* Reset PLL3FRACR register */
|
||||
RCC->PLL3FRACR = 0x00000000U;
|
||||
#endif /* RCC_CR_PLL3ON */
|
||||
|
||||
/* Reset HSEBYP bit */
|
||||
RCC->CR &= ~(RCC_CR_HSEBYP);
|
||||
|
||||
/* Disable all interrupts */
|
||||
RCC->CIER = 0U;
|
||||
|
||||
/* Configure the Vector Table location add offset address ------------------*/
|
||||
#ifdef VECT_TAB_SRAM
|
||||
SCB->VTOR = SRAM1_BASE | VECT_TAB_OFFSET; /* Vector Table Relocation in Internal SRAM */
|
||||
#else
|
||||
SCB->VTOR = FLASH_BASE | VECT_TAB_OFFSET; /* Vector Table Relocation in Internal FLASH */
|
||||
#endif /* VECT_TAB_SRAM */
|
||||
|
||||
/* Check OPSR register to verify if there is an ongoing swap or option bytes update interrupted by a reset */
|
||||
reg_opsr = FLASH->OPSR & FLASH_OPSR_CODE_OP;
|
||||
if ((reg_opsr == FLASH_OPSR_CODE_OP) || (reg_opsr == (FLASH_OPSR_CODE_OP_2 | FLASH_OPSR_CODE_OP_1)))
|
||||
{
|
||||
/* Check FLASH Option Control Register access */
|
||||
if ((FLASH->OPTCR & FLASH_OPTCR_OPTLOCK) != 0U)
|
||||
{
|
||||
/* Authorizes the Option Byte registers programming */
|
||||
FLASH->OPTKEYR = 0x08192A3BU;
|
||||
FLASH->OPTKEYR = 0x4C5D6E7FU;
|
||||
}
|
||||
/* Launch the option bytes change operation */
|
||||
FLASH->OPTCR |= FLASH_OPTCR_OPTSTART;
|
||||
|
||||
/* Lock the FLASH Option Control Register access */
|
||||
FLASH->OPTCR |= FLASH_OPTCR_OPTLOCK;
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Update SystemCoreClock variable according to Clock Register Values.
|
||||
* The SystemCoreClock variable contains the core clock (HCLK), it can
|
||||
* be used by the user application to setup the SysTick timer or configure
|
||||
* other parameters.
|
||||
*
|
||||
* @note Each time the core clock (HCLK) changes, this function must be called
|
||||
* to update SystemCoreClock variable value. Otherwise, any configuration
|
||||
* based on this variable will be incorrect.
|
||||
*
|
||||
* @note - The system frequency computed by this function is not the real
|
||||
* frequency in the chip. It is calculated based on the predefined
|
||||
* constant and the selected clock source:
|
||||
*
|
||||
* - If SYSCLK source is CSI, SystemCoreClock will contain the CSI_VALUE(*)
|
||||
*
|
||||
* - If SYSCLK source is HSI, SystemCoreClock will contain the HSI_VALUE(**)
|
||||
*
|
||||
* - If SYSCLK source is HSE, SystemCoreClock will contain the HSE_VALUE(***)
|
||||
*
|
||||
* - If SYSCLK source is PLL, SystemCoreClock will contain the HSE_VALUE(***)
|
||||
* or HSI_VALUE(**) or CSI_VALUE(*) multiplied/divided by the PLL factors.
|
||||
*
|
||||
* (*) CSI_VALUE is a constant defined in stm32h5xx_hal.h file (default value
|
||||
* 4 MHz) but the real value may vary depending on the variations
|
||||
* in voltage and temperature.
|
||||
*
|
||||
* (**) HSI_VALUE is a constant defined in stm32h5xx_hal.h file (default value
|
||||
* 64 MHz) but the real value may vary depending on the variations
|
||||
* in voltage and temperature.
|
||||
*
|
||||
* (***) HSE_VALUE is a constant defined in stm32h5xx_hal.h file (default value
|
||||
* 25 MHz), user has to ensure that HSE_VALUE is same as the real
|
||||
* frequency of the crystal used. Otherwise, this function may
|
||||
* have wrong result.
|
||||
*
|
||||
* - The result of this function could be not correct when using fractional
|
||||
* value for HSE crystal.
|
||||
*
|
||||
* @param None
|
||||
* @retval None
|
||||
*/
|
||||
void SystemCoreClockUpdate(void)
|
||||
{
|
||||
uint32_t pllp, pllsource, pllm, pllfracen, hsivalue, tmp;
|
||||
float_t fracn1, pllvco;
|
||||
|
||||
/* Get SYSCLK source -------------------------------------------------------*/
|
||||
switch (RCC->CFGR1 & RCC_CFGR1_SWS)
|
||||
{
|
||||
case 0x00UL: /* HSI used as system clock source */
|
||||
SystemCoreClock = (uint32_t) (HSI_VALUE >> ((RCC->CR & RCC_CR_HSIDIV)>> 3));
|
||||
break;
|
||||
|
||||
case 0x08UL: /* CSI used as system clock source */
|
||||
SystemCoreClock = CSI_VALUE;
|
||||
break;
|
||||
|
||||
case 0x10UL: /* HSE used as system clock source */
|
||||
SystemCoreClock = HSE_VALUE;
|
||||
break;
|
||||
|
||||
case 0x18UL: /* PLL1 used as system clock source */
|
||||
/* PLL_VCO = (HSE_VALUE or HSI_VALUE or CSI_VALUE/ PLLM) * PLLN
|
||||
SYSCLK = PLL_VCO / PLLR
|
||||
*/
|
||||
pllsource = (RCC->PLL1CFGR & RCC_PLL1CFGR_PLL1SRC);
|
||||
pllm = ((RCC->PLL1CFGR & RCC_PLL1CFGR_PLL1M)>> RCC_PLL1CFGR_PLL1M_Pos);
|
||||
pllfracen = ((RCC->PLL1CFGR & RCC_PLL1CFGR_PLL1FRACEN)>>RCC_PLL1CFGR_PLL1FRACEN_Pos);
|
||||
fracn1 = (float_t)(uint32_t)(pllfracen* ((RCC->PLL1FRACR & RCC_PLL1FRACR_PLL1FRACN)>> RCC_PLL1FRACR_PLL1FRACN_Pos));
|
||||
|
||||
switch (pllsource)
|
||||
{
|
||||
case 0x01UL: /* HSI used as PLL clock source */
|
||||
hsivalue = (HSI_VALUE >> ((RCC->CR & RCC_CR_HSIDIV)>> 3)) ;
|
||||
pllvco = ((float_t)hsivalue / (float_t)pllm) * ((float_t)(uint32_t)(RCC->PLL1DIVR & RCC_PLL1DIVR_PLL1N) + \
|
||||
(fracn1/(float_t)0x2000) +(float_t)1 );
|
||||
break;
|
||||
|
||||
case 0x02UL: /* CSI used as PLL clock source */
|
||||
pllvco = ((float_t)CSI_VALUE / (float_t)pllm) * ((float_t)(uint32_t)(RCC->PLL1DIVR & RCC_PLL1DIVR_PLL1N) + \
|
||||
(fracn1/(float_t)0x2000) +(float_t)1 );
|
||||
break;
|
||||
|
||||
case 0x03UL: /* HSE used as PLL clock source */
|
||||
pllvco = ((float_t)HSE_VALUE / (float_t)pllm) * ((float_t)(uint32_t)(RCC->PLL1DIVR & RCC_PLL1DIVR_PLL1N) + \
|
||||
(fracn1/(float_t)0x2000) +(float_t)1 );
|
||||
break;
|
||||
|
||||
default: /* No clock sent to PLL*/
|
||||
pllvco = (float_t) 0U;
|
||||
break;
|
||||
}
|
||||
|
||||
pllp = (((RCC->PLL1DIVR & RCC_PLL1DIVR_PLL1P) >>RCC_PLL1DIVR_PLL1P_Pos) + 1U ) ;
|
||||
SystemCoreClock = (uint32_t)(float_t)(pllvco/(float_t)pllp);
|
||||
|
||||
break;
|
||||
|
||||
default:
|
||||
SystemCoreClock = HSI_VALUE;
|
||||
break;
|
||||
}
|
||||
/* Compute HCLK clock frequency --------------------------------------------*/
|
||||
/* Get HCLK prescaler */
|
||||
tmp = AHBPrescTable[((RCC->CFGR2 & RCC_CFGR2_HPRE) >> RCC_CFGR2_HPRE_Pos)];
|
||||
/* HCLK clock frequency */
|
||||
SystemCoreClock >>= tmp;
|
||||
}
|
||||
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
107
src/main/startup/system_stm32h5xx.h
Normal file
107
src/main/startup/system_stm32h5xx.h
Normal file
|
@ -0,0 +1,107 @@
|
|||
/**
|
||||
******************************************************************************
|
||||
* @file system_stm32h5xx.h
|
||||
* @author MCD Application Team
|
||||
* @brief CMSIS Cortex-M33 Device System Source File for STM32H5xx devices.
|
||||
******************************************************************************
|
||||
* @attention
|
||||
*
|
||||
* Copyright (c) 2023 STMicroelectronics.
|
||||
* All rights reserved.
|
||||
*
|
||||
* This software is licensed under terms that can be found in the LICENSE file
|
||||
* in the root directory of this software component.
|
||||
* If no LICENSE file comes with this software, it is provided AS-IS.
|
||||
*
|
||||
******************************************************************************
|
||||
*/
|
||||
|
||||
/** @addtogroup CMSIS
|
||||
* @{
|
||||
*/
|
||||
|
||||
/** @addtogroup stm32h5xx_system
|
||||
* @{
|
||||
*/
|
||||
|
||||
#ifndef SYSTEM_STM32H5XX_H
|
||||
#define SYSTEM_STM32H5XX_H
|
||||
|
||||
#ifdef __cplusplus
|
||||
extern "C" {
|
||||
#endif
|
||||
|
||||
/** @addtogroup STM32H5xx_System_Includes
|
||||
* @{
|
||||
*/
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/** @addtogroup STM32H5xx_System_Exported_Variables
|
||||
* @{
|
||||
*/
|
||||
/* The SystemCoreClock variable is updated in three ways:
|
||||
1) by calling CMSIS function SystemCoreClockUpdate()
|
||||
2) by calling HAL API function HAL_RCC_GetSysClockFreq()
|
||||
3) each time HAL_RCC_ClockConfig() is called to configure the system clock frequency
|
||||
Note: If you use this function to configure the system clock; then there
|
||||
is no need to call the 2 first functions listed above, since SystemCoreClock
|
||||
variable is updated automatically.
|
||||
*/
|
||||
extern uint32_t SystemCoreClock; /*!< System Clock Frequency (Core Clock) */
|
||||
|
||||
extern const uint8_t AHBPrescTable[16]; /*!< AHB prescalers table values */
|
||||
extern const uint8_t APBPrescTable[8]; /*!< APB prescalers table values */
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
|
||||
/** @addtogroup STM32H5xx_System_Exported_Functions
|
||||
* @{
|
||||
*/
|
||||
|
||||
/**
|
||||
* @brief Setup the microcontroller system.
|
||||
*
|
||||
* Initialize the System and update the SystemCoreClock variable.
|
||||
*/
|
||||
extern void SystemInit (void);
|
||||
|
||||
|
||||
/**
|
||||
* @brief Update SystemCoreClock variable.
|
||||
*
|
||||
* Updates the SystemCoreClock with current core Clock retrieved from cpu registers.
|
||||
*/
|
||||
extern void SystemCoreClockUpdate (void);
|
||||
|
||||
|
||||
/**
|
||||
* @brief Update SystemCoreClock variable from secure application and return its value
|
||||
* when security is implemented in the system (Non-secure callable function).
|
||||
*
|
||||
* Returns the SystemCoreClock value with current core Clock retrieved from cpu registers.
|
||||
*/
|
||||
extern uint32_t SECURE_SystemCoreClockUpdate(void);
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif /* SYSTEM_STM32H5XX_H */
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
147
src/main/target/STM32H563/target.h
Normal file
147
src/main/target/STM32H563/target.h
Normal file
|
@ -0,0 +1,147 @@
|
|||
/*
|
||||
* This file is part of Betaflight.
|
||||
*
|
||||
* Betaflight is free software. You can redistribute
|
||||
* this software and/or modify this software under the terms of the
|
||||
* GNU General Public License as published by the Free Software
|
||||
* Foundation, either version 3 of the License, or (at your option)
|
||||
* any later version.
|
||||
*
|
||||
* Betaflight is distributed in the hope that they
|
||||
* will be useful, but WITHOUT ANY WARRANTY; without even the implied
|
||||
* warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
|
||||
* See the GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with this software.
|
||||
*
|
||||
* If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#pragma once
|
||||
|
||||
#define TARGET_BOARD_IDENTIFIER "SH56"
|
||||
|
||||
#define USBD_PRODUCT_STRING "Betaflight STM32H563"
|
||||
|
||||
#undef USE_PWM
|
||||
#undef USE_PWM_OUTPUT
|
||||
#undef USE_DSHOT
|
||||
#undef USE_ADC
|
||||
#undef USE_TIMER
|
||||
#undef USE_DMA
|
||||
#undef USE_FLASH
|
||||
#undef USE_FLASH_CHIP
|
||||
#undef USE_FLASHFS
|
||||
#undef USE_FLASH_TOOLS
|
||||
#undef USE_FLASH_M25P16
|
||||
#undef USE_FLASH_W25N01G
|
||||
#undef USE_FLASH_W25M
|
||||
#undef USE_FLASH_W25M512
|
||||
#undef USE_FLASH_W25M02G
|
||||
#undef USE_FLASH_W25Q128FV
|
||||
#undef USE_FLASH_PY25Q128HA
|
||||
|
||||
#undef USE_TRANSPONDER
|
||||
#undef USE_SDCARD
|
||||
#undef USE_LED_STRIP
|
||||
#undef USE_SOFTSERIAL
|
||||
#undef USE_VCP
|
||||
#undef USE_ESCSERIAL
|
||||
#undef USE_SPI
|
||||
#undef USE_I2C
|
||||
#undef USE_UART
|
||||
#undef USE_USB_DETECT
|
||||
#undef USE_BEEPER
|
||||
#undef USE_EXTI
|
||||
#undef USE_TIMER_UP_CONFIG
|
||||
#undef USE_RX_SPI
|
||||
#undef USE_RX_CC2500
|
||||
#undef USE_BARO
|
||||
#undef USE_I2C_GYRO
|
||||
#undef USE_SPI_GYRO
|
||||
#undef USE_GYRO
|
||||
#undef USE_ACC
|
||||
#undef USE_MAG
|
||||
#undef USE_MAX7456
|
||||
#undef USE_VTX_RTC6705
|
||||
#undef USE_VTX_RTC6705_SOFTSPI
|
||||
#undef USE_CLI
|
||||
#undef USE_CAMERA_CONTROL
|
||||
#undef USE_RX_PWM
|
||||
#undef USE_LED_STRIP
|
||||
#undef USE_TRANSPONDER
|
||||
#undef USE_SERIAL_4WAY_BLHELI_INTERFACE
|
||||
#undef USE_SERIAL_4WAY_SK_BOOTLOADER
|
||||
#undef USE_SERIAL_4WAY_BLHELI_BOOTLOADER
|
||||
#undef USE_MOTOR
|
||||
#undef USE_SERVO
|
||||
|
||||
#define USE_VIRTUAL_GYRO
|
||||
|
||||
|
||||
|
||||
//#define USE_I2C_DEVICE_1
|
||||
//#define USE_I2C_DEVICE_2
|
||||
//#define USE_I2C_DEVICE_3
|
||||
//#define USE_I2C_DEVICE_4
|
||||
|
||||
//#define USE_VCP
|
||||
|
||||
//#define USE_SOFTSERIAL
|
||||
|
||||
#define UNIFIED_SERIAL_PORT_COUNT 0
|
||||
|
||||
#define USE_UART1
|
||||
//#define USE_UART2
|
||||
//#define USE_UART3
|
||||
//#define USE_UART4
|
||||
//#define USE_UART5
|
||||
//#define USE_UART6
|
||||
//#define USE_UART7
|
||||
//#define USE_UART8
|
||||
|
||||
#define SERIAL_PORT_COUNT (UNIFIED_SERIAL_PORT_COUNT + 1)
|
||||
|
||||
//#define USE_SPI_DEVICE_1
|
||||
//#define USE_SPI_DEVICE_2
|
||||
//#define USE_SPI_DEVICE_3
|
||||
//#define USE_SPI_DEVICE_4
|
||||
//#define USE_SPI_DEVICE_5
|
||||
//#define USE_SPI_DEVICE_6
|
||||
|
||||
#define TARGET_IO_PORTA 0xffff
|
||||
#define TARGET_IO_PORTB 0xffff
|
||||
#define TARGET_IO_PORTC 0xffff
|
||||
#define TARGET_IO_PORTD 0xffff
|
||||
#define TARGET_IO_PORTE 0xffff
|
||||
#define TARGET_IO_PORTF 0xffff
|
||||
//#define TARGET_IO_PORTG 0xffff
|
||||
|
||||
//#define USE_I2C
|
||||
//#define I2C_FULL_RECONFIGURABILITY
|
||||
|
||||
//#define USE_BEEPER
|
||||
|
||||
#ifdef USE_SDCARD
|
||||
#define USE_SDCARD_SPI
|
||||
#define USE_SDCARD_SDIO
|
||||
#endif
|
||||
|
||||
//#define USE_SPI
|
||||
//#define SPI_FULL_RECONFIGURABILITY
|
||||
//#define USE_SPI_DMA_ENABLE_LATE
|
||||
|
||||
//#define USE_USB_DETECT
|
||||
|
||||
//#define USE_ESCSERIAL
|
||||
|
||||
//#define USE_ADC
|
||||
//#define USE_EXTI
|
||||
//#define USE_TIMER_UP_CONFIG
|
||||
|
||||
#define FLASH_PAGE_SIZE ((uint32_t)0x20000) // 128K sectors
|
||||
|
||||
#if defined(USE_LED_STRIP) && !defined(USE_LED_STRIP_CACHE_MGMT)
|
||||
#define USE_LED_STRIP_CACHE_MGMT
|
||||
#endif
|
2
src/main/target/STM32H563/target.mk
Normal file
2
src/main/target/STM32H563/target.mk
Normal file
|
@ -0,0 +1,2 @@
|
|||
TARGET_MCU := STM32H563xx
|
||||
TARGET_MCU_FAMILY := STM32H5
|
Loading…
Add table
Add a link
Reference in a new issue