Merge pull request #10318 from jflyper/bfdev-h7-h7a3

[H7] H7A3 support
This commit is contained in:
Michael Keller 2020-11-05 02:11:20 +13:00 committed by GitHub
commit 4bf3e99e9c
No known key found for this signature in database
GPG Key ID: 4AEE18F83AFDEB23
17 changed files with 1363 additions and 49 deletions

View File

@ -153,8 +153,9 @@ ARCH_FLAGS = -mthumb -mcpu=cortex-m7 -mfloat-abi=hard -mfpu=fpv5-sp-d16 -fs
DEVICE_FLAGS = -DUSE_HAL_DRIVER -DUSE_FULL_LL_DRIVER
#
# H743xI : 2M FLASH, 1M RAM (H753xI also)
# H743xG : 1M FLASH, 1M RAM (H753xG also)
# H743xI : 2M FLASH, 512KB AXI SRAM + 512KB D2 & D3 SRAM (H753xI also)
# H743xG : 1M FLASH, 512KB AXI SRAM + 512KB D2 & D3 SRAM (H753xG also)
# H7A3xI : 2M FLASH, 1MB AXI SRAM + 160KB AHB & SRD SRAM
# H750xB : 128K FLASH, 1M RAM
#
ifeq ($(TARGET),$(filter $(TARGET),$(H743xI_TARGETS)))
@ -172,6 +173,36 @@ MCU_FLASH_SIZE := FIRMWARE_SIZE
DEFAULT_LD_SCRIPT = $(LINKER_DIR)/stm32_ram_h743.ld
endif
else ifeq ($(TARGET),$(filter $(TARGET),$(H7A3xIQ_TARGETS)))
DEVICE_FLAGS += -DSTM32H7A3xxQ
DEFAULT_LD_SCRIPT = $(LINKER_DIR)/stm32_flash_h7a3_2m.ld
STARTUP_SRC = startup_stm32h7a3xx.s
MCU_FLASH_SIZE := 2048
DEVICE_FLAGS += -DMAX_MPU_REGIONS=16
ifeq ($(RAM_BASED),yes)
FIRMWARE_SIZE := 448
# TARGET_FLASH now becomes the amount of RAM memory that is occupied by the firmware
# and the maximum size of the data stored on the external storage device.
MCU_FLASH_SIZE := FIRMWARE_SIZE
DEFAULT_LD_SCRIPT = $(LINKER_DIR)/stm32_flash_h7a3_ram_based.ld
endif
else ifeq ($(TARGET),$(filter $(TARGET),$(H7A3xI_TARGETS)))
DEVICE_FLAGS += -DSTM32H7A3xx
DEFAULT_LD_SCRIPT = $(LINKER_DIR)/stm32_flash_h7a3_2m.ld
STARTUP_SRC = startup_stm32h7a3xx.s
MCU_FLASH_SIZE := 2048
DEVICE_FLAGS += -DMAX_MPU_REGIONS=16
ifeq ($(RAM_BASED),yes)
FIRMWARE_SIZE := 448
# TARGET_FLASH now becomes the amount of RAM memory that is occupied by the firmware
# and the maximum size of the data stored on the external storage device.
MCU_FLASH_SIZE := FIRMWARE_SIZE
DEFAULT_LD_SCRIPT = $(LINKER_DIR)/stm32_flash_h7a3_ram_based.ld
endif
else ifeq ($(TARGET),$(filter $(TARGET),$(H750xB_TARGETS)))
DEVICE_FLAGS += -DSTM32H750xx
DEFAULT_LD_SCRIPT = $(LINKER_DIR)/stm32_flash_h750_128k.ld

View File

@ -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 := $(G4X3_TARGETS)
H7_TARGETS := $(H743xI_TARGETS) $(H750xB_TARGETS)
H7_TARGETS := $(H743xI_TARGETS) $(H750xB_TARGETS) $(H7A3xI_TARGETS) $(H7A3xIQ_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?)

View File

@ -0,0 +1,289 @@
/*
*****************************************************************************
**
** File : stm32_flash_h7a3_2m.ld
**
** Abstract : Linker script for STM32H743xI Device with
**
** Note
** Flash sector (erase unit) is 8KB
**
*****************************************************************************
*/
/* Entry Point */
ENTRY(Reset_Handler)
/*
0x00000000 to 0x0000FFFF 64K ITCM
0x20000000 to 0x2001FFFF 128K DTCM
0x24000000 to 0x2403FFFF 256K AXI SRAM1, CD domain, main RAM
0x24040000 to 0x2409FFFF 384K AXI SRAM2, CD domain, main RAM
0x240A0000 to 0x240FFFFF 384K AXI SRAM3, CD domain, main RAM
0x30000000 to 0x3000FFFF 64K AHB_SRAM1, CD domain, unused
0x30010000 to 0x3001FFFF 64K AHB_SRAM2, CD domain, unused
0x38000000 to 0x3800FFFF 32K SRD_SRAM, SRD domain, unused
0x38800000 to 0x38800FFF 4K BKP_SRAM, Backup domain, unused
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 = 16K /* 2 sectors */
FLASH_CONFIG (r) : ORIGIN = 0x08020000, LENGTH = 16K /* 2 sectors */
FLASH1 (rx) : ORIGIN = 0x08040000, LENGTH = 2016K
ITCM_RAM (rwx) : ORIGIN = 0x00000000, LENGTH = 64K
DTCM_RAM (rwx) : ORIGIN = 0x20000000, LENGTH = 128K
RAM (rwx) : ORIGIN = 0x24000000, LENGTH = 1024K
D2_RAM (rwx) : ORIGIN = 0x30000000, LENGTH = 128K /* AHB_SRAM1 + AHB_SRAM2 */
MEMORY_B1 (rx) : ORIGIN = 0x60000000, LENGTH = 0K
}
REGION_ALIAS("STACKRAM", DTCM_RAM)
REGION_ALIAS("FASTRAM", DTCM_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
/* 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 >FLASH1
.ARM.extab :
{
*(.ARM.extab* .gnu.linkonce.armextab.*)
} >FLASH
.ARM :
{
__exidx_start = .;
*(.ARM.exidx*) __exidx_end = .;
} >FLASH
.pg_registry :
{
PROVIDE_HIDDEN (__pg_registry_start = .);
KEEP (*(.pg_registry))
KEEP (*(SORT(.pg_registry.*)))
PROVIDE_HIDDEN (__pg_registry_end = .);
} >FLASH
.pg_resetdata :
{
PROVIDE_HIDDEN (__pg_resetdata_start = .);
KEEP (*(.pg_resetdata))
PROVIDE_HIDDEN (__pg_resetdata_end = .);
} >FLASH
/* 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 >FLASH
/* 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_RAM 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 >FLASH
. = 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
.DMA_RAM (NOLOAD) :
{
. = ALIGN(32);
PROVIDE(dmaram_start = .);
_sdmaram = .;
_dmaram_start__ = _sdmaram;
KEEP(*(.DMA_RAM))
PROVIDE(dmaram_end = .);
_edmaram = .;
_dmaram_end__ = _edmaram;
} >D2_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
.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) }
}

View File

@ -72,6 +72,8 @@ mcuTypeId_e getMcuTypeId(void)
default:
return MCU_TYPE_H743_REV_UNKNOWN;
}
#elif defined(STM32H7A3xx) || defined(STM32H7A3xxQ)
return MCU_TYPE_H7A3;
#else
return MCU_TYPE_UNKNOWN;
#endif

View File

@ -57,6 +57,7 @@ typedef enum {
MCU_TYPE_H743_REV_Y,
MCU_TYPE_H743_REV_X,
MCU_TYPE_H743_REV_V,
MCU_TYPE_H7A3,
MCU_TYPE_UNKNOWN = 255,
} mcuTypeId_e;

View File

@ -305,6 +305,7 @@ static const char *mcuTypeNames[] = {
"H743 (Rev.Y)",
"H743 (Rev.X)",
"H743 (Rev.V)",
"H7A3",
};
static const char *configurationStates[] = { "UNCONFIGURED", "CUSTOM DEFAULTS", "CONFIGURED" };

View File

@ -72,6 +72,8 @@ uint8_t eepromData[EEPROM_SIZE];
// H7
# elif defined(STM32H743xx) || defined(STM32H750xx)
# define FLASH_PAGE_SIZE ((uint32_t)0x20000) // 128K sectors
# elif defined(STM32H7A3xx) || defined(STM32H7A3xxQ)
# define FLASH_PAGE_SIZE ((uint32_t)0x2000) // 8K sectors
// G4
# elif defined(STM32G4)
# define FLASH_PAGE_SIZE ((uint32_t)0x800) // 2K page
@ -272,7 +274,7 @@ static uint32_t getFLASHSectorForEEPROM(void)
}
}
#elif defined(STM32H743xx) || defined(STM32G4)
#elif defined(STM32H743xx) || defined(STM32G4) || defined(STM32H7A3xx) || defined(STM32H7A3xxQ)
/*
MCUs with uniform array of equal size sectors, handled in two banks having contiguous address.
(Devices with non-contiguous flash layout is not currently useful anyways.)
@ -282,6 +284,11 @@ H743
Bank 1 0x08000000 - 0x080FFFFF 128KB * 8
Bank 2 0x08100000 - 0x081FFFFF 128KB * 8
H7A3
2 bank * 128 sector/bank * 8KB/sector (2MB)
Bank 1 0x08000000 - 0x080FFFFF 8KB * 128
Bank 2 0x08100000 - 0x081FFFFF 8KB * 128
G473/474 in dual bank mode
2 bank * 128 sector/bank * 2KB/sector (512KB)
Bank 1 0x08000000 - 0x0803FFFF 2KB * 128
@ -294,6 +301,8 @@ FLASH_BANK_SIZE constant is set to one half of the available flash size in HAL.
#if defined(STM32H743xx)
#define FLASH_PAGE_PER_BANK 8
#elif defined(STM32H7A3xx) || defined(STM32H7A3xxQ)
#define FLASH_PAGE_PER_BANK 128
#elif defined(STM32G4)
#define FLASH_PAGE_PER_BANK 128
// These are not defined in CMSIS like H7
@ -420,7 +429,9 @@ static int write_word(config_streamer_t *c, config_streamer_buffer_align_type_t
if (c->address % FLASH_PAGE_SIZE == 0) {
FLASH_EraseInitTypeDef EraseInitStruct = {
.TypeErase = FLASH_TYPEERASE_SECTORS,
#if !(defined(STM32H7A3xx) || defined(STM32H7A3xxQ))
.VoltageRange = FLASH_VOLTAGE_RANGE_3, // 2.7-3.6V
#endif
.NbSectors = 1
};
getFLASHSectorForEEPROM(c->address, &EraseInitStruct.Banks, &EraseInitStruct.Sector);

View File

@ -29,9 +29,12 @@
#ifdef CONFIG_IN_EXTERNAL_FLASH
#define CONFIG_STREAMER_BUFFER_SIZE 8 // Must not be greater than the smallest flash page size of all compiled-in flash devices.
typedef uint32_t config_streamer_buffer_align_type_t;
#elif defined(STM32H7)
#elif defined(STM32H743xx) || defined(STM32H750xx)
#define CONFIG_STREAMER_BUFFER_SIZE 32 // Flash word = 256-bits
typedef uint64_t config_streamer_buffer_align_type_t;
#elif defined(STM32H7A3xx) || defined(STM32H7A3xxQ)
#define CONFIG_STREAMER_BUFFER_SIZE 16 // Flash word = 128-bits
typedef uint64_t config_streamer_buffer_align_type_t;
#elif defined(STM32G4)
#define CONFIG_STREAMER_BUFFER_SIZE 8 // Flash word = 64-bits
typedef uint64_t config_streamer_buffer_align_type_t;

View File

@ -79,7 +79,9 @@ const adcDevice_t adcHardware[ADCDEV_COUNT] = {
.channel = DMA_REQUEST_ADC2,
#endif
},
// ADC3 can be serviced by BDMA also, but we settle for DMA1 or 2 (for now).
#if !(defined(STM32H7A3xx) || defined(STM32H7A3xxQ))
// ADC3 is not available on H7A3
// On H743 and H750, ADC3 can be serviced by BDMA also, but we settle for DMA1 or 2 (for now).
{
.ADCx = ADC3_INSTANCE,
.rccADC = RCC_AHB4(ADC3),
@ -88,10 +90,19 @@ const adcDevice_t adcHardware[ADCDEV_COUNT] = {
.channel = DMA_REQUEST_ADC3,
#endif
}
#endif // !STM32H7A3
};
adcDevice_t adcDevice[ADCDEV_COUNT];
#if defined(STM32H743xx) || defined(STM32H750xx)
#define ADC_DEVICE_FOR_INTERNAL ADC_DEVICES_3
#elif defined(STM32H7A3xx) || defined(STM32H7A3xxQ)
#define ADC_DEVICE_FOR_INTERNAL ADC_DEVICES_2
#else
#error Unknown MCU
#endif
/* note these could be packed up for saving space */
const adcTagMap_t adcTagMap[] = {
#ifdef USE_ADC_INTERNAL
@ -99,8 +110,8 @@ 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
{ DEFIO_TAG_E__NONE, ADC_DEVICES_3, ADC_CHANNEL_VREFINT, 18 },
{ DEFIO_TAG_E__NONE, ADC_DEVICES_3, ADC_CHANNEL_TEMPSENSOR, 19 },
{ 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
// Inputs available for all packages
{ DEFIO_TAG_E__PC0, ADC_DEVICES_123, ADC_CHANNEL_10, 10 },
@ -216,7 +227,7 @@ int adcFindTagMapEntry(ioTag_t tag)
void adcInitCalibrationValues(void)
{
adcVREFINTCAL = *(uint16_t *)VREFINT_CAL_ADDR >> 4;
adcVREFINTCAL = *VREFINT_CAL_ADDR >> 4;
adcTSCAL1 = *TEMPSENSOR_CAL1_ADDR >> 4;
adcTSCAL2 = *TEMPSENSOR_CAL2_ADDR >> 4;
adcTSSlopeK = (TEMPSENSOR_CAL2_TEMP - TEMPSENSOR_CAL1_TEMP) * 1000 / (adcTSCAL2 - adcTSCAL1);
@ -259,10 +270,10 @@ void adcInit(const adcConfig_t *config)
if (i == ADC_TEMPSENSOR) {
map = ADC_TAG_MAP_TEMPSENSOR;
dev = ADCDEV_3;
dev = ffs(adcTagMap[map].devices) - 1;
} else if (i == ADC_VREFINT) {
map = ADC_TAG_MAP_VREFINT;
dev = ADCDEV_3;
dev = ffs(adcTagMap[map].devices) - 1;
} else {
if (!adcOperatingConfig[i].tag) {
continue;

View File

@ -235,12 +235,21 @@ dmaResource_t* dmaGetRefByIdentifier(const dmaIdentifier_e identifier);
// HAL library has a macro for this, but it is extremely inefficient in that it compares
// the address against all possible values.
// Here, we just compare the address against regions of memory.
// If it's not in D3 peripheral area, then it's DMA1/2 and it's stream based.
#if defined(STM32H7A3xx) || defined(STM32H7A3xxQ)
// For H7A3, if it's lower than CD_AHB2PERIPH_BASE, then it's DMA1/2 and it's stream based.
// If not, it's BDMA and it's channel based.
#define IS_DMA_ENABLED(reg) \
((uint32_t)(reg) < CD_AHB2PERIPH_BASE) ? \
(((DMA_Stream_TypeDef *)(reg))->CR & DMA_SxCR_EN) : \
(((BDMA_Channel_TypeDef *)(reg))->CCR & BDMA_CCR_EN)
#else
// For H743 and H750, if it's not in D3 peripheral area, then it's DMA1/2 and it's stream based.
// If not, it's BDMA and it's channel based.
#define IS_DMA_ENABLED(reg) \
((uint32_t)(reg) < D3_AHB1PERIPH_BASE) ? \
(((DMA_Stream_TypeDef *)(reg))->CR & DMA_SxCR_EN) : \
(((BDMA_Channel_TypeDef *)(reg))->CCR & BDMA_CCR_EN)
#endif
#elif defined(STM32G4)
#define IS_DMA_ENABLED(reg) (((DMA_ARCH_TYPE *)(reg))->CCR & DMA_CCR_EN)
// Missing __HAL_DMA_SET_COUNTER in FW library V1.0.0

View File

@ -228,8 +228,10 @@ static const dmaPeripheralMapping_t dmaPeripheralMapping[] = {
#ifdef USE_ADC
REQMAP(ADC, 1),
REQMAP(ADC, 2),
#if defined(STM32H743xx) || defined(STM32H750xx)
REQMAP(ADC, 3),
#endif
#endif
#ifdef USE_UART
REQMAP_DIR(UART, 1, TX),

View File

@ -77,9 +77,16 @@ void systemInit(void)
//RCC_ClearFlag();
#if defined(STM32H743xx) || defined(STM32H750xx)
__HAL_RCC_D2SRAM1_CLK_ENABLE();
__HAL_RCC_D2SRAM2_CLK_ENABLE();
__HAL_RCC_D2SRAM3_CLK_ENABLE();
#elif defined(STM32H7A3xx) || defined(STM32H7A3xxQ)
__HAL_RCC_AHBSRAM1_CLK_ENABLE();
__HAL_RCC_AHBSRAM2_CLK_ENABLE();
#else
#error Unknown MCU
#endif
#ifdef USE_MCO_OUTPUTS
configureMasterClockOutputs();
@ -129,7 +136,13 @@ void systemResetToBootloader(bootloaderRequestType_e requestType)
}
#if defined(STM32H743xx) || defined(STM32H750xx)
#define SYSMEMBOOT_VECTOR_TABLE ((uint32_t *)0x1ff09800)
#elif defined(STM32H7A3xx) || defined(STM32H7A3xxQ)
#define SYSMEMBOOT_VECTOR_TABLE ((uint32_t *)0x1ff0a000)
#else
#error Unknown MCU
#endif
typedef void *(*bootJumpPtr)(void);

View File

@ -160,6 +160,7 @@ const timerHardware_t fullTimerHardware[FULL_TIMER_CHANNEL_COUNT] = {
};
#endif
uint32_t timerClock(TIM_TypeDef *tim)
{
int timpre;
@ -167,16 +168,27 @@ uint32_t timerClock(TIM_TypeDef *tim)
uint32_t ppre;
// Implement the table:
// RM0433 "Table 48. Ratio between clock timer and pclk"
// RM0433 (Rev 6) Table 52.
// RM0455 (Rev 3) Table 55.
// "Ratio between clock timer and pclk"
// (Tables are the same, just D2 or CD difference)
#if defined(STM32H743xx) || defined(STM32H750xx)
#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)
#else
#error Unknown MCU type
#endif
if (tim == TIM1 || tim == TIM8 || tim == TIM15 || tim == TIM16 || tim == TIM17) {
// Timers on APB2
pclk = HAL_RCC_GetPCLK2Freq();
ppre = (RCC->D2CFGR & RCC_D2CFGR_D2PPRE2) >> RCC_D2CFGR_D2PPRE2_Pos;
ppre = PERIPH_PRESCALER(2);
} else {
// Timers on APB1
pclk = HAL_RCC_GetPCLK1Freq();
ppre = (RCC->D2CFGR & RCC_D2CFGR_D2PPRE1) >> RCC_D2CFGR_D2PPRE1_Pos;
ppre = PERIPH_PRESCALER(1);
}
timpre = (RCC->CFGR & RCC_CFGR_TIMPRE) ? 1 : 0;
@ -189,5 +201,7 @@ uint32_t timerClock(TIM_TypeDef *tim)
};
return pclk * periphToKernel[index];
#undef PERIPH_PRESCALER
}
#endif

View File

@ -49,7 +49,7 @@
#define STM32G4
#endif
#elif defined(STM32H743xx) || defined(STM32H750xx)
#elif defined(STM32H743xx) || defined(STM32H750xx) || defined(STM32H7A3xx) || defined(STM32H7A3xxQ)
#include "stm32h7xx.h"
#include "stm32h7xx_hal.h"
#include "system_stm32h7xx.h"

View File

@ -0,0 +1,779 @@
/**
******************************************************************************
* @file startup_stm32h7a3xx.s
* @author MCD Application Team
* @brief STM32H7B3xx 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
*
* <h2><center>&copy; Copyright (c) 2019 STMicroelectronics.
* All rights reserved.</center></h2>
*
* 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
/* Zero fill the bss segment. */
ldr r2, =_sbss
b LoopFillZerobss
FillZerobss:
movs r3, #0
str r3, [r2], #4
LoopFillZerobss:
ldr r3, = _ebss
cmp r2, r3
bcc FillZerobss
/* Zero fill the sram2 segment. */
ldr r2, =_ssram2
b LoopFillZerosram2
FillZerosram2:
movs r3, #0
str r3, [r2], #4
LoopFillZerosram2:
ldr r3, = _esram2
cmp r2, r3
bcc FillZerosram2
/* Zero fill the fastram_bss segment. */
ldr r2, =_sfastram_bss
b LoopFillZerofastram_bss
FillZerofastram_bss:
movs r3, #0
str r3, [r2], #4
LoopFillZerofastram_bss:
ldr r3, = _efastram_bss
cmp r2, r3
bcc FillZerofastram_bss
/* 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_PVM_IRQHandler /* PVD/PVM through EXTI Line detection */
.word RTC_TAMP_STAMP_CSS_LSE_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 DFSDM2_IRQHandler /* DFSDM2 Interrupt */
.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 0 /* Reserved */
.word 0 /* Reserved */
.word FDCAN_CAL_IRQHandler /* FDCAN calibration unit interrupt*/
.word DFSDM1_FLT4_IRQHandler /* DFSDM Filter4 Interrupt */
.word DFSDM1_FLT5_IRQHandler /* DFSDM Filter5 Interrupt */
.word DFSDM1_FLT6_IRQHandler /* DFSDM Filter6 Interrupt */
.word DFSDM1_FLT7_IRQHandler /* DFSDM Filter7 Interrupt */
.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 0 /* Reserved */
.word RNG_IRQHandler /* 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 SAI2_IRQHandler /* SAI2 */
.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 JPEG_IRQHandler /* JPEG global Interrupt */
.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 DAC2_IRQHandler /* DAC2 global Interrupt */
.word DMAMUX2_OVR_IRQHandler /* DMAMUX Overrun interrupt */
.word BDMA2_Channel0_IRQHandler /* BDMA2 Channel 0 global Interrupt */
.word BDMA2_Channel1_IRQHandler /* BDMA2 Channel 1 global Interrupt */
.word BDMA2_Channel2_IRQHandler /* BDMA2 Channel 2 global Interrupt */
.word BDMA2_Channel3_IRQHandler /* BDMA2 Channel 3 global Interrupt */
.word BDMA2_Channel4_IRQHandler /* BDMA2 Channel 4 global Interrupt */
.word BDMA2_Channel5_IRQHandler /* BDMA2 Channel 5 global Interrupt */
.word BDMA2_Channel6_IRQHandler /* BDMA2 Channel 6 global Interrupt */
.word BDMA2_Channel7_IRQHandler /* BDMA2 Channel 7 global Interrupt */
.word COMP_IRQHandler /* COMP global Interrupt */
.word LPTIM2_IRQHandler /* LP TIM2 global interrupt */
.word LPTIM3_IRQHandler /* LP TIM3 global interrupt */
.word UART9_IRQHandler /* UART9 global interrupt */
.word USART10_IRQHandler /* USART10 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 0 /* Reserved */
.word DTS_IRQHandler /* DTS */
.word 0 /* Reserved */
.word WAKEUP_PIN_IRQHandler /* Interrupt for all 6 wake-up pins */
.word OCTOSPI2_IRQHandler /* OCTOSPI2 */
.word 0 /* Reserved */
.word 0 /* Reserved */
.word GFXMMU_IRQHandler /* GFXMMU */
.word BDMA1_IRQHandler /* BDMA1 */
/*******************************************************************************
*
* 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_PVM_IRQHandler
.thumb_set PVD_PVM_IRQHandler,Default_Handler
.weak RTC_TAMP_STAMP_CSS_LSE_IRQHandler
.thumb_set RTC_TAMP_STAMP_CSS_LSE_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 DFSDM2_IRQHandler
.thumb_set DFSDM2_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 FDCAN_CAL_IRQHandler
.thumb_set FDCAN_CAL_IRQHandler,Default_Handler
.weak DFSDM1_FLT4_IRQHandler
.thumb_set DFSDM1_FLT4_IRQHandler,Default_Handler
.weak DFSDM1_FLT5_IRQHandler
.thumb_set DFSDM1_FLT5_IRQHandler,Default_Handler
.weak DFSDM1_FLT6_IRQHandler
.thumb_set DFSDM1_FLT6_IRQHandler,Default_Handler
.weak DFSDM1_FLT7_IRQHandler
.thumb_set DFSDM1_FLT7_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 RNG_IRQHandler
.thumb_set 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 SAI2_IRQHandler
.thumb_set SAI2_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 JPEG_IRQHandler
.thumb_set JPEG_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 DAC2_IRQHandler
.thumb_set DAC2_IRQHandler,Default_Handler
.weak DMAMUX2_OVR_IRQHandler
.thumb_set DMAMUX2_OVR_IRQHandler,Default_Handler
.weak BDMA2_Channel0_IRQHandler
.thumb_set BDMA2_Channel0_IRQHandler,Default_Handler
.weak BDMA2_Channel1_IRQHandler
.thumb_set BDMA2_Channel1_IRQHandler,Default_Handler
.weak BDMA2_Channel2_IRQHandler
.thumb_set BDMA2_Channel2_IRQHandler,Default_Handler
.weak BDMA2_Channel3_IRQHandler
.thumb_set BDMA2_Channel3_IRQHandler,Default_Handler
.weak BDMA2_Channel4_IRQHandler
.thumb_set BDMA2_Channel4_IRQHandler,Default_Handler
.weak BDMA2_Channel5_IRQHandler
.thumb_set BDMA2_Channel5_IRQHandler,Default_Handler
.weak BDMA2_Channel6_IRQHandler
.thumb_set BDMA2_Channel6_IRQHandler,Default_Handler
.weak BDMA2_Channel7_IRQHandler
.thumb_set BDMA2_Channel7_IRQHandler,Default_Handler
.weak COMP_IRQHandler
.thumb_set COMP_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 UART9_IRQHandler
.thumb_set UART9_IRQHandler,Default_Handler
.weak USART10_IRQHandler
.thumb_set USART10_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 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 GFXMMU_IRQHandler
.thumb_set GFXMMU_IRQHandler,Default_Handler
.weak BDMA1_IRQHandler
.thumb_set BDMA1_IRQHandler,Default_Handler
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View File

@ -163,7 +163,7 @@ static void SystemInit_ExtMemCtl(void);
* @{
*/
static void Error_Handler(void)
static void ErrorHandler(void)
{
while (1);
}
@ -191,10 +191,12 @@ typedef struct pllConfig_s {
uint8_t q;
uint8_t r;
uint32_t vos;
uint32_t vciRange;
} pllConfig_t;
#if defined(STM32H743xx) || defined(STM32H750xx)
/*
PLL1 configuration for different silicon revisions.
PLL1 configuration for different silicon revisions of H743 and H750.
Note for future overclocking support.
@ -215,7 +217,8 @@ pllConfig_t pll1ConfigRevY = {
.p = 2,
.q = 8,
.r = 5,
.vos = PWR_REGULATOR_VOLTAGE_SCALE1
.vos = PWR_REGULATOR_VOLTAGE_SCALE1,
.vciRange = RCC_PLL1VCIRANGE_2,
};
// 480MHz for Rev.V
@ -226,12 +229,65 @@ pllConfig_t pll1ConfigRevV = {
.p = 2,
.q = 8,
.r = 5,
.vos = PWR_REGULATOR_VOLTAGE_SCALE0
.vos = PWR_REGULATOR_VOLTAGE_SCALE0,
.vciRange = RCC_PLL1VCIRANGE_2,
};
#define MCU_HCLK_DIVIDER RCC_HCLK_DIV2
// H743 and H750
// For HCLK=200MHz with VOS1 range, ST recommended flash latency is 2WS.
// RM0433 (Rev.5) Table 12. FLASH recommended number of wait states and programming delay
//
// For higher HCLK frequency, VOS0 is available on RevV silicons, with FLASH wait states 4WS
// AN5312 (Rev.1) Section 1.2.1 Voltage scaling Table.1
//
// XXX Check if Rev.V requires a different value
#define MCU_FLASH_LATENCY FLASH_LATENCY_2
// Source for CRS input
#define MCU_RCC_CRS_SYNC_SOURCE RCC_CRS_SYNC_SOURCE_USB2
// Workaround for weird HSE behaviors
// (Observed only on Rev.V H750, but may also apply to H743 and Rev.V.)
#define USE_H7_HSERDY_SLOW_WORKAROUND
#define USE_H7_HSE_TIMEOUT_WORKAROUND
#elif defined(STM32H7A3xx) || defined(STM32H7A3xxQ)
// Nominal max 280MHz with 8MHz HSE
// (340 is okay, 360 doesn't work.)
//
pllConfig_t pll1Config7A3 = {
.clockMhz = 280,
.m = 4,
.n = 280,
.p = 2,
.q = 8,
.r = 5,
.vos = PWR_REGULATOR_VOLTAGE_SCALE0,
.vciRange = RCC_PLL1VCIRANGE_1,
};
// Unlike H743/H750, HCLK can be directly fed with SYSCLK.
#define MCU_HCLK_DIVIDER RCC_HCLK_DIV1
// RM0455 (Rev.6) Table 15. FLASH recommended number of wait states and programming delay
// 280MHz at VOS0 is 6WS
#define MCU_FLASH_LATENCY FLASH_LATENCY_6
// Source for CRS input
#define MCU_RCC_CRS_SYNC_SOURCE RCC_CRS_SYNC_SOURCE_USB1
#else
#error Unknown MCU type
#endif
// HSE clock configuration, originally taken from
// STM32Cube_FW_H7_V1.3.0/Projects/STM32H743ZI-Nucleo/Examples/RCC/RCC_ClockConfig/Src/main.c
static void SystemClockHSE_Config(void)
{
RCC_ClkInitTypeDef RCC_ClkInitStruct = {0};
@ -247,11 +303,19 @@ static void SystemClockHSE_Config(void)
RCC_ClkInitStruct.SYSCLKSource = RCC_SYSCLKSOURCE_CSI;
if (HAL_RCC_ClockConfig(&RCC_ClkInitStruct, FLASH_LATENCY_1) != HAL_OK) {
/* Initialization Error */
Error_Handler();
ErrorHandler();
}
#endif
pllConfig_t *pll1Config = (HAL_GetREVID() == REV_ID_V) ? &pll1ConfigRevV : &pll1ConfigRevY;
pllConfig_t *pll1Config;
#if defined(STM32H743xx) || defined(STM32H750xx)
pll1Config = (HAL_GetREVID() == REV_ID_V) ? &pll1ConfigRevV : &pll1ConfigRevY;
#elif defined(STM32H7A3xx) || defined(STM32H7A3xxQ)
pll1Config = &pll1Config7A3;
#else
#error Unknown MCU type
#endif
// Configure voltage scale.
// It has been pre-configured at PWR_REGULATOR_VOLTAGE_SCALE1,
@ -265,9 +329,7 @@ static void SystemClockHSE_Config(void)
/* -2- Enable HSE Oscillator, select it as PLL source and finally activate the PLL */
#define USE_H7_HSERDY_SLOW_WORKAROUND
#ifdef USE_H7_HSERDY_SLOW_WORKAROUND
// With reference to 2.3.22 in the ES0250 Errata for the L476.
// Applying the same workaround here in the vain hopes that it improves startup times.
// Randomly the HSERDY bit takes AGES, over 10 seconds, to be set.
@ -286,7 +348,7 @@ static void SystemClockHSE_Config(void)
#endif
RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_HSE;
RCC_OscInitStruct.HSEState = RCC_HSE_ON; // Even Nucleo-H473 work without RCC_HSE_BYPASS
RCC_OscInitStruct.HSEState = RCC_HSE_ON; // Even Nucleo-H473ZI and Nucleo-H7A3ZI work without RCC_HSE_BYPASS
RCC_OscInitStruct.PLL.PLLState = RCC_PLL_ON;
RCC_OscInitStruct.PLL.PLLSource = RCC_PLLSOURCE_HSE;
@ -297,11 +359,9 @@ static void SystemClockHSE_Config(void)
RCC_OscInitStruct.PLL.PLLR = pll1Config->r;
RCC_OscInitStruct.PLL.PLLVCOSEL = RCC_PLL1VCOWIDE;
RCC_OscInitStruct.PLL.PLLRGE = RCC_PLL1VCIRANGE_2;
RCC_OscInitStruct.PLL.PLLRGE = pll1Config->vciRange;
HAL_StatusTypeDef status = HAL_RCC_OscConfig(&RCC_OscInitStruct);
#define USE_H7_HSE_TIMEOUT_WORKAROUND
#ifdef USE_H7_HSE_TIMEOUT_WORKAROUND
if (status == HAL_TIMEOUT) {
forcedSystemResetWithoutDisablingCaches(); // DC - sometimes HSERDY gets stuck, waiting longer doesn't help.
@ -310,7 +370,7 @@ static void SystemClockHSE_Config(void)
if (status != HAL_OK) {
/* Initialization Error */
Error_Handler();
ErrorHandler();
}
// Configure PLL2 and PLL3
@ -337,23 +397,18 @@ static void SystemClockHSE_Config(void)
RCC_CLOCKTYPE_PCLK1 | \
RCC_CLOCKTYPE_PCLK2 | \
RCC_CLOCKTYPE_D3PCLK1);
RCC_ClkInitStruct.SYSCLKSource = RCC_SYSCLKSOURCE_PLLCLK; // = PLL1P = 400
RCC_ClkInitStruct.SYSCLKDivider = RCC_SYSCLK_DIV1; // = PLL1P(400) / 1 = 400
RCC_ClkInitStruct.AHBCLKDivider = RCC_HCLK_DIV2; // = SYSCLK(400) / 2 = 200
RCC_ClkInitStruct.APB3CLKDivider = RCC_APB3_DIV2; // = HCLK(200) / 2 = 100
RCC_ClkInitStruct.APB1CLKDivider = RCC_APB1_DIV2; // = HCLK(200) / 2 = 100
RCC_ClkInitStruct.APB2CLKDivider = RCC_APB2_DIV2; // = HCLK(200) / 2 = 100
RCC_ClkInitStruct.APB4CLKDivider = RCC_APB4_DIV2; // = HCLK(200) / 2 = 100
RCC_ClkInitStruct.SYSCLKSource = RCC_SYSCLKSOURCE_PLLCLK;
RCC_ClkInitStruct.SYSCLKDivider = RCC_SYSCLK_DIV1;
// For HCLK=200MHz with VOS1 range, ST recommended flash latency is 2WS.
// RM0433 (Rev.5) Table 12. FLASH recommended number of wait states and programming delay
//
// For higher HCLK frequency, VOS0 is available on RevV silicons, with FLASH wait states 4WS
// AN5312 (Rev.1) Section 1.2.1 Voltage scaling Table.1
RCC_ClkInitStruct.AHBCLKDivider = MCU_HCLK_DIVIDER;
RCC_ClkInitStruct.APB3CLKDivider = RCC_APB3_DIV2;
RCC_ClkInitStruct.APB1CLKDivider = RCC_APB1_DIV2;
RCC_ClkInitStruct.APB2CLKDivider = RCC_APB2_DIV2;
RCC_ClkInitStruct.APB4CLKDivider = RCC_APB4_DIV2;
if (HAL_RCC_ClockConfig(&RCC_ClkInitStruct, FLASH_LATENCY_2) != HAL_OK) {
if (HAL_RCC_ClockConfig(&RCC_ClkInitStruct, MCU_FLASH_LATENCY) != HAL_OK) {
/* Initialization Error */
Error_Handler();
ErrorHandler();
}
/* -4- Optional: Disable CSI Oscillator (if the HSI is no more needed by the application)*/
@ -362,7 +417,7 @@ static void SystemClockHSE_Config(void)
RCC_OscInitStruct.PLL.PLLState = RCC_PLL_NONE;
if (HAL_RCC_OscConfig(&RCC_OscInitStruct) != HAL_OK) {
/* Initialization Error */
Error_Handler();
ErrorHandler();
}
}
@ -370,6 +425,8 @@ void SystemClock_Config(void)
{
// Configure power supply
#if defined(STM32H743xx) || defined(STM32H750xx)
HAL_PWREx_ConfigSupply(PWR_LDO_SUPPLY);
// Pre-configure voltage scale to PWR_REGULATOR_VOLTAGE_SCALE1.
@ -377,6 +434,26 @@ void SystemClock_Config(void)
__HAL_PWR_VOLTAGESCALING_CONFIG(PWR_REGULATOR_VOLTAGE_SCALE1);
#elif defined(STM32H7A3xxQ)
// Nucleo-H7A3ZI-Q is preconfigured for power supply configuration 2 (Direct SMPS)
// Here we assume that all boards with SMPS equipped devices use this mode.
HAL_PWREx_ConfigSupply(PWR_DIRECT_SMPS_SUPPLY);
__HAL_PWR_VOLTAGESCALING_CONFIG(PWR_REGULATOR_VOLTAGE_SCALE0);
#elif defined(STM32H7A3xx)
// H7A3 line LDO only devices
// Can probably be treated like STM32H743xx or STM32H750xx (can even be a part of the first conditional)
#error LDO only chip is not supported yet
#else
#error Unknown MCU
#endif
while (!__HAL_PWR_GET_FLAG(PWR_FLAG_VOSRDY)) {
// Empty
}
@ -415,7 +492,7 @@ void SystemClock_Config(void)
RCC_CRSInitTypeDef crsInit = {
.Prescaler = RCC_CRS_SYNC_DIV1,
.Source = RCC_CRS_SYNC_SOURCE_USB2,
.Source = MCU_RCC_CRS_SYNC_SOURCE,
.Polarity = RCC_CRS_SYNC_POLARITY_RISING,
.ReloadValue = RCC_CRS_RELOADVALUE_DEFAULT,
.ErrorLimitValue = RCC_CRS_ERRORLIMIT_DEFAULT,
@ -470,7 +547,7 @@ void SystemClock_Config(void)
// CSI (csi_ker_ck)
// HSE (hse_ck)
// For the first cut, we use 100MHz from various sources
// We use 100MHz for Rev.Y and 120MHz for Rev.V from various sources
RCC_PeriphClkInit.PeriphClockSelection = RCC_PERIPHCLK_SPI123|RCC_PERIPHCLK_SPI45|RCC_PERIPHCLK_SPI6;
RCC_PeriphClkInit.Spi123ClockSelection = RCC_SPI123CLKSOURCE_PLL;
@ -603,6 +680,7 @@ void SystemInit (void)
RCC->CR |= RCC_CR_HSEON;
RCC->CR |= RCC_CR_HSI48ON;
#if defined(STM32H743xx) || defined(STM32H750xx)
/* Reset D1CFGR register */
RCC->D1CFGR = 0x00000000;
@ -611,6 +689,16 @@ void SystemInit (void)
/* Reset D3CFGR register */
RCC->D3CFGR = 0x00000000;
#elif defined(STM32H7A3xx) || defined(STM32H7A3xxQ)
/* Reset CDCFGR1 register */
RCC->CDCFGR1 = 0x00000000;
/* Reset CDCFGR2 register */
RCC->CDCFGR2 = 0x00000000;
/* Reset SRDCFGR register */
RCC->SRDCFGR = 0x00000000;
#endif
/* Reset PLLCKSELR register */
RCC->PLLCKSELR = 0x00000000;
@ -649,7 +737,13 @@ void SystemInit (void)
/* Configure the Vector Table location add offset address ------------------*/
#if defined(VECT_TAB_SRAM)
#if defined(STM32H743xx) || defined(STM32H750xx)
SCB->VTOR = D1_AXISRAM_BASE | VECT_TAB_OFFSET; /* Vector Table Relocation in Internal ITCMSRAM */
#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
#elif defined(USE_EXST)
// Don't touch the vector table, the bootloader will have already set it.
#else

View File

@ -76,7 +76,7 @@ PCD_HandleTypeDef hpcd;
PCD BSP Routines
*******************************************************************************/
#ifdef USE_USB_FS
#if defined(USE_USB_FS) && !defined(STM32H7A3xx)&& !defined(STM32H7A3xxQ)
void OTG_FS_IRQHandler(void)
#else
void OTG_HS_IRQHandler(void)
@ -92,7 +92,37 @@ void OTG_HS_IRQHandler(void)
*/
void HAL_PCD_MspInit(PCD_HandleTypeDef * hpcd)
{
GPIO_InitTypeDef GPIO_InitStruct;
GPIO_InitTypeDef GPIO_InitStruct = {0};
#if defined(STM32H7A3xx) || defined(STM32H7A3xxQ)
// H7A3 uses USB1_OTG_HS in FS mode
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);
/* Peripheral clock enable */
__HAL_RCC_USB1_OTG_HS_CLK_ENABLE();
/* Set USB HS Interrupt priority */
HAL_NVIC_SetPriority(OTG_HS_IRQn, 6, 0);
/* Enable USB HS Interrupt */
HAL_NVIC_EnableIRQ(OTG_HS_IRQn);
#elif defined(STM32H743xx) || defined(STM32H750xx)
if (hpcd->Instance == USB_OTG_FS)
{
@ -199,6 +229,9 @@ void HAL_PCD_MspInit(PCD_HandleTypeDef * hpcd)
/* Enable USBHS Interrupt */
HAL_NVIC_EnableIRQ(OTG_HS_IRQn);
}
#else
#error Unknown MCU type
#endif
}
/**
@ -208,6 +241,18 @@ void HAL_PCD_MspInit(PCD_HandleTypeDef * hpcd)
*/
void HAL_PCD_MspDeInit(PCD_HandleTypeDef * hpcd)
{
#if defined(STM32H7A3xx) || defined(STM32H7A3xxQ)
if(hpcd->Instance==USB1_OTG_HS) {
__HAL_RCC_USB1_OTG_HS_CLK_DISABLE();
HAL_GPIO_DeInit(GPIOA, GPIO_PIN_11|GPIO_PIN_12);
HAL_NVIC_DisableIRQ(OTG_HS_IRQn);
__HAL_RCC_GPIOA_CLK_DISABLE();
}
#elif defined(STM32H743xx) || defined(STM32H750xx)
if (hpcd->Instance == USB2_OTG_FS)
{
/* Disable USB FS Clocks */
@ -219,6 +264,9 @@ void HAL_PCD_MspDeInit(PCD_HandleTypeDef * hpcd)
__HAL_RCC_USB1_OTG_HS_CLK_DISABLE();
__HAL_RCC_USB1_OTG_HS_ULPI_CLK_DISABLE();
}
#else
#error Unknown MCU
#endif
}
/*******************************************************************************
@ -374,7 +422,13 @@ USBD_StatusTypeDef USBD_LL_Init(USBD_HandleTypeDef * pdev)
{
#ifdef USE_USB_FS
/* Set LL Driver parameters */
#if defined(STM32H7A3xx) || defined(STM32H7A3xxQ)
hpcd.Instance = USB1_OTG_HS;
#elif defined(STM32H743xx) || defined(STM32H750xx)
hpcd.Instance = USB2_OTG_FS;
#else
#error Unknown MCU type
#endif
hpcd.Init.dev_endpoints = 9;
hpcd.Init.use_dedicated_ep1 = DISABLE;
hpcd.Init.ep0_mps = DEP0CTL_MPS_64;