diff --git a/Makefile b/Makefile index ef934fa936..868bd8dd2d 100644 --- a/Makefile +++ b/Makefile @@ -229,6 +229,7 @@ CROSS_CXX := $(CCACHE) $(ARM_SDK_PREFIX)g++ CROSS_GDB := $(ARM_SDK_PREFIX)gdb OBJCOPY := $(ARM_SDK_PREFIX)objcopy OBJDUMP := $(ARM_SDK_PREFIX)objdump +READELF := $(ARM_SDK_PREFIX)readelf SIZE := $(ARM_SDK_PREFIX)size DFUSE-PACK := src/utils/dfuse-pack.py @@ -384,8 +385,14 @@ $(TARGET_BIN): $(TARGET_UNPATCHED_BIN) @echo "Patching MD5 hash into HASH section" "$(STDOUT)" $(V1) cat $(TARGET_UNPATCHED_BIN).md5 | awk '{printf("%08x: %s",64-16,$$2);}' | xxd -r - $(TARGET_EXST_HASH_SECTION_FILE) - @echo "Patching updated HASH section into $(TARGET_EXST_ELF)" "$(STDOUT)" - $(OBJCOPY) $(TARGET_ELF) $(TARGET_EXST_ELF) --update-section .exst_hash=$(TARGET_EXST_HASH_SECTION_FILE) +# For some currently unknown reason, OBJCOPY, with only input/output files, will generate a file around 2GB for the H730 unless we remove an unused-section +# As a workaround drop the ._user_heap_stack section, which is only used during build to show errors if there's not enough space for the heap/stack. +# The issue can be seen with `readelf -S $(TARGET_EXST_ELF)' vs `readelf -S $(TARGET_ELF)` + $(V1) @echo "Patching updated HASH section into $(TARGET_EXST_ELF)" "$(STDOUT)" + $(OBJCOPY) $(TARGET_ELF) $(TARGET_EXST_ELF) --remove-section ._user_heap_stack --update-section .exst_hash=$(TARGET_EXST_HASH_SECTION_FILE) + + $(V1) $(READELF) -S $(TARGET_EXST_ELF) + $(V1) $(READELF) -l $(TARGET_EXST_ELF) $(TARGET_HEX): $(TARGET_BIN) $(if $(EXST_ADJUST_VMA),,$(error "EXST_ADJUST_VMA not specified")) @@ -395,7 +402,7 @@ $(TARGET_HEX): $(TARGET_BIN) endif -$(TARGET_ELF): $(TARGET_OBJS) $(LD_SCRIPT) +$(TARGET_ELF): $(TARGET_OBJS) $(LD_SCRIPT) $(LD_SCRIPTS) @echo "Linking $(TARGET)" "$(STDOUT)" $(V1) $(CROSS_CC) -o $@ $(filter-out %.ld,$^) $(LD_FLAGS) $(V1) $(SIZE) $(TARGET_ELF) diff --git a/make/mcu/STM32H7.mk b/make/mcu/STM32H7.mk index b97156fae8..469f22f8fc 100644 --- a/make/mcu/STM32H7.mk +++ b/make/mcu/STM32H7.mk @@ -217,6 +217,28 @@ 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 diff --git a/make/targets.mk b/make/targets.mk index a45c99ad07..883d5713da 100644 --- a/make/targets.mk +++ b/make/targets.mk @@ -19,7 +19,7 @@ endif F4_TARGETS := $(F405_TARGETS) $(F411_TARGETS) $(F446_TARGETS) F7_TARGETS := $(F7X2RE_TARGETS) $(F7X5XE_TARGETS) $(F7X5XG_TARGETS) $(F7X5XI_TARGETS) $(F7X6XG_TARGETS) G4_TARGETS := $(G47X_TARGETS) -H7_TARGETS := $(H743xI_TARGETS) $(H750xB_TARGETS) $(H7A3xI_TARGETS) $(H7A3xIQ_TARGETS) $(H723xG_TARGETS) $(H725xG_TARGETS) +H7_TARGETS := $(H743xI_TARGETS) $(H750xB_TARGETS) $(H7A3xI_TARGETS) $(H7A3xIQ_TARGETS) $(H723xG_TARGETS) $(H725xG_TARGETS) $(H730xB_TARGETS) ifeq ($(filter $(TARGET),$(VALID_TARGETS)),) $(error Target '$(TARGET)' is not valid, must be one of $(VALID_TARGETS). Have you prepared a valid target.mk?) diff --git a/src/link/stm32_h730_common.ld b/src/link/stm32_h730_common.ld new file mode 100644 index 0000000000..a485128aa8 --- /dev/null +++ b/src/link/stm32_h730_common.ld @@ -0,0 +1,174 @@ + +/* Entry Point */ +ENTRY(Reset_Handler) + +/* Highest address of the user mode stack */ +_estack = ORIGIN(STACKRAM) + LENGTH(STACKRAM); /* end of RAM */ + +/* Base address where the quad spi. */ +__octospi1_start = ORIGIN(OCTOSPI1); +__octospi2_start = ORIGIN(OCTOSPI2); + +/* 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 +{ + _isr_vector_table_flash_base = LOADADDR(.isr_vector); + PROVIDE (isr_vector_table_flash_base = _isr_vector_table_flash_base); + + .isr_vector : + { + . = ALIGN(512); + PROVIDE (isr_vector_table_base = .); + KEEP(*(.isr_vector)) /* Startup code */ + . = ALIGN(4); + PROVIDE (isr_vector_table_end = .); + } >VECTAB AT> MAIN + + _ram_isr_vector_table_base = LOADADDR(.ram_isr_vector); + PROVIDE (ram_isr_vector_table_base = _ram_isr_vector_table_base); + + .ram_isr_vector (NOLOAD) : + { + . = ALIGN(512); /* Vector table offset must be multiple of 0x200 */ + PROVIDE (ram_isr_vector_table_base = .); + . += (isr_vector_table_end - isr_vector_table_base); + . = ALIGN(4); + PROVIDE (ram_isr_vector_table_end = .); + } >DTCM_RAM + + /* The program code and other data goes into MAIN */ + .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 */ + } >MAIN + + /* Critical program code goes into ITCM RAM */ + /* Copy specific fast-executing code to ITCM RAM */ + tcm_code = LOADADDR(.tcm_code); + .tcm_code : + { + . = ALIGN(4); + tcm_code_start = .; + *(.tcm_code) + *(.tcm_code*) + . = ALIGN(4); + tcm_code_end = .; + } >ITCM_RAM AT >MAIN + + .ARM.extab : + { + *(.ARM.extab* .gnu.linkonce.armextab.*) + } >MAIN + + .ARM : + { + __exidx_start = .; + *(.ARM.exidx*) __exidx_end = .; + } >MAIN + + .pg_registry : + { + PROVIDE_HIDDEN (__pg_registry_start = .); + KEEP (*(.pg_registry)) + KEEP (*(SORT(.pg_registry.*))) + PROVIDE_HIDDEN (__pg_registry_end = .); + } >MAIN + + .pg_resetdata : + { + PROVIDE_HIDDEN (__pg_resetdata_start = .); + KEEP (*(.pg_resetdata)) + PROVIDE_HIDDEN (__pg_resetdata_end = .); + } >MAIN + + /* 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 */ + } >DTCM_RAM AT >MAIN + + /* 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 >MAIN + + . = 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 +} diff --git a/src/link/stm32_h730_common_post.ld b/src/link/stm32_h730_common_post.ld new file mode 100644 index 0000000000..89b4224806 --- /dev/null +++ b/src/link/stm32_h730_common_post.ld @@ -0,0 +1,44 @@ +SECTIONS +{ + .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) } +} diff --git a/src/link/stm32_ram_h730_exst.ld b/src/link/stm32_ram_h730_exst.ld new file mode 100644 index 0000000000..46669d27fa --- /dev/null +++ b/src/link/stm32_ram_h730_exst.ld @@ -0,0 +1,143 @@ +/* +***************************************************************************** +** +** File : stm32_flash_h750_exst.ld +** +** Abstract : Linker script for STM32H750xB Device with +** 512K AXI-RAM mapped onto AXI bus on D1 domain +** 128K SRAM1 mapped on D2 domain +** 128K SRAM2 mapped on D2 domain +** 32K SRAM3 mapped on D2 domain +** 64K SRAM4 mapped on D3 domain +** 64K ITCM +** 128K DTCM +** +***************************************************************************** +*/ + +/* Entry Point */ +ENTRY(Reset_Handler) + +/* +0x00000000 to 0x0000FFFF 64K ITCM +0x20000000 to 0x2001FFFF 128K DTCM, main RAM +0x24000000 to 0x2404FFFF 320K AXI SRAM, D1 domain +0x30000000 to 0x30003FFF 16K SRAM1, D2 domain +0x30004000 to 0x30007FFF 16K SRAM2, D2 domain +0x38000000 to 0x38003FFF 16K SRAM4, D3 domain, unused +0x38800000 to 0x38800FFF 4K BACKUP SRAM, Backup domain, unused + +0x08000000 to 0x0801FFFF 128K isr vector, startup code, firmware, no config! // FLASH_Sector_0 +*/ + +/* + +For H7 EXFL (External Flash) targets a binary is built that is placed on an external device. +The bootloader will enable the memory mapped mode on the CPU which allows code to run directly from +the external flash device. + +The bootloader then executes code at the CODE_RAM address. The address of CODE_RAM is fixed to 0x90010000 +and must not be changed. + +The initial CODE_RAM is sized at 1MB. + +*/ + +/* see .exst section below */ +_exst_hash_size = 64; + +/* Specify the memory areas */ +MEMORY +{ + ITCM_RAM (rwx) : ORIGIN = 0x00000000, LENGTH = 64K + DTCM_RAM (rwx) : ORIGIN = 0x20000000, LENGTH = 128K + RAM (rwx) : ORIGIN = 0x24000000, LENGTH = 128K + 192K /* 128K AXI SRAM + 192K ITCM & AXI = 320K */ + + D2_RAM (rwx) : ORIGIN = 0x30000000, LENGTH = 32K /* SRAM1 16K + SRAM2 16K */ + D3_RAM (rwx) : ORIGIN = 0x38000000, LENGTH = 16K /* SRAM4 16K */ + + BACKUP_SRAM (rwx) : ORIGIN = 0x38800000, LENGTH = 4K + + MEMORY_B1 (rx) : ORIGIN = 0x60000000, LENGTH = 0K + + OCTOSPI2 (rx) : ORIGIN = 0x70000000, LENGTH = 256M + OCTOSPI1 (rx) : ORIGIN = 0x90000000, LENGTH = 256M + OCTOSPI1_CODE (rx): ORIGIN = ORIGIN(OCTOSPI1) + 1M, LENGTH = 1M - _exst_hash_size /* hard coded start address, as required by SPRACINGH7 boot loader, don't change! */ + EXST_HASH (rx) : ORIGIN = ORIGIN(OCTOSPI1_CODE) + LENGTH(OCTOSPI1_CODE), LENGTH = _exst_hash_size +} + +REGION_ALIAS("STACKRAM", DTCM_RAM) +REGION_ALIAS("FASTRAM", DTCM_RAM) +REGION_ALIAS("MAIN", OCTOSPI1_CODE) + +REGION_ALIAS("VECTAB", MAIN) + +INCLUDE "stm32_h730_common.ld" + +SECTIONS +{ + /* 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 >MAIN + + . = 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 + + .DMA_RW_D2 (NOLOAD) : + { + . = ALIGN(32); + PROVIDE(dmarw_start = .); + _sdmarw = .; + _dmarw_start__ = _sdmarw; + KEEP(*(.DMA_RW)) + PROVIDE(dmarw_end = .); + _edmarw = .; + _dmarw_end__ = _edmarw; + } >D2_RAM + + .DMA_RW_AXI (NOLOAD) : + { + . = ALIGN(32); + PROVIDE(dmarwaxi_start = .); + _sdmarwaxi = .; + _dmarwaxi_start__ = _sdmarwaxi; + KEEP(*(.DMA_RW_AXI)) + PROVIDE(dmarwaxi_end = .); + _edmarwaxi = .; + _dmarwaxi_end__ = _edmarwaxi; + } >RAM +} + +INCLUDE "stm32_h730_common_post.ld" +INCLUDE "stm32_ram_h730_exst_post.ld" + diff --git a/src/link/stm32_ram_h730_exst_post.ld b/src/link/stm32_ram_h730_exst_post.ld new file mode 100644 index 0000000000..97ed6c28f3 --- /dev/null +++ b/src/link/stm32_ram_h730_exst_post.ld @@ -0,0 +1,29 @@ +SECTIONS +{ + /* Create space for a hash. Currently an MD5 has is used, which is 16 */ + /* bytes long. however the last 64 bytes are RESERVED for hash related */ + .exst_hash : + { + /* 64 bytes is the size of an MD5 hashing block size. */ + . = ORIGIN(EXST_HASH); + + BYTE(0x00); /* block format */ + BYTE(0x00); /* Checksum method, 0x00 = MD5 hash */ + BYTE(0x00); /* Reserved */ + BYTE(0x00); /* Reserved */ + + /* Fill the last 60 bytes with data, including an empty hash aligned */ + + /* to the last 16 bytes. */ + FILL(0x00000000); /* Reserved */ + + . = ORIGIN(EXST_HASH) + LENGTH(EXST_HASH) - 16; + __md5_hash_address__ = .; + LONG(0x00000000); + LONG(0x00000000); + LONG(0x00000000); + LONG(0x00000000); + . = ORIGIN(EXST_HASH) + LENGTH(EXST_HASH); + __firmware_end__ = .; + } >EXST_HASH +} diff --git a/src/main/build/build_config.c b/src/main/build/build_config.c index 1e7fd73b39..e3c6fb7345 100644 --- a/src/main/build/build_config.c +++ b/src/main/build/build_config.c @@ -61,6 +61,8 @@ mcuTypeId_e getMcuTypeId(void) return MCU_TYPE_F765; #elif defined(STM32H750xx) return MCU_TYPE_H750; +#elif defined(STM32H730xx) + return MCU_TYPE_H730; #elif defined(STM32H743xx) switch (HAL_GetREVID()) { case REV_ID_Y: diff --git a/src/main/build/build_config.h b/src/main/build/build_config.h index ed2707751b..46bcbc242d 100644 --- a/src/main/build/build_config.h +++ b/src/main/build/build_config.h @@ -60,6 +60,7 @@ typedef enum { MCU_TYPE_H7A3, MCU_TYPE_H723_725, MCU_TYPE_G474, + MCU_TYPE_H730, MCU_TYPE_UNKNOWN = 255, } mcuTypeId_e; diff --git a/src/main/cli/cli.c b/src/main/cli/cli.c index 77ce46f9f6..a11b1394a9 100644 --- a/src/main/cli/cli.c +++ b/src/main/cli/cli.c @@ -310,6 +310,7 @@ static const char *mcuTypeNames[] = { "H7A3", "H723/H725", "G474", + "H730", }; static const char *configurationStates[] = { "UNCONFIGURED", "CUSTOM DEFAULTS", "CONFIGURED" }; diff --git a/src/main/config/config_streamer.c b/src/main/config/config_streamer.c index f9ee24af89..682aa9fb19 100644 --- a/src/main/config/config_streamer.c +++ b/src/main/config/config_streamer.c @@ -36,8 +36,8 @@ uint8_t eepromData[EEPROM_SIZE]; #endif -#if defined(STM32H750xx) && !(defined(CONFIG_IN_EXTERNAL_FLASH) || defined(CONFIG_IN_RAM) || defined(CONFIG_IN_SDCARD)) -#error "STM32750xx only has one flash page which contains the bootloader, no spare flash pages available, use external storage for persistent config or ram for target testing" +#if (defined(STM32H750xx) || defined(STM32H730xx)) && !(defined(CONFIG_IN_EXTERNAL_FLASH) || defined(CONFIG_IN_RAM) || defined(CONFIG_IN_SDCARD)) +#error "The configured MCU only has one flash page which contains the bootloader, no spare flash pages available, use external storage for persistent config or ram for target testing" #endif // @todo this is not strictly correct for F4/F7, where sector sizes are variable #if !defined(FLASH_PAGE_SIZE) @@ -70,7 +70,7 @@ uint8_t eepromData[EEPROM_SIZE]; # elif defined(UNIT_TEST) # define FLASH_PAGE_SIZE (0x400) // H7 -# elif defined(STM32H743xx) || defined(STM32H750xx) || defined(STM32H723xx) || defined(STM32H725xx) +# elif defined(STM32H743xx) || defined(STM32H750xx) || defined(STM32H723xx) || defined(STM32H725xx) || defined(STM32H730xx) # define FLASH_PAGE_SIZE ((uint32_t)0x20000) // 128K sectors # elif defined(STM32H7A3xx) || defined(STM32H7A3xxQ) # define FLASH_PAGE_SIZE ((uint32_t)0x2000) // 8K sectors diff --git a/src/main/drivers/adc.h b/src/main/drivers/adc.h index 15abf7fdb5..f122d2dea0 100644 --- a/src/main/drivers/adc.h +++ b/src/main/drivers/adc.h @@ -71,9 +71,11 @@ typedef enum { ADC_RSSI = 3, #if defined(STM32H7) || defined(STM32G4) // On H7 and G4, internal sensors are treated in the similar fashion as regular ADC inputs - ADC_CHANNEL_INTERNAL = 4, + ADC_CHANNEL_INTERNAL_FIRST_ID = 4, + ADC_TEMPSENSOR = 4, ADC_VREFINT = 5, + ADC_VBAT4 = 6, #endif ADC_CHANNEL_COUNT } AdcChannel; diff --git a/src/main/drivers/adc_stm32g4xx.c b/src/main/drivers/adc_stm32g4xx.c index 62d3a8885e..e3780b5fc7 100644 --- a/src/main/drivers/adc_stm32g4xx.c +++ b/src/main/drivers/adc_stm32g4xx.c @@ -485,7 +485,7 @@ void adcGetChannelValues(void) // Transfer values in conversion buffer into adcValues[] // Cache coherency should be maintained by MPU facility - for (int i = 0; i < ADC_CHANNEL_INTERNAL; i++) { + for (int i = 0; i < ADC_CHANNEL_INTERNAL_FIRST_ID; i++) { if (adcOperatingConfig[i].enabled) { adcValues[adcOperatingConfig[i].dmaIndex] = adcConversionBuffer[adcOperatingConfig[i].dmaIndex]; } diff --git a/src/main/drivers/adc_stm32h7xx.c b/src/main/drivers/adc_stm32h7xx.c index 1e74ea524c..c45bad8160 100644 --- a/src/main/drivers/adc_stm32h7xx.c +++ b/src/main/drivers/adc_stm32h7xx.c @@ -84,7 +84,7 @@ const adcDevice_t adcHardware[ADCDEV_COUNT] = { adcDevice_t adcDevice[ADCDEV_COUNT]; -#if defined(STM32H743xx) || defined(STM32H750xx) || defined(STM32H723xx) || defined(STM32H725xx) +#if defined(STM32H743xx) || defined(STM32H750xx) || defined(STM32H723xx) || defined(STM32H725xx) || defined(STM32H730xx) #define ADC_DEVICE_FOR_INTERNAL ADC_DEVICES_3 #elif defined(STM32H7A3xx) || defined(STM32H7A3xxQ) #define ADC_DEVICE_FOR_INTERNAL ADC_DEVICES_2 @@ -99,15 +99,26 @@ const adcTagMap_t adcTagMap[] = { // Keep these at the beginning for easy indexing by ADC_TAG_MAP_{VREFINT,TEMPSENSOR} #define ADC_TAG_MAP_VREFINT 0 #define ADC_TAG_MAP_TEMPSENSOR 1 +#define ADC_TAG_MAP_VBAT4 2 -#if defined(STM32H743xx) || defined(STM32H750xx) || defined(STM32H7A3xx) || defined(STM32H7A3xxQ) - { DEFIO_TAG_E__NONE, ADC_DEVICE_FOR_INTERNAL, ADC_CHANNEL_VREFINT, 18 }, - { DEFIO_TAG_E__NONE, ADC_DEVICE_FOR_INTERNAL, ADC_CHANNEL_TEMPSENSOR, 17 }, -#elif defined(STM32H723xx) || defined(STM32H725xx) - { DEFIO_TAG_E__NONE, ADC_DEVICE_FOR_INTERNAL, ADC_CHANNEL_VREFINT, 18 }, - { DEFIO_TAG_E__NONE, ADC_DEVICE_FOR_INTERNAL, ADC_CHANNEL_TEMPSENSOR, 19 }, -#endif +#if defined(STM32H723xx) || defined(STM32H725xx) || defined(STM32H730xx) // RM0468 Rev 2 Table 240. ADC interconnection + { DEFIO_TAG_E__NONE, ADC_DEVICE_FOR_INTERNAL, ADC_CHANNEL_VREFINT, 18 }, // 18 VREFINT + { DEFIO_TAG_E__NONE, ADC_DEVICE_FOR_INTERNAL, ADC_CHANNEL_TEMPSENSOR, 17 }, // 17 VSENSE + { DEFIO_TAG_E__NONE, ADC_DEVICE_FOR_INTERNAL, ADC_CHANNEL_VBAT, 16 }, // 16 VBAT/4 +#elif defined(STM32H743xx) || defined(STM32H750xx) // RM0433 Rev 7 Table 205. ADC interconnection + { DEFIO_TAG_E__NONE, ADC_DEVICE_FOR_INTERNAL, ADC_CHANNEL_VREFINT, 19 }, // 19 VREFINT + { DEFIO_TAG_E__NONE, ADC_DEVICE_FOR_INTERNAL, ADC_CHANNEL_TEMPSENSOR, 18 }, // 18 VSENSE + { DEFIO_TAG_E__NONE, ADC_DEVICE_FOR_INTERNAL, ADC_CHANNEL_VBAT, 17 }, // 17 VBAT/4 +#elif defined(STM32H7A3xx) || defined(STM32H7A3xxQ) // RM0455 Rev 5 187. ADC interconnection + { DEFIO_TAG_E__NONE, ADC_DEVICE_FOR_INTERNAL, ADC_CHANNEL_VREFINT, 19 }, // 19 VREFINT + { DEFIO_TAG_E__NONE, ADC_DEVICE_FOR_INTERNAL, ADC_CHANNEL_TEMPSENSOR, 18 }, // 18 VSENSE + { DEFIO_TAG_E__NONE, ADC_DEVICE_FOR_INTERNAL, ADC_CHANNEL_VBAT, 17 }, // 17 VBAT/4 +#elif +#error MCU not defined #endif + +#endif // USE_ADC_INTERNAL + #if defined(STM32H7A3xx) || defined(STM32H7A3xxQ) // See DS13195 Rev 6 Page 51/52 { DEFIO_TAG_E__PC0, ADC_DEVICES_12, ADC_CHANNEL_10, 10 }, @@ -203,7 +214,7 @@ void adcInitDevice(adcDevice_t *adcdev, int channelCount) // Enable circular DMA. // ADC3 of H72X and H73X has a special way of doing this. -#if defined(STM32H723xx) || defined(STM32H725xx) +#if defined(STM32H723xx) || defined(STM32H725xx) || defined(STM32H730xx) if (adcdev->ADCx == ADC3) { hadc->Init.DMAContinuousRequests = ENABLE; } else @@ -240,10 +251,10 @@ int adcFindTagMapEntry(ioTag_t tag) } // H743, H750 and H7A3 seems to use 16-bit precision value, -// while H723 and H725 seems to use 12-bit precision value. +// while H723, H725 and H730 seems to use 12-bit precision value. #if defined(STM32H743xx) || defined(STM32H750xx) || defined(STM32H7A3xx) || defined(STM32H7A3xxQ) #define VREFINT_CAL_SHIFT 4 -#elif defined(STM32H723xx) || defined(STM32H725xx) +#elif defined(STM32H723xx) || defined(STM32H725xx) || defined(STM32H730xx) #define VREFINT_CAL_SHIFT 0 #else #error Unknown MCU @@ -292,13 +303,22 @@ void adcInit(const adcConfig_t *config) int map; int dev; +#ifdef USE_ADC_INTERNAL if (i == ADC_TEMPSENSOR) { map = ADC_TAG_MAP_TEMPSENSOR; dev = ffs(adcTagMap[map].devices) - 1; } else if (i == ADC_VREFINT) { map = ADC_TAG_MAP_VREFINT; dev = ffs(adcTagMap[map].devices) - 1; + } else if (i == ADC_VBAT4) { + map = ADC_TAG_MAP_VBAT4; + dev = ffs(adcTagMap[map].devices) - 1; } else { +#else + { +#endif + dev = ADC_CFG_TO_DEV(adcOperatingConfig[i].adcDevice); + if (!adcOperatingConfig[i].tag) { continue; } @@ -507,7 +527,7 @@ void adcGetChannelValues(void) // Transfer values in conversion buffer into adcValues[] // Cache coherency should be maintained by MPU facility - for (int i = 0; i < ADC_CHANNEL_INTERNAL; i++) { + for (int i = 0; i < ADC_CHANNEL_INTERNAL_FIRST_ID; i++) { if (adcOperatingConfig[i].enabled) { adcValues[adcOperatingConfig[i].dmaIndex] = adcConversionBuffer[adcOperatingConfig[i].dmaIndex]; } diff --git a/src/main/drivers/dma_reqmap.c b/src/main/drivers/dma_reqmap.c index 7579e62766..0f3da3b7e7 100644 --- a/src/main/drivers/dma_reqmap.c +++ b/src/main/drivers/dma_reqmap.c @@ -250,7 +250,7 @@ static const dmaPeripheralMapping_t dmaPeripheralMapping[] = { #ifdef USE_ADC REQMAP(ADC, 1), REQMAP(ADC, 2), -#if defined(STM32H743xx) || defined(STM32H750xx) || defined(STM32H723xx) || defined(STM32H725xx) +#if defined(STM32H743xx) || defined(STM32H750xx) || defined(STM32H723xx) || defined(STM32H725xx) || defined(STM32H730xx) REQMAP(ADC, 3), #endif #endif diff --git a/src/main/drivers/io.c b/src/main/drivers/io.c index 6bb1920eb1..8487bb3fb8 100644 --- a/src/main/drivers/io.c +++ b/src/main/drivers/io.c @@ -90,7 +90,7 @@ const struct ioPortDef_s ioPortDefs[] = { { RCC_AHB4(GPIOF) }, { RCC_AHB4(GPIOG) }, { RCC_AHB4(GPIOH) }, -#if !(defined(STM32H723xx) || defined(STM32H725xx)) +#if !(defined(STM32H723xx) || defined(STM32H725xx) || defined(STM32H730xx)) { RCC_AHB4(GPIOI) }, #endif }; diff --git a/src/main/drivers/sdio_h7xx.c b/src/main/drivers/sdio_h7xx.c index db9bd304a8..52e5e12697 100644 --- a/src/main/drivers/sdio_h7xx.c +++ b/src/main/drivers/sdio_h7xx.c @@ -281,8 +281,11 @@ static SD_Error_t SD_DoInit(void) hsd1.Init.BusWide = SDMMC_BUS_WIDE_1B; // FIXME untested } hsd1.Init.HardwareFlowControl = SDMMC_HARDWARE_FLOW_CONTROL_ENABLE; +#if defined(STM32H730xx) + hsd1.Init.ClockDiv = 2; // 200Mhz / (2 * 2 ) = 50Mhz, used for "UltraHigh speed SD card" only, see HAL_SD_ConfigWideBusOperation, SDMMC_HSpeed_CLK_DIV, SDMMC_NSpeed_CLK_DIV +#else hsd1.Init.ClockDiv = 1; // 200Mhz / (2 * 1 ) = 100Mhz, used for "UltraHigh speed SD card" only, see HAL_SD_ConfigWideBusOperation, SDMMC_HSpeed_CLK_DIV, SDMMC_NSpeed_CLK_DIV - +#endif status = HAL_SD_Init(&hsd1); // Will call HAL_SD_MspInit if (status != HAL_OK) { diff --git a/src/main/drivers/system_stm32h7xx.c b/src/main/drivers/system_stm32h7xx.c index 6ada6e0b21..49f96f831b 100644 --- a/src/main/drivers/system_stm32h7xx.c +++ b/src/main/drivers/system_stm32h7xx.c @@ -84,7 +84,7 @@ void systemInit(void) #elif defined(STM32H7A3xx) || defined(STM32H7A3xxQ) __HAL_RCC_AHBSRAM1_CLK_ENABLE(); __HAL_RCC_AHBSRAM2_CLK_ENABLE(); -#elif defined(STM32H723xx) || defined(STM32H725xx) +#elif defined(STM32H723xx) || defined(STM32H725xx) || defined(STM32H730xx) __HAL_RCC_D2SRAM1_CLK_ENABLE(); __HAL_RCC_D2SRAM2_CLK_ENABLE(); #else @@ -137,7 +137,7 @@ void systemResetToBootloader(bootloaderRequestType_e requestType) } -#if defined(STM32H743xx) || defined(STM32H750xx) || defined(STM32H723xx) || defined(STM32H725xx) +#if defined(STM32H743xx) || defined(STM32H750xx) || defined(STM32H723xx) || defined(STM32H725xx) || defined(STM32H730xx) #define SYSMEMBOOT_VECTOR_TABLE ((uint32_t *)0x1ff09800) #elif defined(STM32H7A3xx) || defined(STM32H7A3xxQ) #define SYSMEMBOOT_VECTOR_TABLE ((uint32_t *)0x1ff0a000) diff --git a/src/main/drivers/timer_stm32h7xx.c b/src/main/drivers/timer_stm32h7xx.c index 89b3ef7dd4..5177076a79 100644 --- a/src/main/drivers/timer_stm32h7xx.c +++ b/src/main/drivers/timer_stm32h7xx.c @@ -173,7 +173,7 @@ uint32_t timerClock(TIM_TypeDef *tim) // "Ratio between clock timer and pclk" // (Tables are the same, just D2 or CD difference) -#if defined(STM32H743xx) || defined(STM32H750xx) || defined(STM32H723xx) || defined(STM32H725xx) +#if defined(STM32H743xx) || defined(STM32H750xx) || defined(STM32H723xx) || defined(STM32H725xx) || defined(STM32H730xx) #define PERIPH_PRESCALER(bus) ((RCC->D2CFGR & RCC_D2CFGR_D2PPRE ## bus) >> RCC_D2CFGR_D2PPRE ## bus ## _Pos) #elif defined(STM32H7A3xx) || defined(STM32H7A3xxQ) #define PERIPH_PRESCALER(bus) ((RCC->CDCFGR2 & RCC_CDCFGR2_CDPPRE ## bus) >> RCC_CDCFGR2_CDPPRE ## bus ## _Pos) diff --git a/src/main/drivers/usb_msc_h7xx.c b/src/main/drivers/usb_msc_h7xx.c index 9fbf62c8ee..96f5d2a4b4 100644 --- a/src/main/drivers/usb_msc_h7xx.c +++ b/src/main/drivers/usb_msc_h7xx.c @@ -63,7 +63,7 @@ uint8_t mscStart(void) USBD_Init(&USBD_Device, &VCP_Desc, 0); - /** Regsiter class */ + /** Register class */ USBD_RegisterClass(&USBD_Device, USBD_MSC_CLASS); /** Register interface callbacks */ diff --git a/src/main/platform.h b/src/main/platform.h index 462f85ffbd..b19aca6516 100644 --- a/src/main/platform.h +++ b/src/main/platform.h @@ -49,7 +49,7 @@ #define STM32G4 #endif -#elif defined(STM32H743xx) || defined(STM32H750xx) || defined(STM32H7A3xx) || defined(STM32H7A3xxQ) || defined(STM32H723xx) || defined(STM32H725xx) +#elif defined(STM32H743xx) || defined(STM32H750xx) || defined(STM32H7A3xx) || defined(STM32H7A3xxQ) || defined(STM32H723xx) || defined(STM32H725xx) || defined(STM32H730xx) #include "stm32h7xx.h" #include "stm32h7xx_hal.h" #include "system_stm32h7xx.h" diff --git a/src/main/startup/startup_stm32h730xx.s b/src/main/startup/startup_stm32h730xx.s new file mode 100644 index 0000000000..c534faa807 --- /dev/null +++ b/src/main/startup/startup_stm32h730xx.s @@ -0,0 +1,805 @@ +/** + ****************************************************************************** + * @file startup_stm32h730xx.s + * @author MCD Application Team + * @brief STM32H730xx Devices vector table for GCC based toolchain. + * This module performs: + * - Set the initial SP + * - Set the initial PC == Reset_Handler, + * - Set the vector table entries with the exceptions ISR address + * - Branches to main in the C library (which eventually + * calls main()). + * After Reset the Cortex-M processor is in Thread mode, + * priority is Privileged, and the Stack is set to Main. + ****************************************************************************** + * @attention + * + *

© Copyright (c) 2019 STMicroelectronics. + * All rights reserved.

+ * + * This software component is licensed by ST under BSD 3-Clause license, + * the "License"; You may not use this file except in compliance with the + * License. You may obtain a copy of the License at: + * opensource.org/licenses/BSD-3-Clause + * + ****************************************************************************** + */ + + .syntax unified + .cpu cortex-m7 + .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 +/* stack used for SystemInit_ExtMemCtl; always internal RAM used */ + +/** + * @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 sp, =_estack /* set stack pointer */ + + bl persistentObjectInit + +/* Copy the data segment initializers from flash to SRAM */ + movs r1, #0 + b LoopCopyDataInit + +CopyDataInit: + ldr r3, =_sidata + ldr r3, [r3, r1] + str r3, [r0, r1] + adds r1, r1, #4 + +LoopCopyDataInit: + ldr r0, =_sdata + ldr r3, =_edata + adds r2, r0, r1 + cmp r2, r3 + bcc CopyDataInit + ldr r2, =_sbss + b LoopFillZerobss +/* Zero fill the bss segment. */ +FillZerobss: + movs r3, #0 + str r3, [r2], #4 + +LoopFillZerobss: + ldr r3, = _ebss + cmp r2, r3 + bcc FillZerobss + +/*-----*/ + ldr r2, =_ssram2 + b LoopFillZerosram2 +/* Zero fill the sram2 segment. */ +FillZerosram2: + movs r3, #0 + str r3, [r2], #4 + +LoopFillZerosram2: + ldr r3, = _esram2 + cmp r2, r3 + bcc FillZerosram2 + + ldr r2, =_sfastram_bss + b LoopFillZerofastram_bss +/* Zero fill the fastram_bss segment. */ +FillZerofastram_bss: + movs r3, #0 + str r3, [r2], #4 + +LoopFillZerofastram_bss: + ldr r3, = _efastram_bss + cmp r2, r3 + bcc FillZerofastram_bss +/*-----*/ + +/* Mark the heap and stack */ + ldr r2, =_heap_stack_begin + b LoopMarkHeapStack + +MarkHeapStack: + movs r3, 0xa5a5a5a5 + str r3, [r2], #4 + +LoopMarkHeapStack: + ldr r3, = _heap_stack_end + cmp r2, r3 + bcc MarkHeapStack + +/* Call the clock system intitialization function.*/ + bl SystemInit +/* Call static constructors */ +/* bl __libc_init_array */ +/* Call the application's entry point.*/ + bl main + bx lr +.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 minimal vector table for a Cortex M. 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 + .size g_pfnVectors, .-g_pfnVectors + + +g_pfnVectors: + .word _estack + .word Reset_Handler + + .word NMI_Handler + .word HardFault_Handler + .word MemManage_Handler + .word BusFault_Handler + .word UsageFault_Handler + .word 0 + .word 0 + .word 0 + .word 0 + .word SVC_Handler + .word DebugMon_Handler + .word 0 + .word PendSV_Handler + .word SysTick_Handler + + /* External Interrupts */ + .word WWDG_IRQHandler /* Window WatchDog */ + .word PVD_AVD_IRQHandler /* PVD/AVD through EXTI Line detection */ + .word TAMP_STAMP_IRQHandler /* Tamper and TimeStamps through the EXTI line */ + .word RTC_WKUP_IRQHandler /* RTC Wakeup through the EXTI line */ + .word FLASH_IRQHandler /* FLASH */ + .word RCC_IRQHandler /* RCC */ + .word EXTI0_IRQHandler /* EXTI Line0 */ + .word EXTI1_IRQHandler /* EXTI Line1 */ + .word EXTI2_IRQHandler /* EXTI Line2 */ + .word EXTI3_IRQHandler /* EXTI Line3 */ + .word EXTI4_IRQHandler /* EXTI Line4 */ + .word DMA1_Stream0_IRQHandler /* DMA1 Stream 0 */ + .word DMA1_Stream1_IRQHandler /* DMA1 Stream 1 */ + .word DMA1_Stream2_IRQHandler /* DMA1 Stream 2 */ + .word DMA1_Stream3_IRQHandler /* DMA1 Stream 3 */ + .word DMA1_Stream4_IRQHandler /* DMA1 Stream 4 */ + .word DMA1_Stream5_IRQHandler /* DMA1 Stream 5 */ + .word DMA1_Stream6_IRQHandler /* DMA1 Stream 6 */ + .word ADC_IRQHandler /* ADC1, ADC2 and ADC3s */ + .word FDCAN1_IT0_IRQHandler /* FDCAN1 interrupt line 0 */ + .word FDCAN2_IT0_IRQHandler /* FDCAN2 interrupt line 0 */ + .word FDCAN1_IT1_IRQHandler /* FDCAN1 interrupt line 1 */ + .word FDCAN2_IT1_IRQHandler /* FDCAN2 interrupt line 1 */ + .word EXTI9_5_IRQHandler /* External Line[9:5]s */ + .word TIM1_BRK_IRQHandler /* TIM1 Break interrupt */ + .word TIM1_UP_IRQHandler /* TIM1 Update interrupt */ + .word TIM1_TRG_COM_IRQHandler /* TIM1 Trigger and Commutation interrupt */ + .word TIM1_CC_IRQHandler /* TIM1 Capture Compare */ + .word TIM2_IRQHandler /* TIM2 */ + .word TIM3_IRQHandler /* TIM3 */ + .word TIM4_IRQHandler /* TIM4 */ + .word I2C1_EV_IRQHandler /* I2C1 Event */ + .word I2C1_ER_IRQHandler /* I2C1 Error */ + .word I2C2_EV_IRQHandler /* I2C2 Event */ + .word I2C2_ER_IRQHandler /* I2C2 Error */ + .word SPI1_IRQHandler /* SPI1 */ + .word SPI2_IRQHandler /* SPI2 */ + .word USART1_IRQHandler /* USART1 */ + .word USART2_IRQHandler /* USART2 */ + .word USART3_IRQHandler /* USART3 */ + .word EXTI15_10_IRQHandler /* External Line[15:10]s */ + .word RTC_Alarm_IRQHandler /* RTC Alarm (A and B) through EXTI Line */ + .word 0 /* Reserved */ + .word TIM8_BRK_TIM12_IRQHandler /* TIM8 Break and TIM12 */ + .word TIM8_UP_TIM13_IRQHandler /* TIM8 Update and TIM13 */ + .word TIM8_TRG_COM_TIM14_IRQHandler /* TIM8 Trigger and Commutation and TIM14 */ + .word TIM8_CC_IRQHandler /* TIM8 Capture Compare */ + .word DMA1_Stream7_IRQHandler /* DMA1 Stream7 */ + .word FMC_IRQHandler /* FMC */ + .word SDMMC1_IRQHandler /* SDMMC1 */ + .word TIM5_IRQHandler /* TIM5 */ + .word SPI3_IRQHandler /* SPI3 */ + .word UART4_IRQHandler /* UART4 */ + .word UART5_IRQHandler /* UART5 */ + .word TIM6_DAC_IRQHandler /* TIM6 and DAC1&2 underrun errors */ + .word TIM7_IRQHandler /* TIM7 */ + .word DMA2_Stream0_IRQHandler /* DMA2 Stream 0 */ + .word DMA2_Stream1_IRQHandler /* DMA2 Stream 1 */ + .word DMA2_Stream2_IRQHandler /* DMA2 Stream 2 */ + .word DMA2_Stream3_IRQHandler /* DMA2 Stream 3 */ + .word DMA2_Stream4_IRQHandler /* DMA2 Stream 4 */ + .word ETH_IRQHandler /* Ethernet */ + .word ETH_WKUP_IRQHandler /* Ethernet Wakeup through EXTI line */ + .word FDCAN_CAL_IRQHandler /* FDCAN calibration unit interrupt*/ + .word 0 /* Reserved */ + .word 0 /* Reserved */ + .word 0 /* Reserved */ + .word 0 /* Reserved */ + .word DMA2_Stream5_IRQHandler /* DMA2 Stream 5 */ + .word DMA2_Stream6_IRQHandler /* DMA2 Stream 6 */ + .word DMA2_Stream7_IRQHandler /* DMA2 Stream 7 */ + .word USART6_IRQHandler /* USART6 */ + .word I2C3_EV_IRQHandler /* I2C3 event */ + .word I2C3_ER_IRQHandler /* I2C3 error */ + .word OTG_HS_EP1_OUT_IRQHandler /* USB OTG HS End Point 1 Out */ + .word OTG_HS_EP1_IN_IRQHandler /* USB OTG HS End Point 1 In */ + .word OTG_HS_WKUP_IRQHandler /* USB OTG HS Wakeup through EXTI */ + .word OTG_HS_IRQHandler /* USB OTG HS */ + .word DCMI_PSSI_IRQHandler /* DCMI, PSSI */ + .word CRYP_IRQHandler /* CRYP */ + .word HASH_RNG_IRQHandler /* Hash and Rng */ + .word FPU_IRQHandler /* FPU */ + .word UART7_IRQHandler /* UART7 */ + .word UART8_IRQHandler /* UART8 */ + .word SPI4_IRQHandler /* SPI4 */ + .word SPI5_IRQHandler /* SPI5 */ + .word SPI6_IRQHandler /* SPI6 */ + .word SAI1_IRQHandler /* SAI1 */ + .word LTDC_IRQHandler /* LTDC */ + .word LTDC_ER_IRQHandler /* LTDC error */ + .word DMA2D_IRQHandler /* DMA2D */ + .word 0 /* Reserved */ + .word OCTOSPI1_IRQHandler /* OCTOSPI1 */ + .word LPTIM1_IRQHandler /* LPTIM1 */ + .word CEC_IRQHandler /* HDMI_CEC */ + .word I2C4_EV_IRQHandler /* I2C4 Event */ + .word I2C4_ER_IRQHandler /* I2C4 Error */ + .word SPDIF_RX_IRQHandler /* SPDIF_RX */ + .word 0 /* Reserved */ + .word 0 /* Reserved */ + .word 0 /* Reserved */ + .word 0 /* Reserved */ + .word DMAMUX1_OVR_IRQHandler /* DMAMUX1 Overrun interrupt */ + .word 0 /* Reserved */ + .word 0 /* Reserved */ + .word 0 /* Reserved */ + .word 0 /* Reserved */ + .word 0 /* Reserved */ + .word 0 /* Reserved */ + .word 0 /* Reserved */ + .word DFSDM1_FLT0_IRQHandler /* DFSDM Filter0 Interrupt */ + .word DFSDM1_FLT1_IRQHandler /* DFSDM Filter1 Interrupt */ + .word DFSDM1_FLT2_IRQHandler /* DFSDM Filter2 Interrupt */ + .word DFSDM1_FLT3_IRQHandler /* DFSDM Filter3 Interrupt */ + .word 0 /* Reserved */ + .word SWPMI1_IRQHandler /* Serial Wire Interface 1 global interrupt */ + .word TIM15_IRQHandler /* TIM15 global Interrupt */ + .word TIM16_IRQHandler /* TIM16 global Interrupt */ + .word TIM17_IRQHandler /* TIM17 global Interrupt */ + .word MDIOS_WKUP_IRQHandler /* MDIOS Wakeup Interrupt */ + .word MDIOS_IRQHandler /* MDIOS global Interrupt */ + .word 0 /* Reserved */ + .word MDMA_IRQHandler /* MDMA global Interrupt */ + .word 0 /* Reserved */ + .word SDMMC2_IRQHandler /* SDMMC2 global Interrupt */ + .word HSEM1_IRQHandler /* HSEM1 global Interrupt */ + .word 0 /* Reserved */ + .word ADC3_IRQHandler /* ADC3 global Interrupt */ + .word DMAMUX2_OVR_IRQHandler /* DMAMUX Overrun interrupt */ + .word BDMA_Channel0_IRQHandler /* BDMA Channel 0 global Interrupt */ + .word BDMA_Channel1_IRQHandler /* BDMA Channel 1 global Interrupt */ + .word BDMA_Channel2_IRQHandler /* BDMA Channel 2 global Interrupt */ + .word BDMA_Channel3_IRQHandler /* BDMA Channel 3 global Interrupt */ + .word BDMA_Channel4_IRQHandler /* BDMA Channel 4 global Interrupt */ + .word BDMA_Channel5_IRQHandler /* BDMA Channel 5 global Interrupt */ + .word BDMA_Channel6_IRQHandler /* BDMA Channel 6 global Interrupt */ + .word BDMA_Channel7_IRQHandler /* BDMA Channel 7 global Interrupt */ + .word COMP1_IRQHandler /* COMP1 global Interrupt */ + .word LPTIM2_IRQHandler /* LP TIM2 global interrupt */ + .word LPTIM3_IRQHandler /* LP TIM3 global interrupt */ + .word LPTIM4_IRQHandler /* LP TIM4 global interrupt */ + .word LPTIM5_IRQHandler /* LP TIM5 global interrupt */ + .word LPUART1_IRQHandler /* LP UART1 interrupt */ + .word 0 /* Reserved */ + .word CRS_IRQHandler /* Clock Recovery Global Interrupt */ + .word ECC_IRQHandler /* ECC diagnostic Global Interrupt */ + .word SAI4_IRQHandler /* SAI4 global interrupt */ + .word DTS_IRQHandler /* Digital Temperature Sensor interrupt */ + .word 0 /* Reserved */ + .word WAKEUP_PIN_IRQHandler /* Interrupt for all 6 wake-up pins */ + .word OCTOSPI2_IRQHandler /* OCTOSPI2 Interrupt */ + .word OTFDEC1_IRQHandler /* OTFDEC1 Interrupt */ + .word OTFDEC2_IRQHandler /* OTFDEC2 Interrupt */ + .word FMAC_IRQHandler /* FMAC Interrupt */ + .word CORDIC_IRQHandler /* CORDIC Interrupt */ + .word UART9_IRQHandler /* UART9 Interrupt */ + .word USART10_IRQHandler /* UART10 Interrupt */ + .word I2C5_EV_IRQHandler /* I2C5 Event Interrupt */ + .word I2C5_ER_IRQHandler /* I2C5 Error Interrupt */ + .word FDCAN3_IT0_IRQHandler /* FDCAN3 interrupt line 0 */ + .word FDCAN3_IT1_IRQHandler /* FDCAN3 interrupt line 1 */ + .word TIM23_IRQHandler /* TIM23 global interrupt */ + .word TIM24_IRQHandler /* TIM24 global interrupt */ + +/******************************************************************************* +* +* 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 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 TAMP_STAMP_IRQHandler + .thumb_set TAMP_STAMP_IRQHandler,Default_Handler + + .weak RTC_WKUP_IRQHandler + .thumb_set RTC_WKUP_IRQHandler,Default_Handler + + .weak FLASH_IRQHandler + .thumb_set FLASH_IRQHandler,Default_Handler + + .weak RCC_IRQHandler + .thumb_set RCC_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 DMA1_Stream0_IRQHandler + .thumb_set DMA1_Stream0_IRQHandler,Default_Handler + + .weak DMA1_Stream1_IRQHandler + .thumb_set DMA1_Stream1_IRQHandler,Default_Handler + + .weak DMA1_Stream2_IRQHandler + .thumb_set DMA1_Stream2_IRQHandler,Default_Handler + + .weak DMA1_Stream3_IRQHandler + .thumb_set DMA1_Stream3_IRQHandler,Default_Handler + + .weak DMA1_Stream4_IRQHandler + .thumb_set DMA1_Stream4_IRQHandler,Default_Handler + + .weak DMA1_Stream5_IRQHandler + .thumb_set DMA1_Stream5_IRQHandler,Default_Handler + + .weak DMA1_Stream6_IRQHandler + .thumb_set DMA1_Stream6_IRQHandler,Default_Handler + + .weak ADC_IRQHandler + .thumb_set ADC_IRQHandler,Default_Handler + + .weak FDCAN1_IT0_IRQHandler + .thumb_set FDCAN1_IT0_IRQHandler,Default_Handler + + .weak FDCAN2_IT0_IRQHandler + .thumb_set FDCAN2_IT0_IRQHandler,Default_Handler + + .weak FDCAN1_IT1_IRQHandler + .thumb_set FDCAN1_IT1_IRQHandler,Default_Handler + + .weak FDCAN2_IT1_IRQHandler + .thumb_set FDCAN2_IT1_IRQHandler,Default_Handler + + .weak EXTI9_5_IRQHandler + .thumb_set EXTI9_5_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 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 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 EXTI15_10_IRQHandler + .thumb_set EXTI15_10_IRQHandler,Default_Handler + + .weak RTC_Alarm_IRQHandler + .thumb_set RTC_Alarm_IRQHandler,Default_Handler + + .weak TIM8_BRK_TIM12_IRQHandler + .thumb_set TIM8_BRK_TIM12_IRQHandler,Default_Handler + + .weak TIM8_UP_TIM13_IRQHandler + .thumb_set TIM8_UP_TIM13_IRQHandler,Default_Handler + + .weak TIM8_TRG_COM_TIM14_IRQHandler + .thumb_set TIM8_TRG_COM_TIM14_IRQHandler,Default_Handler + + .weak TIM8_CC_IRQHandler + .thumb_set TIM8_CC_IRQHandler,Default_Handler + + .weak DMA1_Stream7_IRQHandler + .thumb_set DMA1_Stream7_IRQHandler,Default_Handler + + .weak FMC_IRQHandler + .thumb_set FMC_IRQHandler,Default_Handler + + .weak SDMMC1_IRQHandler + .thumb_set SDMMC1_IRQHandler,Default_Handler + + .weak TIM5_IRQHandler + .thumb_set TIM5_IRQHandler,Default_Handler + + .weak SPI3_IRQHandler + .thumb_set SPI3_IRQHandler,Default_Handler + + .weak UART4_IRQHandler + .thumb_set UART4_IRQHandler,Default_Handler + + .weak UART5_IRQHandler + .thumb_set UART5_IRQHandler,Default_Handler + + .weak TIM6_DAC_IRQHandler + .thumb_set TIM6_DAC_IRQHandler,Default_Handler + + .weak TIM7_IRQHandler + .thumb_set TIM7_IRQHandler,Default_Handler + + .weak DMA2_Stream0_IRQHandler + .thumb_set DMA2_Stream0_IRQHandler,Default_Handler + + .weak DMA2_Stream1_IRQHandler + .thumb_set DMA2_Stream1_IRQHandler,Default_Handler + + .weak DMA2_Stream2_IRQHandler + .thumb_set DMA2_Stream2_IRQHandler,Default_Handler + + .weak DMA2_Stream3_IRQHandler + .thumb_set DMA2_Stream3_IRQHandler,Default_Handler + + .weak DMA2_Stream4_IRQHandler + .thumb_set DMA2_Stream4_IRQHandler,Default_Handler + + .weak ETH_IRQHandler + .thumb_set ETH_IRQHandler,Default_Handler + + .weak ETH_WKUP_IRQHandler + .thumb_set ETH_WKUP_IRQHandler,Default_Handler + + .weak FDCAN_CAL_IRQHandler + .thumb_set FDCAN_CAL_IRQHandler,Default_Handler + + .weak DMA2_Stream5_IRQHandler + .thumb_set DMA2_Stream5_IRQHandler,Default_Handler + + .weak DMA2_Stream6_IRQHandler + .thumb_set DMA2_Stream6_IRQHandler,Default_Handler + + .weak DMA2_Stream7_IRQHandler + .thumb_set DMA2_Stream7_IRQHandler,Default_Handler + + .weak USART6_IRQHandler + .thumb_set USART6_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 OTG_HS_EP1_OUT_IRQHandler + .thumb_set OTG_HS_EP1_OUT_IRQHandler,Default_Handler + + .weak OTG_HS_EP1_IN_IRQHandler + .thumb_set OTG_HS_EP1_IN_IRQHandler,Default_Handler + + .weak OTG_HS_WKUP_IRQHandler + .thumb_set OTG_HS_WKUP_IRQHandler,Default_Handler + + .weak OTG_HS_IRQHandler + .thumb_set OTG_HS_IRQHandler,Default_Handler + + .weak DCMI_PSSI_IRQHandler + .thumb_set DCMI_PSSI_IRQHandler,Default_Handler + + .weak CRYP_IRQHandler + .thumb_set CRYP_IRQHandler,Default_Handler + + .weak HASH_RNG_IRQHandler + .thumb_set HASH_RNG_IRQHandler,Default_Handler + + .weak FPU_IRQHandler + .thumb_set FPU_IRQHandler,Default_Handler + + .weak UART7_IRQHandler + .thumb_set UART7_IRQHandler,Default_Handler + + .weak UART8_IRQHandler + .thumb_set UART8_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 SAI1_IRQHandler + .thumb_set SAI1_IRQHandler,Default_Handler + + .weak LTDC_IRQHandler + .thumb_set LTDC_IRQHandler,Default_Handler + + .weak LTDC_ER_IRQHandler + .thumb_set LTDC_ER_IRQHandler,Default_Handler + + .weak DMA2D_IRQHandler + .thumb_set DMA2D_IRQHandler,Default_Handler + + .weak OCTOSPI1_IRQHandler + .thumb_set OCTOSPI1_IRQHandler,Default_Handler + + .weak LPTIM1_IRQHandler + .thumb_set LPTIM1_IRQHandler,Default_Handler + + .weak CEC_IRQHandler + .thumb_set CEC_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 SPDIF_RX_IRQHandler + .thumb_set SPDIF_RX_IRQHandler,Default_Handler + + .weak DMAMUX1_OVR_IRQHandler + .thumb_set DMAMUX1_OVR_IRQHandler,Default_Handler + + .weak DFSDM1_FLT0_IRQHandler + .thumb_set DFSDM1_FLT0_IRQHandler,Default_Handler + + .weak DFSDM1_FLT1_IRQHandler + .thumb_set DFSDM1_FLT1_IRQHandler,Default_Handler + + .weak DFSDM1_FLT2_IRQHandler + .thumb_set DFSDM1_FLT2_IRQHandler,Default_Handler + + .weak DFSDM1_FLT3_IRQHandler + .thumb_set DFSDM1_FLT3_IRQHandler,Default_Handler + + .weak SWPMI1_IRQHandler + .thumb_set SWPMI1_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 MDIOS_WKUP_IRQHandler + .thumb_set MDIOS_WKUP_IRQHandler,Default_Handler + + .weak MDIOS_IRQHandler + .thumb_set MDIOS_IRQHandler,Default_Handler + + .weak MDMA_IRQHandler + .thumb_set MDMA_IRQHandler,Default_Handler + + .weak SDMMC2_IRQHandler + .thumb_set SDMMC2_IRQHandler,Default_Handler + + .weak HSEM1_IRQHandler + .thumb_set HSEM1_IRQHandler,Default_Handler + + .weak ADC3_IRQHandler + .thumb_set ADC3_IRQHandler,Default_Handler + + .weak DMAMUX2_OVR_IRQHandler + .thumb_set DMAMUX2_OVR_IRQHandler,Default_Handler + + .weak BDMA_Channel0_IRQHandler + .thumb_set BDMA_Channel0_IRQHandler,Default_Handler + + .weak BDMA_Channel1_IRQHandler + .thumb_set BDMA_Channel1_IRQHandler,Default_Handler + + .weak BDMA_Channel2_IRQHandler + .thumb_set BDMA_Channel2_IRQHandler,Default_Handler + + .weak BDMA_Channel3_IRQHandler + .thumb_set BDMA_Channel3_IRQHandler,Default_Handler + + .weak BDMA_Channel4_IRQHandler + .thumb_set BDMA_Channel4_IRQHandler,Default_Handler + + .weak BDMA_Channel5_IRQHandler + .thumb_set BDMA_Channel5_IRQHandler,Default_Handler + + .weak BDMA_Channel6_IRQHandler + .thumb_set BDMA_Channel6_IRQHandler,Default_Handler + + .weak BDMA_Channel7_IRQHandler + .thumb_set BDMA_Channel7_IRQHandler,Default_Handler + + .weak COMP1_IRQHandler + .thumb_set COMP1_IRQHandler,Default_Handler + + .weak LPTIM2_IRQHandler + .thumb_set LPTIM2_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 LPUART1_IRQHandler + .thumb_set LPUART1_IRQHandler,Default_Handler + + .weak CRS_IRQHandler + .thumb_set CRS_IRQHandler,Default_Handler + + .weak ECC_IRQHandler + .thumb_set ECC_IRQHandler,Default_Handler + + .weak SAI4_IRQHandler + .thumb_set SAI4_IRQHandler,Default_Handler + + .weak DTS_IRQHandler + .thumb_set DTS_IRQHandler,Default_Handler + + .weak WAKEUP_PIN_IRQHandler + .thumb_set WAKEUP_PIN_IRQHandler,Default_Handler + + .weak OCTOSPI2_IRQHandler + .thumb_set OCTOSPI2_IRQHandler,Default_Handler + + .weak OTFDEC1_IRQHandler + .thumb_set OTFDEC1_IRQHandler,Default_Handler + + .weak OTFDEC2_IRQHandler + .thumb_set OTFDEC2_IRQHandler,Default_Handler + + .weak FMAC_IRQHandler + .thumb_set FMAC_IRQHandler,Default_Handler + + .weak CORDIC_IRQHandler + .thumb_set CORDIC_IRQHandler,Default_Handler + + .weak UART9_IRQHandler + .thumb_set UART9_IRQHandler,Default_Handler + + .weak USART10_IRQHandler + .thumb_set USART10_IRQHandler,Default_Handler + + .weak I2C5_EV_IRQHandler + .thumb_set I2C5_EV_IRQHandler,Default_Handler + + .weak I2C5_ER_IRQHandler + .thumb_set I2C5_ER_IRQHandler,Default_Handler + + .weak FDCAN3_IT0_IRQHandler + .thumb_set FDCAN3_IT0_IRQHandler,Default_Handler + + .weak FDCAN3_IT1_IRQHandler + .thumb_set FDCAN3_IT1_IRQHandler,Default_Handler + + .weak TIM23_IRQHandler + .thumb_set TIM23_IRQHandler,Default_Handler + + .weak TIM24_IRQHandler + .thumb_set TIM24_IRQHandler,Default_Handler + +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ + diff --git a/src/main/startup/system_stm32h7xx.c b/src/main/startup/system_stm32h7xx.c index 3e257ea5c9..890ed7ee57 100644 --- a/src/main/startup/system_stm32h7xx.c +++ b/src/main/startup/system_stm32h7xx.c @@ -307,6 +307,33 @@ pllConfig_t pll1Config72x = { #define MCU_RCC_CRS_SYNC_SOURCE RCC_CRS_SYNC_SOURCE_USB1 +#elif defined(STM32H730xx) + +// Nominal max 550MHz, but >520Mhz requires ECC to be disabled, CPUFREQ_BOOST set in option bytes and prevents OCTOSPI clock from running at the correct clock speed. +// 4.9.24 FLASH option status register 2 (FLASH_OPTSR2_CUR) +// "Bit 2CPUFREQ_BOOST: CPU frequency boost status bitThis bit indicates whether the CPU frequency can be boosted or not. When it is set, the ECC on ITCM and DTCM are no more used" +// ... +// So use 520Mhz so that OCTOSPI clk can be 200Mhz with OCTOPSI prescaler 2 via PLL2R or 130Mhz with OCTOPSI prescaler 1 via PLL1Q + +pllConfig_t pll1Config73x = { + .clockMhz = 520, + .m = 2, + .n = 130, + .p = 1, + .q = 4, + .r = 2, + .vos = PWR_REGULATOR_VOLTAGE_SCALE0, + .vciRange = RCC_PLL1VCIRANGE_1, +}; + +#define MCU_HCLK_DIVIDER RCC_HCLK_DIV2 + +// RM0468 (Rev.2) Table 16. +// 520MHz (AXI Interface clock) at VOS0 is 3WS +#define MCU_FLASH_LATENCY FLASH_LATENCY_3 + +#define MCU_RCC_CRS_SYNC_SOURCE RCC_CRS_SYNC_SOURCE_USB1 + #else #error Unknown MCU type #endif @@ -340,6 +367,8 @@ static void SystemClockHSE_Config(void) pll1Config = &pll1Config7A3; #elif defined(STM32H723xx) || defined(STM32H725xx) pll1Config = &pll1Config72x; +#elif defined(STM32H730xx) + pll1Config = &pll1Config73x; #else #error Unknown MCU type #endif @@ -452,8 +481,8 @@ void SystemClock_Config(void) { // Configure power supply -#if defined(STM32H743xx) || defined(STM32H750xx) || defined(STM32H723xx) || defined(STM32H7A3xx) - // Legacy H7 devices (H743, H750) and newer but SMPS-less devices(H7A3, H723) +#if defined(STM32H743xx) || defined(STM32H750xx) || defined(STM32H723xx) || defined(STM32H7A3xx) || defined(STM32H730xx) + // Legacy H7 devices (H743, H750) and newer but SMPS-less devices(H7A3, H723, H730) HAL_PWREx_ConfigSupply(PWR_LDO_SUPPLY); @@ -597,6 +626,8 @@ void SystemClock_Config(void) HAL_RCCEx_PeriphCLKConfig(&RCC_PeriphClkInit); #ifdef USE_SDCARD_SDIO + __HAL_RCC_SDMMC1_CLK_ENABLE(); // FIXME enable SDMMC1 or SDMMC2 depending on target. + RCC_PeriphClkInit.PeriphClockSelection = RCC_PERIPHCLK_SDMMC; # if (HSE_VALUE != 8000000) @@ -613,14 +644,30 @@ void SystemClock_Config(void) RCC_PeriphClkInit.PLL2.PLL2P = 2; // 800Mhz / 2 = 400Mhz RCC_PeriphClkInit.PLL2.PLL2Q = 3; // 800Mhz / 3 = 266Mhz // 133Mhz can be derived from this for for QSPI if flash chip supports the speed. RCC_PeriphClkInit.PLL2.PLL2R = 4; // 800Mhz / 4 = 200Mhz // HAL LIBS REQUIRE 200MHZ SDMMC CLOCK, see HAL_SD_ConfigWideBusOperation, SDMMC_HSpeed_CLK_DIV, SDMMC_NSpeed_CLK_DIV - RCC_PeriphClkInit.SdmmcClockSelection = RCC_SDMMCCLKSOURCE_PLL2; - HAL_RCCEx_PeriphCLKConfig(&RCC_PeriphClkInit); +# elif defined(STM32H730xx) + RCC_PeriphClkInit.PLL2.PLL2M = 8; + RCC_PeriphClkInit.PLL2.PLL2N = 400; // 8Mhz (Oscillator Frequency) / 8 (PLL2M) = 1.0 * 400 (PLL2N) = 400Mhz. + RCC_PeriphClkInit.PLL2.PLL2VCOSEL = RCC_PLL2VCOMEDIUM; // Medium VCO range:150 to 420 MHz + RCC_PeriphClkInit.PLL2.PLL2RGE = RCC_PLL2VCIRANGE_0; // PLL2 input between 1 and 2Mhz (1.0) + RCC_PeriphClkInit.PLL2.PLL2FRACN = 0; + + RCC_PeriphClkInit.PLL2.PLL2P = 3; // 400Mhz / 3 = 133Mhz // ADC does't like much higher when using PLL2P + RCC_PeriphClkInit.PLL2.PLL2Q = 3; // 400Mhz / 3 = 133Mhz // SPI6 does't like much higher when using PLL2Q + RCC_PeriphClkInit.PLL2.PLL2R = 2; // 400Mhz / 2 = 200Mhz // HAL LIBS REQUIRE 200MHZ SDMMC CLOCK, see HAL_SD_ConfigWideBusOperation, SDMMC_HSpeed_CLK_DIV, SDMMC_NSpeed_CLK_DIV # else # error Unknown MCU type # endif + RCC_PeriphClkInit.SdmmcClockSelection = RCC_SDMMCCLKSOURCE_PLL2; + HAL_RCCEx_PeriphCLKConfig(&RCC_PeriphClkInit); # endif #endif + RCC_PeriphClkInit.PeriphClockSelection = RCC_PERIPHCLK_ADC; + RCC_PeriphClkInit.AdcClockSelection = RCC_ADCCLKSOURCE_CLKP; + HAL_RCCEx_PeriphCLKConfig(&RCC_PeriphClkInit); + + // TODO H730 OCTOSPI clock for 100Mhz flash chips should use PLL2R at 200Mhz + // Configure MCO clocks for clock test/verification // Possible sources for MCO1: @@ -711,7 +758,7 @@ void SystemInit (void) RCC->CR |= RCC_CR_HSEON; RCC->CR |= RCC_CR_HSI48ON; -#if defined(STM32H743xx) || defined(STM32H750xx) +#if defined(STM32H743xx) || defined(STM32H750xx) || defined(STM32H723xx) || defined(STM32H725xx) || defined(STM32H730xx) /* Reset D1CFGR register */ RCC->D1CFGR = 0x00000000; @@ -768,17 +815,29 @@ void SystemInit (void) /* Configure the Vector Table location add offset address ------------------*/ #if defined(VECT_TAB_SRAM) -#if defined(STM32H743xx) || defined(STM32H750xx) + #if defined(STM32H743xx) || defined(STM32H750xx) || defined(STM32H723xx) || defined(STM32H725xx) || defined(STM32H730xx) SCB->VTOR = D1_AXISRAM_BASE | VECT_TAB_OFFSET; /* Vector Table Relocation in Internal ITCMSRAM */ -#elif defined(STM32H7A3xx) || defined(STM32H7A3xxQ) + #elif defined(STM32H7A3xx) || defined(STM32H7A3xxQ) SCB->VTOR = CD_AXISRAM_BASE | VECT_TAB_OFFSET; /* Vector Table Relocation in Internal ITCMSRAM */ -#else -#error Unknown MCU type -#endif + #else + #error Unknown MCU type + #endif #elif defined(USE_EXST) - extern void *isr_vector_table_base; + extern uint8_t isr_vector_table_base; SCB->VTOR = (uint32_t)&isr_vector_table_base; + #if defined(STM32H730xx) + /* Configure the Vector Table location add offset address ------------------*/ + + extern uint8_t isr_vector_table_flash_base; + extern uint8_t isr_vector_table_end; + + extern uint8_t ram_isr_vector_table_base; + + memcpy(&ram_isr_vector_table_base, &isr_vector_table_flash_base, (size_t) (&isr_vector_table_end - &isr_vector_table_base)); + + SCB->VTOR = (uint32_t)&ram_isr_vector_table_base; + #endif #else SCB->VTOR = FLASH_BANK1_BASE | VECT_TAB_OFFSET; /* Vector Table Relocation in Internal FLASH */ #endif diff --git a/src/main/vcp_hal/usbd_conf_stm32h7xx.c b/src/main/vcp_hal/usbd_conf_stm32h7xx.c index c294dcb2bc..bbe8290c3b 100644 --- a/src/main/vcp_hal/usbd_conf_stm32h7xx.c +++ b/src/main/vcp_hal/usbd_conf_stm32h7xx.c @@ -76,7 +76,7 @@ PCD_HandleTypeDef hpcd; PCD BSP Routines *******************************************************************************/ -#if defined(USE_USB_FS) && !(defined(STM32H7A3xx) || defined(STM32H7A3xxQ) || defined(STM32H723xx) || defined(STM32H725xx)) +#if defined(USE_USB_FS) && !(defined(STM32H7A3xx) || defined(STM32H7A3xxQ) || defined(STM32H723xx) || defined(STM32H725xx) || defined(STM32H730xx)) void OTG_FS_IRQHandler(void) #else void OTG_HS_IRQHandler(void) @@ -254,6 +254,33 @@ void HAL_PCD_MspInit(PCD_HandleTypeDef * hpcd) /* Enable USB FS Interrupt */ HAL_NVIC_EnableIRQ(OTG_HS_IRQn); +#elif defined(STM32H730xx) + UNUSED(hpcd); + + __HAL_RCC_GPIOA_CLK_ENABLE(); + + /**USB GPIO Configuration + PA11 ------> USB_DM + PA12 ------> USB_DP + */ + GPIO_InitStruct.Pin = GPIO_PIN_11|GPIO_PIN_12; + GPIO_InitStruct.Mode = GPIO_MODE_AF_PP; + GPIO_InitStruct.Pull = GPIO_NOPULL; + GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_VERY_HIGH; + GPIO_InitStruct.Alternate = GPIO_AF10_OTG1_HS; + HAL_GPIO_Init(GPIOA, &GPIO_InitStruct); + + /* Enable USB HS Clocks */ + __HAL_RCC_USB1_OTG_HS_CLK_ENABLE(); + + HAL_NVIC_SetPriority(OTG_HS_EP1_OUT_IRQn, 6, 0); + HAL_NVIC_EnableIRQ(OTG_HS_EP1_OUT_IRQn); + + HAL_NVIC_SetPriority(OTG_HS_EP1_IN_IRQn, 6, 0); + HAL_NVIC_EnableIRQ(OTG_HS_EP1_IN_IRQn); + + HAL_NVIC_SetPriority(OTG_HS_IRQn, 7, 0); + HAL_NVIC_EnableIRQ(OTG_HS_IRQn); #else #error Unknown MCU type @@ -290,7 +317,7 @@ void HAL_PCD_MspDeInit(PCD_HandleTypeDef * hpcd) __HAL_RCC_USB1_OTG_HS_CLK_DISABLE(); __HAL_RCC_USB1_OTG_HS_ULPI_CLK_DISABLE(); } -#elif defined(STM32H723xx) || defined(STM32H725xx) +#elif defined(STM32H723xx) || defined(STM32H725xx) || defined(STM32H730xx) if(hpcd->Instance==USB1_OTG_HS) { /* Peripheral clock disable */ @@ -463,7 +490,7 @@ USBD_StatusTypeDef USBD_LL_Init(USBD_HandleTypeDef * pdev) { #ifdef USE_USB_FS /* Set LL Driver parameters */ -#if defined(STM32H7A3xx) || defined(STM32H7A3xxQ) || defined(STM32H723xx) || defined(STM32H725xx) +#if defined(STM32H7A3xx) || defined(STM32H7A3xxQ) || defined(STM32H723xx) || defined(STM32H725xx) || defined(STM32H730xx) hpcd.Instance = USB1_OTG_HS; #elif defined(STM32H743xx) || defined(STM32H750xx) hpcd.Instance = USB2_OTG_FS;