diff --git a/hw/bsp/stm32h743nucleo/STM32H743ZITx_FLASH.ld b/hw/bsp/stm32h743nucleo/STM32H743ZITx_FLASH.ld
new file mode 100644
index 000000000..65274992e
--- /dev/null
+++ b/hw/bsp/stm32h743nucleo/STM32H743ZITx_FLASH.ld
@@ -0,0 +1,173 @@
+/*
+*****************************************************************************
+**
+
+** File : LinkerScript.ld
+**
+** Abstract : Linker script for STM32H743ZITx Device with
+** 2048KByte FLASH, 1056KByte RAM
+**
+** Set heap size, stack size and stack location according
+** to application requirements.
+**
+** Set memory bank area and size if external memory is used.
+**
+** Target : STMicroelectronics STM32
+**
+**
+** Distribution: The file is distributed as is, without any warranty
+** of any kind.
+**
+** (c)Copyright Ac6.
+** You may use this file as-is or modify it according to the needs of your
+** project. Distribution of this file (unmodified or modified) is not
+** permitted. Ac6 permit registered System Workbench for MCU users the
+** rights to distribute the assembled, compiled & linked contents of this
+** file as part of an application binary file, provided that it is built
+** using the System Workbench for MCU toolchain.
+**
+*****************************************************************************
+*/
+
+/* Entry Point */
+ENTRY(Reset_Handler)
+
+/* Highest address of the user mode stack */
+_estack = 0x20020000; /* end of RAM */
+/* Generate a link error if heap and stack don't fit into RAM */
+_Min_Heap_Size = 0x200; /* required amount of heap */
+_Min_Stack_Size = 0x400; /* required amount of stack */
+
+/* Specify the memory areas */
+MEMORY
+{
+DTCMRAM (xrw) : ORIGIN = 0x20000000, LENGTH = 128K
+RAM_D1 (xrw) : ORIGIN = 0x24000000, LENGTH = 512K
+RAM_D2 (xrw) : ORIGIN = 0x30000000, LENGTH = 288K
+RAM_D3 (xrw) : ORIGIN = 0x38000000, LENGTH = 64K
+ITCMRAM (xrw) : ORIGIN = 0x00000000, LENGTH = 64K
+FLASH (rx) : ORIGIN = 0x8000000, LENGTH = 2048K
+}
+
+/* Define output sections */
+SECTIONS
+{
+ /* The startup code goes first into FLASH */
+ .isr_vector :
+ {
+ . = ALIGN(4);
+ 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) */
+ *(.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 */
+ } >FLASH
+
+ /* Constant data goes into FLASH */
+ .rodata :
+ {
+ . = ALIGN(4);
+ *(.rodata) /* .rodata sections (constants, strings, etc.) */
+ *(.rodata*) /* .rodata* sections (constants, strings, etc.) */
+ . = ALIGN(4);
+ } >FLASH
+
+ .ARM.extab : { *(.ARM.extab* .gnu.linkonce.armextab.*) } >FLASH
+ .ARM : {
+ __exidx_start = .;
+ *(.ARM.exidx*)
+ __exidx_end = .;
+ } >FLASH
+
+ .preinit_array :
+ {
+ PROVIDE_HIDDEN (__preinit_array_start = .);
+ KEEP (*(.preinit_array*))
+ PROVIDE_HIDDEN (__preinit_array_end = .);
+ } >FLASH
+ .init_array :
+ {
+ PROVIDE_HIDDEN (__init_array_start = .);
+ KEEP (*(SORT(.init_array.*)))
+ KEEP (*(.init_array*))
+ PROVIDE_HIDDEN (__init_array_end = .);
+ } >FLASH
+ .fini_array :
+ {
+ PROVIDE_HIDDEN (__fini_array_start = .);
+ KEEP (*(SORT(.fini_array.*)))
+ KEEP (*(.fini_array*))
+ PROVIDE_HIDDEN (__fini_array_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 */
+ } >DTCMRAM AT> FLASH
+
+
+ /* Uninitialized data section */
+ . = ALIGN(4);
+ .bss :
+ {
+ /* 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)
+ *(.bss*)
+ *(COMMON)
+
+ . = ALIGN(4);
+ _ebss = .; /* define a global symbol at bss end */
+ __bss_end__ = _ebss;
+ } >DTCMRAM
+
+ /* User_heap_stack section, used to check that there is enough RAM left */
+ ._user_heap_stack :
+ {
+ . = ALIGN(8);
+ PROVIDE ( end = . );
+ PROVIDE ( _end = . );
+ . = . + _Min_Heap_Size;
+ . = . + _Min_Stack_Size;
+ . = ALIGN(8);
+ } >DTCMRAM
+
+
+
+ /* Remove information from the standard libraries */
+ /DISCARD/ :
+ {
+ libc.a ( * )
+ libm.a ( * )
+ libgcc.a ( * )
+ }
+
+ .ARM.attributes 0 : { *(.ARM.attributes) }
+}
+
+
diff --git a/hw/bsp/stm32h743nucleo/board.mk b/hw/bsp/stm32h743nucleo/board.mk
new file mode 100644
index 000000000..d1ad97bbf
--- /dev/null
+++ b/hw/bsp/stm32h743nucleo/board.mk
@@ -0,0 +1,36 @@
+CFLAGS += \
+ -DHSE_VALUE=8000000 \
+ -DSTM32H743xx \
+ -mthumb \
+ -mabi=aapcs-linux \
+ -mcpu=cortex-m7 \
+ -mfloat-abi=hard \
+ -mfpu=fpv5-d16 \
+ -nostdlib -nostartfiles \
+ -DCFG_TUSB_MCU=OPT_MCU_STM32H7 \
+ -Wno-error=sign-compare
+
+# The -Wno-error=sign-compare line is required due to STM32H7xx_HAL_Driver.
+
+# All source paths should be relative to the top level.
+LD_FILE = hw/bsp/stm32h743nucleo/STM32H743ZITx_FLASH.ld
+
+SRC_C += \
+ hw/mcu/st/system-init/system_stm32h7xx.c \
+ hw/mcu/st/stm32lib/STM32H7xx_HAL_Driver/Src/stm32h7xx_hal.c \
+ hw/mcu/st/stm32lib/STM32H7xx_HAL_Driver/Src/stm32h7xx_hal_cortex.c \
+ hw/mcu/st/stm32lib/STM32H7xx_HAL_Driver/Src/stm32h7xx_hal_rcc.c \
+ hw/mcu/st/stm32lib/STM32H7xx_HAL_Driver/Src/stm32h7xx_hal_gpio.c
+
+SRC_S += \
+ hw/mcu/st/startup/stm32h7/startup_stm32h743xx.s
+
+INC += \
+ $(TOP)/hw/mcu/st/cmsis \
+ $(TOP)/hw/mcu/st/stm32lib/CMSIS/STM32H7xx/Include \
+ $(TOP)/hw/mcu/st/stm32lib/STM32H7xx_HAL_Driver/Inc \
+ $(TOP)/hw/bsp/stm32h743nucleo
+
+# For TinyUSB port source
+VENDOR = st
+CHIP_FAMILY = stm32h7
diff --git a/hw/bsp/stm32h743nucleo/board_stm32h743nucleo.c b/hw/bsp/stm32h743nucleo/board_stm32h743nucleo.c
new file mode 100644
index 000000000..ab64cab8b
--- /dev/null
+++ b/hw/bsp/stm32h743nucleo/board_stm32h743nucleo.c
@@ -0,0 +1,93 @@
+/*
+ * The MIT License (MIT)
+ *
+ * Copyright (c) 2019 William D. Jones (thor0505@comcast.net),
+ * Ha Thach (tinyusb.org)
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to deal
+ * in the Software without restriction, including without limitation the rights
+ * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
+ * copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
+ * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
+ * THE SOFTWARE.
+ *
+ * This file is part of the TinyUSB stack.
+ */
+
+#include "../board.h"
+
+#include "stm32h7xx.h"
+#include "stm32h7xx_hal_conf.h"
+
+
+static void SystemClock_Config(void)
+{
+
+}
+
+void board_init(void)
+{
+
+}
+
+//--------------------------------------------------------------------+
+// Board porting API
+//--------------------------------------------------------------------+
+
+void board_led_write(bool state)
+{
+ SystemClock_Config();
+}
+
+uint32_t board_button_read(void)
+{
+ // TODO implement
+ return 0;
+}
+
+int board_uart_read(uint8_t* buf, int len)
+{
+ return 0;
+}
+
+int board_uart_write(void const * buf, int len)
+{
+ return 0;
+}
+
+
+#if CFG_TUSB_OS == OPT_OS_NONE
+volatile uint32_t system_ticks = 0;
+void SysTick_Handler (void)
+{
+ system_ticks++;
+}
+
+uint32_t board_millis(void)
+{
+ return system_ticks;
+}
+#endif
+
+void HardFault_Handler (void)
+{
+ asm("bkpt");
+}
+
+// Required by __libc_init_array in startup code if we are compiling using
+// -nostdlib/-nostartfiles.
+void _init(void)
+{
+
+}
diff --git a/hw/bsp/stm32h743nucleo/stm32h7xx_hal_conf.h b/hw/bsp/stm32h743nucleo/stm32h7xx_hal_conf.h
new file mode 100644
index 000000000..1e51f6772
--- /dev/null
+++ b/hw/bsp/stm32h743nucleo/stm32h7xx_hal_conf.h
@@ -0,0 +1,431 @@
+/**
+ ******************************************************************************
+ * @file stm32h7xx_hal_conf_template.h
+ * @brief HAL configuration template file.
+ * This file should be copied to the application folder and renamed
+ * to stm32h7xx_hal_conf.h.
+ ******************************************************************************
+ * @attention
+ *
+ *
© COPYRIGHT(c) 2019 STMicroelectronics
+ *
+ * Redistribution and use in source and binary forms, with or without modification,
+ * are permitted provided that the following conditions are met:
+ * 1. Redistributions of source code must retain the above copyright notice,
+ * this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright notice,
+ * this list of conditions and the following disclaimer in the documentation
+ * and/or other materials provided with the distribution.
+ * 3. Neither the name of STMicroelectronics nor the names of its contributors
+ * may be used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
+ * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
+ * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
+ * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
+ * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
+ * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
+ * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
+ * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
+ * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
+ * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+ *
+ ******************************************************************************
+ */
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __STM32H7xx_HAL_CONF_H
+#define __STM32H7xx_HAL_CONF_H
+
+#ifdef __cplusplus
+ extern "C" {
+#endif
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+
+/* ########################## Module Selection ############################## */
+/**
+ * @brief This is the list of modules to be used in the HAL driver
+ */
+#define HAL_MODULE_ENABLED
+
+/* #define HAL_ADC_MODULE_ENABLED */
+/* #define HAL_FDCAN_MODULE_ENABLED */
+/* #define HAL_CEC_MODULE_ENABLED */
+/* #define HAL_COMP_MODULE_ENABLED */
+/* #define HAL_CRC_MODULE_ENABLED */
+/* #define HAL_CRYP_MODULE_ENABLED */
+/* #define HAL_DAC_MODULE_ENABLED */
+/* #define HAL_DCMI_MODULE_ENABLED */
+/* #define HAL_DMA2D_MODULE_ENABLED */
+#define HAL_ETH_MODULE_ENABLED
+/* #define HAL_NAND_MODULE_ENABLED */
+/* #define HAL_NOR_MODULE_ENABLED */
+/* #define HAL_SRAM_MODULE_ENABLED */
+/* #define HAL_SDRAM_MODULE_ENABLED */
+/* #define HAL_HASH_MODULE_ENABLED */
+/* #define HAL_HRTIM_MODULE_ENABLED */
+/* #define HAL_HSEM_MODULE_ENABLED */
+/* #define HAL_JPEG_MODULE_ENABLED */
+/* #define HAL_OPAMP_MODULE_ENABLED */
+/* #define HAL_I2S_MODULE_ENABLED */
+/* #define HAL_SMBUS_MODULE_ENABLED */
+/* #define HAL_IWDG_MODULE_ENABLED */
+/* #define HAL_LPTIM_MODULE_ENABLED */
+/* #define HAL_LTDC_MODULE_ENABLED */
+/* #define HAL_QSPI_MODULE_ENABLED */
+/* #define HAL_RNG_MODULE_ENABLED */
+/* #define HAL_RTC_MODULE_ENABLED */
+/* #define HAL_SAI_MODULE_ENABLED */
+/* #define HAL_SD_MODULE_ENABLED */
+/* #define HAL_MMC_MODULE_ENABLED */
+/* #define HAL_SPDIFRX_MODULE_ENABLED */
+/* #define HAL_SPI_MODULE_ENABLED */
+/* #define HAL_SWPMI_MODULE_ENABLED */
+/* #define HAL_TIM_MODULE_ENABLED */
+#define HAL_UART_MODULE_ENABLED
+/* #define HAL_USART_MODULE_ENABLED */
+/* #define HAL_IRDA_MODULE_ENABLED */
+/* #define HAL_SMARTCARD_MODULE_ENABLED */
+/* #define HAL_WWDG_MODULE_ENABLED */
+#define HAL_PCD_MODULE_ENABLED
+/* #define HAL_HCD_MODULE_ENABLED */
+/* #define HAL_DFSDM_MODULE_ENABLED */
+/* #define HAL_DSI_MODULE_ENABLED */
+/* #define HAL_JPEG_MODULE_ENABLED */
+/* #define HAL_MDIOS_MODULE_ENABLED */
+/* #define HAL_EXTI_MODULE_ENABLED */
+#define HAL_GPIO_MODULE_ENABLED
+#define HAL_DMA_MODULE_ENABLED
+#define HAL_MDMA_MODULE_ENABLED
+#define HAL_RCC_MODULE_ENABLED
+#define HAL_FLASH_MODULE_ENABLED
+#define HAL_PWR_MODULE_ENABLED
+#define HAL_I2C_MODULE_ENABLED
+#define HAL_CORTEX_MODULE_ENABLED
+#define HAL_HSEM_MODULE_ENABLED
+
+/* ########################## Oscillator Values adaptation ####################*/
+/**
+ * @brief Adjust the value of External High Speed oscillator (HSE) used in your application.
+ * This value is used by the RCC HAL module to compute the system frequency
+ * (when HSE is used as system clock source, directly or through the PLL).
+ */
+#if !defined (HSE_VALUE)
+#define HSE_VALUE ((uint32_t)8000000) /*!< Value of the External oscillator in Hz : FPGA case fixed to 60MHZ */
+#endif /* HSE_VALUE */
+
+#if !defined (HSE_STARTUP_TIMEOUT)
+ #define HSE_STARTUP_TIMEOUT ((uint32_t)100U) /*!< Time out for HSE start up, in ms */
+#endif /* HSE_STARTUP_TIMEOUT */
+
+/**
+ * @brief Internal oscillator (CSI) default value.
+ * This value is the default CSI value after Reset.
+ */
+#if !defined (CSI_VALUE)
+ #define CSI_VALUE ((uint32_t)4000000) /*!< Value of the Internal oscillator in Hz*/
+#endif /* CSI_VALUE */
+
+/**
+ * @brief Internal High Speed oscillator (HSI) value.
+ * This value is used by the RCC HAL module to compute the system frequency
+ * (when HSI is used as system clock source, directly or through the PLL).
+ */
+#if !defined (HSI_VALUE)
+ #define HSI_VALUE ((uint32_t)64000000) /*!< Value of the Internal oscillator in Hz*/
+#endif /* HSI_VALUE */
+
+/**
+ * @brief External Low Speed oscillator (LSE) value.
+ * This value is used by the UART, RTC HAL module to compute the system frequency
+ */
+#if !defined (LSE_VALUE)
+ #define LSE_VALUE ((uint32_t)32768U) /*!< Value of the External oscillator in Hz*/
+#endif /* LSE_VALUE */
+
+#if !defined (LSE_STARTUP_TIMEOUT)
+ #define LSE_STARTUP_TIMEOUT ((uint32_t)5000U) /*!< Time out for LSE start up, in ms */
+#endif /* LSE_STARTUP_TIMEOUT */
+
+/**
+ * @brief External clock source for I2S peripheral
+ * This value is used by the I2S HAL module to compute the I2S clock source
+ * frequency, this source is inserted directly through I2S_CKIN pad.
+ */
+#if !defined (EXTERNAL_CLOCK_VALUE)
+ #define EXTERNAL_CLOCK_VALUE 12288000U /*!< Value of the External clock in Hz*/
+#endif /* EXTERNAL_CLOCK_VALUE */
+
+/* Tip: To avoid modifying this file each time you need to use different HSE,
+ === you can define the HSE value in your toolchain compiler preprocessor. */
+
+/* ########################### System Configuration ######################### */
+/**
+ * @brief This is the HAL system configuration section
+ */
+#define VDD_VALUE ((uint32_t)3300U) /*!< Value of VDD in mv */
+#define TICK_INT_PRIORITY ((uint32_t)0U) /*!< tick interrupt priority */
+#define USE_RTOS 0U
+#define USE_SD_TRANSCEIVER 1U /*!< use uSD Transceiver */
+/* ########################## Assert Selection ############################## */
+/**
+ * @brief Uncomment the line below to expanse the "assert_param" macro in the
+ * HAL drivers code
+ */
+/* #define USE_FULL_ASSERT 1U */
+
+/* ################## SPI peripheral configuration ########################## */
+
+/* CRC FEATURE: Use to activate CRC feature inside HAL SPI Driver
+* Activated: CRC code is present inside driver
+* Deactivated: CRC code cleaned from driver
+*/
+
+#define USE_SPI_CRC 0U
+
+/* ################## ETH peripheral configuration ########################## */
+
+#define ETH_TX_DESC_CNT ((uint32_t)4) /* Tx Descriptor Length */
+#define ETH_RX_DESC_CNT ((uint32_t)4) /* Rx Descriptor Length */
+
+/* Includes ------------------------------------------------------------------*/
+/**
+ * @brief Include module's header file
+ */
+
+#ifdef HAL_RCC_MODULE_ENABLED
+ #include "stm32h7xx_hal_rcc.h"
+#endif /* HAL_RCC_MODULE_ENABLED */
+
+#ifdef HAL_EXTI_MODULE_ENABLED
+ #include "stm32h7xx_hal_exti.h"
+#endif /* HAL_EXTI_MODULE_ENABLED */
+
+#ifdef HAL_GPIO_MODULE_ENABLED
+ #include "stm32h7xx_hal_gpio.h"
+#endif /* HAL_GPIO_MODULE_ENABLED */
+
+#ifdef HAL_DMA_MODULE_ENABLED
+ #include "stm32h7xx_hal_dma.h"
+#endif /* HAL_DMA_MODULE_ENABLED */
+
+#ifdef HAL_HASH_MODULE_ENABLED
+ #include "stm32h7xx_hal_hash.h"
+#endif /* HAL_HASH_MODULE_ENABLED */
+
+#ifdef HAL_DCMI_MODULE_ENABLED
+ #include "stm32h7xx_hal_dcmi.h"
+#endif /* HAL_DCMI_MODULE_ENABLED */
+
+#ifdef HAL_DMA2D_MODULE_ENABLED
+ #include "stm32h7xx_hal_dma2d.h"
+#endif /* HAL_DMA2D_MODULE_ENABLED */
+
+#ifdef HAL_DFSDM_MODULE_ENABLED
+ #include "stm32h7xx_hal_dfsdm.h"
+#endif /* HAL_DFSDM_MODULE_ENABLED */
+
+#ifdef HAL_ETH_MODULE_ENABLED
+ #include "stm32h7xx_hal_eth.h"
+#endif /* HAL_ETH_MODULE_ENABLED */
+
+#ifdef HAL_CORTEX_MODULE_ENABLED
+ #include "stm32h7xx_hal_cortex.h"
+#endif /* HAL_CORTEX_MODULE_ENABLED */
+
+#ifdef HAL_ADC_MODULE_ENABLED
+ #include "stm32h7xx_hal_adc.h"
+#endif /* HAL_ADC_MODULE_ENABLED */
+
+#ifdef HAL_FDCAN_MODULE_ENABLED
+ #include "stm32h7xx_hal_fdcan.h"
+#endif /* HAL_FDCAN_MODULE_ENABLED */
+
+#ifdef HAL_CEC_MODULE_ENABLED
+ #include "stm32h7xx_hal_cec.h"
+#endif /* HAL_CEC_MODULE_ENABLED */
+
+#ifdef HAL_COMP_MODULE_ENABLED
+ #include "stm32h7xx_hal_comp.h"
+#endif /* HAL_COMP_MODULE_ENABLED */
+
+#ifdef HAL_CRC_MODULE_ENABLED
+ #include "stm32h7xx_hal_crc.h"
+#endif /* HAL_CRC_MODULE_ENABLED */
+
+#ifdef HAL_CRYP_MODULE_ENABLED
+ #include "stm32h7xx_hal_cryp.h"
+#endif /* HAL_CRYP_MODULE_ENABLED */
+
+#ifdef HAL_DAC_MODULE_ENABLED
+ #include "stm32h7xx_hal_dac.h"
+#endif /* HAL_DAC_MODULE_ENABLED */
+
+#ifdef HAL_FLASH_MODULE_ENABLED
+ #include "stm32h7xx_hal_flash.h"
+#endif /* HAL_FLASH_MODULE_ENABLED */
+
+#ifdef HAL_HRTIM_MODULE_ENABLED
+ #include "stm32h7xx_hal_hrtim.h"
+#endif /* HAL_HRTIM_MODULE_ENABLED */
+
+#ifdef HAL_HSEM_MODULE_ENABLED
+ #include "stm32h7xx_hal_hsem.h"
+#endif /* HAL_HSEM_MODULE_ENABLED */
+
+#ifdef HAL_SRAM_MODULE_ENABLED
+ #include "stm32h7xx_hal_sram.h"
+#endif /* HAL_SRAM_MODULE_ENABLED */
+
+#ifdef HAL_NOR_MODULE_ENABLED
+ #include "stm32h7xx_hal_nor.h"
+#endif /* HAL_NOR_MODULE_ENABLED */
+
+#ifdef HAL_NAND_MODULE_ENABLED
+ #include "stm32h7xx_hal_nand.h"
+#endif /* HAL_NAND_MODULE_ENABLED */
+
+#ifdef HAL_I2C_MODULE_ENABLED
+ #include "stm32h7xx_hal_i2c.h"
+#endif /* HAL_I2C_MODULE_ENABLED */
+
+#ifdef HAL_I2S_MODULE_ENABLED
+ #include "stm32h7xx_hal_i2s.h"
+#endif /* HAL_I2S_MODULE_ENABLED */
+
+#ifdef HAL_IWDG_MODULE_ENABLED
+ #include "stm32h7xx_hal_iwdg.h"
+#endif /* HAL_IWDG_MODULE_ENABLED */
+
+#ifdef HAL_JPEG_MODULE_ENABLED
+ #include "stm32h7xx_hal_jpeg.h"
+#endif /* HAL_JPEG_MODULE_ENABLED */
+
+#ifdef HAL_MDIOS_MODULE_ENABLED
+ #include "stm32h7xx_hal_mdios.h"
+#endif /* HAL_MDIOS_MODULE_ENABLED */
+
+#ifdef HAL_MDMA_MODULE_ENABLED
+ #include "stm32h7xx_hal_mdma.h"
+#endif /* HAL_MDMA_MODULE_ENABLED */
+
+#ifdef HAL_LPTIM_MODULE_ENABLED
+#include "stm32h7xx_hal_lptim.h"
+#endif /* HAL_LPTIM_MODULE_ENABLED */
+
+#ifdef HAL_LTDC_MODULE_ENABLED
+#include "stm32h7xx_hal_ltdc.h"
+#endif /* HAL_LTDC_MODULE_ENABLED */
+
+#ifdef HAL_OPAMP_MODULE_ENABLED
+#include "stm32h7xx_hal_opamp.h"
+#endif /* HAL_OPAMP_MODULE_ENABLED */
+
+#ifdef HAL_PWR_MODULE_ENABLED
+ #include "stm32h7xx_hal_pwr.h"
+#endif /* HAL_PWR_MODULE_ENABLED */
+
+#ifdef HAL_QSPI_MODULE_ENABLED
+ #include "stm32h7xx_hal_qspi.h"
+#endif /* HAL_QSPI_MODULE_ENABLED */
+
+#ifdef HAL_RNG_MODULE_ENABLED
+ #include "stm32h7xx_hal_rng.h"
+#endif /* HAL_RNG_MODULE_ENABLED */
+
+#ifdef HAL_RTC_MODULE_ENABLED
+ #include "stm32h7xx_hal_rtc.h"
+#endif /* HAL_RTC_MODULE_ENABLED */
+
+#ifdef HAL_SAI_MODULE_ENABLED
+ #include "stm32h7xx_hal_sai.h"
+#endif /* HAL_SAI_MODULE_ENABLED */
+
+#ifdef HAL_SD_MODULE_ENABLED
+ #include "stm32h7xx_hal_sd.h"
+#endif /* HAL_SD_MODULE_ENABLED */
+
+#ifdef HAL_MMC_MODULE_ENABLED
+ #include "stm32h7xx_hal_mmc.h"
+#endif /* HAL_MMC_MODULE_ENABLED */
+
+#ifdef HAL_SDRAM_MODULE_ENABLED
+ #include "stm32h7xx_hal_sdram.h"
+#endif /* HAL_SDRAM_MODULE_ENABLED */
+
+#ifdef HAL_SPI_MODULE_ENABLED
+ #include "stm32h7xx_hal_spi.h"
+#endif /* HAL_SPI_MODULE_ENABLED */
+
+#ifdef HAL_SPDIFRX_MODULE_ENABLED
+ #include "stm32h7xx_hal_spdifrx.h"
+#endif /* HAL_SPDIFRX_MODULE_ENABLED */
+
+#ifdef HAL_SWPMI_MODULE_ENABLED
+ #include "stm32h7xx_hal_swpmi.h"
+#endif /* HAL_SWPMI_MODULE_ENABLED */
+
+#ifdef HAL_TIM_MODULE_ENABLED
+ #include "stm32h7xx_hal_tim.h"
+#endif /* HAL_TIM_MODULE_ENABLED */
+
+#ifdef HAL_UART_MODULE_ENABLED
+ #include "stm32h7xx_hal_uart.h"
+#endif /* HAL_UART_MODULE_ENABLED */
+
+#ifdef HAL_USART_MODULE_ENABLED
+ #include "stm32h7xx_hal_usart.h"
+#endif /* HAL_USART_MODULE_ENABLED */
+
+#ifdef HAL_IRDA_MODULE_ENABLED
+ #include "stm32h7xx_hal_irda.h"
+#endif /* HAL_IRDA_MODULE_ENABLED */
+
+#ifdef HAL_SMARTCARD_MODULE_ENABLED
+ #include "stm32h7xx_hal_smartcard.h"
+#endif /* HAL_SMARTCARD_MODULE_ENABLED */
+
+#ifdef HAL_SMBUS_MODULE_ENABLED
+ #include "stm32h7xx_hal_smbus.h"
+#endif /* HAL_SMBUS_MODULE_ENABLED */
+
+#ifdef HAL_WWDG_MODULE_ENABLED
+ #include "stm32h7xx_hal_wwdg.h"
+#endif /* HAL_WWDG_MODULE_ENABLED */
+
+#ifdef HAL_PCD_MODULE_ENABLED
+ #include "stm32h7xx_hal_pcd.h"
+#endif /* HAL_PCD_MODULE_ENABLED */
+
+#ifdef HAL_HCD_MODULE_ENABLED
+ #include "stm32h7xx_hal_hcd.h"
+#endif /* HAL_HCD_MODULE_ENABLED */
+
+/* Exported macro ------------------------------------------------------------*/
+#ifdef USE_FULL_ASSERT
+/**
+ * @brief The assert_param macro is used for function's parameters check.
+ * @param expr: If expr is false, it calls assert_failed function
+ * which reports the name of the source file and the source
+ * line number of the call that failed.
+ * If expr is true, it returns no value.
+ * @retval None
+ */
+ #define assert_param(expr) ((expr) ? (void)0 : assert_failed((uint8_t *)__FILE__, __LINE__))
+/* Exported functions ------------------------------------------------------- */
+ void assert_failed(uint8_t* file, uint32_t line);
+#else
+ #define assert_param(expr) ((void)0)
+#endif /* USE_FULL_ASSERT */
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* __STM32H7xx_HAL_CONF_H */
+
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/hw/mcu/st/startup/stm32h7/startup_stm32h743xx.s b/hw/mcu/st/startup/stm32h7/startup_stm32h743xx.s
new file mode 100644
index 000000000..cfb7ee1d3
--- /dev/null
+++ b/hw/mcu/st/startup/stm32h7/startup_stm32h743xx.s
@@ -0,0 +1,761 @@
+/**
+ ******************************************************************************
+ * @file startup_stm32h743xx.s
+ * @author MCD Application Team
+ * @brief STM32H743xx 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 2017 STMicroelectronics
+ *
+ * Redistribution and use in source and binary forms, with or without modification,
+ * are permitted provided that the following conditions are met:
+ * 1. Redistributions of source code must retain the above copyright notice,
+ * this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright notice,
+ * this list of conditions and the following disclaimer in the documentation
+ * and/or other materials provided with the distribution.
+ * 3. Neither the name of STMicroelectronics nor the names of its contributors
+ * may be used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
+ * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
+ * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
+ * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
+ * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
+ * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
+ * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
+ * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
+ * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
+ * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+ *
+ ******************************************************************************
+ */
+
+ .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 */
+
+/* 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
+
+/* 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_IRQHandler /* DCMI */
+ .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 QUADSPI_IRQHandler /* QUADSPI */
+ .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 OTG_FS_EP1_OUT_IRQHandler /* USB OTG FS End Point 1 Out */
+ .word OTG_FS_EP1_IN_IRQHandler /* USB OTG FS End Point 1 In */
+ .word OTG_FS_WKUP_IRQHandler /* USB OTG FS Wakeup through EXTI */
+ .word OTG_FS_IRQHandler /* USB OTG FS */
+ .word DMAMUX1_OVR_IRQHandler /* DMAMUX1 Overrun interrupt */
+ .word HRTIM1_Master_IRQHandler /* HRTIM Master Timer global Interrupt */
+ .word HRTIM1_TIMA_IRQHandler /* HRTIM Timer A global Interrupt */
+ .word HRTIM1_TIMB_IRQHandler /* HRTIM Timer B global Interrupt */
+ .word HRTIM1_TIMC_IRQHandler /* HRTIM Timer C global Interrupt */
+ .word HRTIM1_TIMD_IRQHandler /* HRTIM Timer D global Interrupt */
+ .word HRTIM1_TIME_IRQHandler /* HRTIM Timer E global Interrupt */
+ .word HRTIM1_FLT_IRQHandler /* HRTIM Fault global Interrupt */
+ .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 SAI3_IRQHandler /* SAI3 global Interrupt */
+ .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 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 0 /* Reserved */
+ .word SAI4_IRQHandler /* SAI4 global interrupt */
+ .word 0 /* Reserved */
+ .word 0 /* Reserved */
+ .word WAKEUP_PIN_IRQHandler /* Interrupt for all 6 wake-up pins */
+
+/*******************************************************************************
+*
+* 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_IRQHandler
+ .thumb_set DCMI_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 QUADSPI_IRQHandler
+ .thumb_set QUADSPI_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 OTG_FS_EP1_OUT_IRQHandler
+ .thumb_set OTG_FS_EP1_OUT_IRQHandler,Default_Handler
+
+ .weak OTG_FS_EP1_IN_IRQHandler
+ .thumb_set OTG_FS_EP1_IN_IRQHandler,Default_Handler
+
+ .weak OTG_FS_WKUP_IRQHandler
+ .thumb_set OTG_FS_WKUP_IRQHandler,Default_Handler
+
+ .weak OTG_FS_IRQHandler
+ .thumb_set OTG_FS_IRQHandler,Default_Handler
+
+ .weak DMAMUX1_OVR_IRQHandler
+ .thumb_set DMAMUX1_OVR_IRQHandler,Default_Handler
+
+ .weak HRTIM1_Master_IRQHandler
+ .thumb_set HRTIM1_Master_IRQHandler,Default_Handler
+
+ .weak HRTIM1_TIMA_IRQHandler
+ .thumb_set HRTIM1_TIMA_IRQHandler,Default_Handler
+
+ .weak HRTIM1_TIMB_IRQHandler
+ .thumb_set HRTIM1_TIMB_IRQHandler,Default_Handler
+
+ .weak HRTIM1_TIMC_IRQHandler
+ .thumb_set HRTIM1_TIMC_IRQHandler,Default_Handler
+
+ .weak HRTIM1_TIMD_IRQHandler
+ .thumb_set HRTIM1_TIMD_IRQHandler,Default_Handler
+
+ .weak HRTIM1_TIME_IRQHandler
+ .thumb_set HRTIM1_TIME_IRQHandler,Default_Handler
+
+ .weak HRTIM1_FLT_IRQHandler
+ .thumb_set HRTIM1_FLT_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 SAI3_IRQHandler
+ .thumb_set SAI3_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 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 SAI4_IRQHandler
+ .thumb_set SAI4_IRQHandler,Default_Handler
+
+ .weak WAKEUP_PIN_IRQHandler
+ .thumb_set WAKEUP_PIN_IRQHandler,Default_Handler
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
+
diff --git a/hw/mcu/st/startup/stm32h7/startup_stm32h750xx.s b/hw/mcu/st/startup/stm32h7/startup_stm32h750xx.s
new file mode 100644
index 000000000..9ce116082
--- /dev/null
+++ b/hw/mcu/st/startup/stm32h7/startup_stm32h750xx.s
@@ -0,0 +1,764 @@
+/**
+ ******************************************************************************
+ * @file startup_stm32h750xx.s
+ * @author MCD Application Team
+ * @brief STM32H750xx 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 2018 STMicroelectronics
+ *
+ * Redistribution and use in source and binary forms, with or without modification,
+ * are permitted provided that the following conditions are met:
+ * 1. Redistributions of source code must retain the above copyright notice,
+ * this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright notice,
+ * this list of conditions and the following disclaimer in the documentation
+ * and/or other materials provided with the distribution.
+ * 3. Neither the name of STMicroelectronics nor the names of its contributors
+ * may be used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
+ * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
+ * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
+ * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
+ * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
+ * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
+ * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
+ * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
+ * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
+ * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+ *
+ ******************************************************************************
+ */
+
+ .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 */
+
+/* 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
+
+/* 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_IRQHandler /* DCMI */
+ .word CRYP_IRQHandler /* Crypto */
+ .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 SAI2_IRQHandler /* SAI2 */
+ .word QUADSPI_IRQHandler /* QUADSPI */
+ .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 OTG_FS_EP1_OUT_IRQHandler /* USB OTG FS End Point 1 Out */
+ .word OTG_FS_EP1_IN_IRQHandler /* USB OTG FS End Point 1 In */
+ .word OTG_FS_WKUP_IRQHandler /* USB OTG FS Wakeup through EXTI */
+ .word OTG_FS_IRQHandler /* USB OTG FS */
+ .word DMAMUX1_OVR_IRQHandler /* DMAMUX1 Overrun interrupt */
+ .word HRTIM1_Master_IRQHandler /* HRTIM Master Timer global Interrupt */
+ .word HRTIM1_TIMA_IRQHandler /* HRTIM Timer A global Interrupt */
+ .word HRTIM1_TIMB_IRQHandler /* HRTIM Timer B global Interrupt */
+ .word HRTIM1_TIMC_IRQHandler /* HRTIM Timer C global Interrupt */
+ .word HRTIM1_TIMD_IRQHandler /* HRTIM Timer D global Interrupt */
+ .word HRTIM1_TIME_IRQHandler /* HRTIM Timer E global Interrupt */
+ .word HRTIM1_FLT_IRQHandler /* HRTIM Fault global Interrupt */
+ .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 SAI3_IRQHandler /* SAI3 global Interrupt */
+ .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 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 0 /* Reserved */
+ .word SAI4_IRQHandler /* SAI4 global interrupt */
+ .word 0 /* Reserved */
+ .word 0 /* Reserved */
+ .word WAKEUP_PIN_IRQHandler /* Interrupt for all 6 wake-up pins */
+
+/*******************************************************************************
+*
+* 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_IRQHandler
+ .thumb_set DCMI_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 SAI2_IRQHandler
+ .thumb_set SAI2_IRQHandler,Default_Handler
+
+ .weak QUADSPI_IRQHandler
+ .thumb_set QUADSPI_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 OTG_FS_EP1_OUT_IRQHandler
+ .thumb_set OTG_FS_EP1_OUT_IRQHandler,Default_Handler
+
+ .weak OTG_FS_EP1_IN_IRQHandler
+ .thumb_set OTG_FS_EP1_IN_IRQHandler,Default_Handler
+
+ .weak OTG_FS_WKUP_IRQHandler
+ .thumb_set OTG_FS_WKUP_IRQHandler,Default_Handler
+
+ .weak OTG_FS_IRQHandler
+ .thumb_set OTG_FS_IRQHandler,Default_Handler
+
+ .weak DMAMUX1_OVR_IRQHandler
+ .thumb_set DMAMUX1_OVR_IRQHandler,Default_Handler
+
+ .weak HRTIM1_Master_IRQHandler
+ .thumb_set HRTIM1_Master_IRQHandler,Default_Handler
+
+ .weak HRTIM1_TIMA_IRQHandler
+ .thumb_set HRTIM1_TIMA_IRQHandler,Default_Handler
+
+ .weak HRTIM1_TIMB_IRQHandler
+ .thumb_set HRTIM1_TIMB_IRQHandler,Default_Handler
+
+ .weak HRTIM1_TIMC_IRQHandler
+ .thumb_set HRTIM1_TIMC_IRQHandler,Default_Handler
+
+ .weak HRTIM1_TIMD_IRQHandler
+ .thumb_set HRTIM1_TIMD_IRQHandler,Default_Handler
+
+ .weak HRTIM1_TIME_IRQHandler
+ .thumb_set HRTIM1_TIME_IRQHandler,Default_Handler
+
+ .weak HRTIM1_FLT_IRQHandler
+ .thumb_set HRTIM1_FLT_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 SAI3_IRQHandler
+ .thumb_set SAI3_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 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 SAI4_IRQHandler
+ .thumb_set SAI4_IRQHandler,Default_Handler
+
+ .weak WAKEUP_PIN_IRQHandler
+ .thumb_set WAKEUP_PIN_IRQHandler,Default_Handler
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
+
diff --git a/hw/mcu/st/startup/stm32h7/startup_stm32h753xx.s b/hw/mcu/st/startup/stm32h7/startup_stm32h753xx.s
new file mode 100644
index 000000000..fda2b839e
--- /dev/null
+++ b/hw/mcu/st/startup/stm32h7/startup_stm32h753xx.s
@@ -0,0 +1,764 @@
+/**
+ ******************************************************************************
+ * @file startup_stm32h753xx.s
+ * @author MCD Application Team
+ * @brief STM32H753xx 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 2017 STMicroelectronics
+ *
+ * Redistribution and use in source and binary forms, with or without modification,
+ * are permitted provided that the following conditions are met:
+ * 1. Redistributions of source code must retain the above copyright notice,
+ * this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright notice,
+ * this list of conditions and the following disclaimer in the documentation
+ * and/or other materials provided with the distribution.
+ * 3. Neither the name of STMicroelectronics nor the names of its contributors
+ * may be used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
+ * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
+ * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
+ * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
+ * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
+ * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
+ * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
+ * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
+ * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
+ * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+ *
+ ******************************************************************************
+ */
+
+ .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 */
+
+/* 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
+
+/* 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_IRQHandler /* DCMI */
+ .word CRYP_IRQHandler /* Crypto */
+ .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 SAI2_IRQHandler /* SAI2 */
+ .word QUADSPI_IRQHandler /* QUADSPI */
+ .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 OTG_FS_EP1_OUT_IRQHandler /* USB OTG FS End Point 1 Out */
+ .word OTG_FS_EP1_IN_IRQHandler /* USB OTG FS End Point 1 In */
+ .word OTG_FS_WKUP_IRQHandler /* USB OTG FS Wakeup through EXTI */
+ .word OTG_FS_IRQHandler /* USB OTG FS */
+ .word DMAMUX1_OVR_IRQHandler /* DMAMUX1 Overrun interrupt */
+ .word HRTIM1_Master_IRQHandler /* HRTIM Master Timer global Interrupt */
+ .word HRTIM1_TIMA_IRQHandler /* HRTIM Timer A global Interrupt */
+ .word HRTIM1_TIMB_IRQHandler /* HRTIM Timer B global Interrupt */
+ .word HRTIM1_TIMC_IRQHandler /* HRTIM Timer C global Interrupt */
+ .word HRTIM1_TIMD_IRQHandler /* HRTIM Timer D global Interrupt */
+ .word HRTIM1_TIME_IRQHandler /* HRTIM Timer E global Interrupt */
+ .word HRTIM1_FLT_IRQHandler /* HRTIM Fault global Interrupt */
+ .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 SAI3_IRQHandler /* SAI3 global Interrupt */
+ .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 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 0 /* Reserved */
+ .word SAI4_IRQHandler /* SAI4 global interrupt */
+ .word 0 /* Reserved */
+ .word 0 /* Reserved */
+ .word WAKEUP_PIN_IRQHandler /* Interrupt for all 6 wake-up pins */
+
+/*******************************************************************************
+*
+* 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_IRQHandler
+ .thumb_set DCMI_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 SAI2_IRQHandler
+ .thumb_set SAI2_IRQHandler,Default_Handler
+
+ .weak QUADSPI_IRQHandler
+ .thumb_set QUADSPI_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 OTG_FS_EP1_OUT_IRQHandler
+ .thumb_set OTG_FS_EP1_OUT_IRQHandler,Default_Handler
+
+ .weak OTG_FS_EP1_IN_IRQHandler
+ .thumb_set OTG_FS_EP1_IN_IRQHandler,Default_Handler
+
+ .weak OTG_FS_WKUP_IRQHandler
+ .thumb_set OTG_FS_WKUP_IRQHandler,Default_Handler
+
+ .weak OTG_FS_IRQHandler
+ .thumb_set OTG_FS_IRQHandler,Default_Handler
+
+ .weak DMAMUX1_OVR_IRQHandler
+ .thumb_set DMAMUX1_OVR_IRQHandler,Default_Handler
+
+ .weak HRTIM1_Master_IRQHandler
+ .thumb_set HRTIM1_Master_IRQHandler,Default_Handler
+
+ .weak HRTIM1_TIMA_IRQHandler
+ .thumb_set HRTIM1_TIMA_IRQHandler,Default_Handler
+
+ .weak HRTIM1_TIMB_IRQHandler
+ .thumb_set HRTIM1_TIMB_IRQHandler,Default_Handler
+
+ .weak HRTIM1_TIMC_IRQHandler
+ .thumb_set HRTIM1_TIMC_IRQHandler,Default_Handler
+
+ .weak HRTIM1_TIMD_IRQHandler
+ .thumb_set HRTIM1_TIMD_IRQHandler,Default_Handler
+
+ .weak HRTIM1_TIME_IRQHandler
+ .thumb_set HRTIM1_TIME_IRQHandler,Default_Handler
+
+ .weak HRTIM1_FLT_IRQHandler
+ .thumb_set HRTIM1_FLT_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 SAI3_IRQHandler
+ .thumb_set SAI3_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 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 SAI4_IRQHandler
+ .thumb_set SAI4_IRQHandler,Default_Handler
+
+ .weak WAKEUP_PIN_IRQHandler
+ .thumb_set WAKEUP_PIN_IRQHandler,Default_Handler
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
+
diff --git a/hw/mcu/st/system-init/system_stm32h7xx.c b/hw/mcu/st/system-init/system_stm32h7xx.c
new file mode 100644
index 000000000..4018f505d
--- /dev/null
+++ b/hw/mcu/st/system-init/system_stm32h7xx.c
@@ -0,0 +1,576 @@
+/**
+ ******************************************************************************
+ * @file system_stm32h7xx.c
+ * @author MCD Application Team
+ * @brief CMSIS Cortex-Mx Device Peripheral Access Layer System Source File.
+ *
+ * This file provides two functions and one global variable to be called from
+ * user application:
+ * - SystemInit(): This function is called at startup just after reset and
+ * before branch to main program. This call is made inside
+ * the "startup_stm32h7xx.s" file.
+ *
+ * - SystemCoreClock variable: Contains the core clock (HCLK), it can be used
+ * by the user application to setup the SysTick
+ * timer or configure other parameters.
+ *
+ * - SystemCoreClockUpdate(): Updates the variable SystemCoreClock and must
+ * be called whenever the core clock is changed
+ * during program execution.
+ *
+ *
+ ******************************************************************************
+ * @attention
+ *
+ * © COPYRIGHT(c) 2017 STMicroelectronics
+ *
+ * Redistribution and use in source and binary forms, with or without modification,
+ * are permitted provided that the following conditions are met:
+ * 1. Redistributions of source code must retain the above copyright notice,
+ * this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright notice,
+ * this list of conditions and the following disclaimer in the documentation
+ * and/or other materials provided with the distribution.
+ * 3. Neither the name of STMicroelectronics nor the names of its contributors
+ * may be used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
+ * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
+ * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
+ * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
+ * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
+ * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
+ * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
+ * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
+ * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
+ * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+ *
+ ******************************************************************************
+ */
+
+/** @addtogroup CMSIS
+ * @{
+ */
+
+/** @addtogroup stm32h7xx_system
+ * @{
+ */
+
+/** @addtogroup STM32H7xx_System_Private_Includes
+ * @{
+ */
+
+#include "stm32h7xx.h"
+
+#if !defined (HSE_VALUE)
+#define HSE_VALUE ((uint32_t)25000000) /*!< Value of the External oscillator in Hz */
+#endif /* HSE_VALUE */
+
+#if !defined (CSI_VALUE)
+ #define CSI_VALUE ((uint32_t)4000000) /*!< Value of the Internal oscillator in Hz*/
+#endif /* CSI_VALUE */
+
+#if !defined (HSI_VALUE)
+ #define HSI_VALUE ((uint32_t)64000000) /*!< Value of the Internal oscillator in Hz*/
+#endif /* HSI_VALUE */
+
+
+/**
+ * @}
+ */
+
+/** @addtogroup STM32H7xx_System_Private_TypesDefinitions
+ * @{
+ */
+
+/**
+ * @}
+ */
+
+/** @addtogroup STM32H7xx_System_Private_Defines
+ * @{
+ */
+
+/************************* Miscellaneous Configuration ************************/
+/*!< Uncomment the following line if you need to use external SRAM or SDRAM mounted
+ on EVAL board as data memory */
+/*#define DATA_IN_ExtSRAM */
+/*#define DATA_IN_ExtSDRAM*/
+
+#if defined(DATA_IN_ExtSRAM) && defined(DATA_IN_ExtSDRAM)
+ #error "Please select DATA_IN_ExtSRAM or DATA_IN_ExtSDRAM "
+#endif /* DATA_IN_ExtSRAM && DATA_IN_ExtSDRAM */
+
+/*!< Uncomment the following line if you need to relocate your vector Table in
+ Internal SRAM. */
+/* #define VECT_TAB_SRAM */
+#define VECT_TAB_OFFSET 0x00 /*!< Vector Table base offset field.
+ This value must be a multiple of 0x200. */
+/******************************************************************************/
+
+/**
+ * @}
+ */
+
+/** @addtogroup STM32H7xx_System_Private_Macros
+ * @{
+ */
+
+/**
+ * @}
+ */
+
+/** @addtogroup STM32H7xx_System_Private_Variables
+ * @{
+ */
+ /* This variable is updated in three ways:
+ 1) by calling CMSIS function SystemCoreClockUpdate()
+ 2) by calling HAL API function HAL_RCC_GetHCLKFreq()
+ 3) each time HAL_RCC_ClockConfig() is called to configure the system clock frequency
+ Note: If you use this function to configure the system clock; then there
+ is no need to call the 2 first functions listed above, since SystemCoreClock
+ variable is updated automatically.
+ */
+ uint32_t SystemCoreClock = 64000000;
+ uint32_t SystemD2Clock = 64000000;
+ const uint8_t D1CorePrescTable[16] = {0, 0, 0, 0, 1, 2, 3, 4, 1, 2, 3, 4, 6, 7, 8, 9};
+
+/**
+ * @}
+ */
+
+/** @addtogroup STM32H7xx_System_Private_FunctionPrototypes
+ * @{
+ */
+#if defined (DATA_IN_ExtSRAM) || defined (DATA_IN_ExtSDRAM)
+ static void SystemInit_ExtMemCtl(void);
+#endif /* DATA_IN_ExtSRAM || DATA_IN_ExtSDRAM */
+
+/**
+ * @}
+ */
+
+/** @addtogroup STM32H7xx_System_Private_Functions
+ * @{
+ */
+
+/**
+ * @brief Setup the microcontroller system
+ * Initialize the FPU setting, vector table location and External memory
+ * configuration.
+ * @param None
+ * @retval None
+ */
+void SystemInit (void)
+{
+ /* FPU settings ------------------------------------------------------------*/
+ #if (__FPU_PRESENT == 1) && (__FPU_USED == 1)
+ SCB->CPACR |= ((3UL << 10*2)|(3UL << 11*2)); /* set CP10 and CP11 Full Access */
+ #endif
+ /* Reset the RCC clock configuration to the default reset state ------------*/
+ /* Set HSION bit */
+ RCC->CR |= RCC_CR_HSION;
+
+ /* Reset CFGR register */
+ RCC->CFGR = 0x00000000;
+
+ /* Reset HSEON, CSSON , CSION,RC48ON, CSIKERON PLL1ON, PLL2ON and PLL3ON bits */
+ RCC->CR &= (uint32_t)0xEAF6ED7F;
+
+ /* Reset D1CFGR register */
+ RCC->D1CFGR = 0x00000000;
+
+ /* Reset D2CFGR register */
+ RCC->D2CFGR = 0x00000000;
+
+ /* Reset D3CFGR register */
+ RCC->D3CFGR = 0x00000000;
+
+ /* Reset PLLCKSELR register */
+ RCC->PLLCKSELR = 0x00000000;
+
+ /* Reset PLLCFGR register */
+ RCC->PLLCFGR = 0x00000000;
+ /* Reset PLL1DIVR register */
+ RCC->PLL1DIVR = 0x00000000;
+ /* Reset PLL1FRACR register */
+ RCC->PLL1FRACR = 0x00000000;
+
+ /* Reset PLL2DIVR register */
+ RCC->PLL2DIVR = 0x00000000;
+
+ /* Reset PLL2FRACR register */
+
+ RCC->PLL2FRACR = 0x00000000;
+ /* Reset PLL3DIVR register */
+ RCC->PLL3DIVR = 0x00000000;
+
+ /* Reset PLL3FRACR register */
+ RCC->PLL3FRACR = 0x00000000;
+
+ /* Reset HSEBYP bit */
+ RCC->CR &= (uint32_t)0xFFFBFFFF;
+
+ /* Disable all interrupts */
+ RCC->CIER = 0x00000000;
+
+ /* Change the switch matrix read issuing capability to 1 for the AXI SRAM target (Target 7) */
+ *((__IO uint32_t*)0x51008108) = 0x00000001;
+
+#if defined (DATA_IN_ExtSRAM) || defined (DATA_IN_ExtSDRAM)
+ SystemInit_ExtMemCtl();
+#endif /* DATA_IN_ExtSRAM || DATA_IN_ExtSDRAM */
+
+ /* Configure the Vector Table location add offset address ------------------*/
+#ifdef VECT_TAB_SRAM
+ SCB->VTOR = D1_AXISRAM_BASE | VECT_TAB_OFFSET; /* Vector Table Relocation in Internal ITCMSRAM */
+#else
+ SCB->VTOR = FLASH_BANK1_BASE | VECT_TAB_OFFSET; /* Vector Table Relocation in Internal FLASH */
+#endif
+
+}
+
+/**
+ * @brief Update SystemCoreClock variable according to Clock Register Values.
+ * The SystemCoreClock variable contains the core clock , it can
+ * be used by the user application to setup the SysTick timer or configure
+ * other parameters.
+ *
+ * @note Each time the core clock changes, this function must be called
+ * to update SystemCoreClock variable value. Otherwise, any configuration
+ * based on this variable will be incorrect.
+ *
+ * @note - The system frequency computed by this function is not the real
+ * frequency in the chip. It is calculated based on the predefined
+ * constant and the selected clock source:
+ *
+ * - If SYSCLK source is CSI, SystemCoreClock will contain the CSI_VALUE(*)
+ * - If SYSCLK source is HSI, SystemCoreClock will contain the HSI_VALUE(**)
+ * - If SYSCLK source is HSE, SystemCoreClock will contain the HSE_VALUE(***)
+ * - If SYSCLK source is PLL, SystemCoreClock will contain the CSI_VALUE(*),
+ * HSI_VALUE(**) or HSE_VALUE(***) multiplied/divided by the PLL factors.
+ *
+ * (*) CSI_VALUE is a constant defined in stm32h7xx_hal.h file (default value
+ * 4 MHz) but the real value may vary depending on the variations
+ * in voltage and temperature.
+ * (**) HSI_VALUE is a constant defined in stm32h7xx_hal.h file (default value
+ * 64 MHz) but the real value may vary depending on the variations
+ * in voltage and temperature.
+ *
+ * (***)HSE_VALUE is a constant defined in stm32h7xx_hal.h file (default value
+ * 25 MHz), user has to ensure that HSE_VALUE is same as the real
+ * frequency of the crystal used. Otherwise, this function may
+ * have wrong result.
+ *
+ * - The result of this function could be not correct when using fractional
+ * value for HSE crystal.
+ * @param None
+ * @retval None
+ */
+void SystemCoreClockUpdate (void)
+{
+uint32_t pllp = 2, pllsource = 0, pllm = 2 ,tmp, pllfracen =0 , hsivalue = 0;
+float fracn1, pllvco = 0 ;
+
+ /* Get SYSCLK source -------------------------------------------------------*/
+
+ switch (RCC->CFGR & RCC_CFGR_SWS)
+ {
+ case 0x00: /* HSI used as system clock source */
+ SystemCoreClock = (uint32_t) (HSI_VALUE >> ((RCC->CR & RCC_CR_HSIDIV)>> 3));
+ break;
+
+ case 0x08: /* CSI used as system clock source */
+ SystemCoreClock = CSI_VALUE;
+ break;
+
+ case 0x10: /* HSE used as system clock source */
+ SystemCoreClock = HSE_VALUE;
+ break;
+
+ case 0x18: /* PLL1 used as system clock source */
+
+ /* PLL_VCO = (HSE_VALUE or HSI_VALUE or CSI_VALUE/ PLLM) * PLLN
+ SYSCLK = PLL_VCO / PLLR
+ */
+ pllsource = (RCC->PLLCKSELR & RCC_PLLCKSELR_PLLSRC);
+ pllm = ((RCC->PLLCKSELR & RCC_PLLCKSELR_DIVM1)>> 4) ;
+ pllfracen = RCC->PLLCFGR & RCC_PLLCFGR_PLL1FRACEN;
+ fracn1 = (pllfracen* ((RCC->PLL1FRACR & RCC_PLL1FRACR_FRACN1)>> 3));
+ switch (pllsource)
+ {
+
+ case 0x00: /* HSI used as PLL clock source */
+ hsivalue = (HSI_VALUE >> ((RCC->CR & RCC_CR_HSIDIV)>> 3)) ;
+ pllvco = (hsivalue/ pllm) * ((RCC->PLL1DIVR & RCC_PLL1DIVR_N1) + (fracn1/0x2000) +1 );
+ break;
+
+ case 0x01: /* CSI used as PLL clock source */
+ pllvco = (CSI_VALUE / pllm) * ((RCC->PLL1DIVR & RCC_PLL1DIVR_N1) + (fracn1/0x2000) +1 );
+ break;
+
+ case 0x02: /* HSE used as PLL clock source */
+ pllvco = (HSE_VALUE / pllm) * ((RCC->PLL1DIVR & RCC_PLL1DIVR_N1) + (fracn1/0x2000) +1 );
+ break;
+
+ default:
+ pllvco = (CSI_VALUE / pllm) * ((RCC->PLL1DIVR & RCC_PLL1DIVR_N1) + (fracn1/0x2000) +1 );
+ break;
+ }
+ pllp = (((RCC->PLL1DIVR & RCC_PLL1DIVR_P1) >>9) + 1 ) ;
+ SystemCoreClock = (uint32_t) (pllvco/pllp);
+ break;
+
+ default:
+ SystemCoreClock = CSI_VALUE;
+ break;
+ }
+
+ /* Compute HCLK frequency --------------------------------------------------*/
+ /* Get HCLK prescaler */
+ tmp = D1CorePrescTable[(RCC->D1CFGR & RCC_D1CFGR_D1CPRE)>> POSITION_VAL(RCC_D1CFGR_D1CPRE_0)];
+ /* HCLK frequency */
+ SystemCoreClock >>= tmp;
+}
+#if defined (DATA_IN_ExtSRAM) || defined (DATA_IN_ExtSDRAM)
+/**
+ * @brief Setup the external memory controller.
+ * Called in startup_stm32h7xx.s before jump to main.
+ * This function configures the external memories (SRAM/SDRAM)
+ * This SRAM/SDRAM will be used as program data memory (including heap and stack).
+ * @param None
+ * @retval None
+ */
+void SystemInit_ExtMemCtl(void)
+{
+#if defined (DATA_IN_ExtSDRAM)
+ register uint32_t tmpreg = 0, timeout = 0xFFFF;
+ register __IO uint32_t index;
+
+ /* Enable GPIOD, GPIOE, GPIOF, GPIOG, GPIOH and GPIOI interface
+ clock */
+ RCC->AHB4ENR |= 0x000001F8;
+ /* Connect PDx pins to FMC Alternate function */
+ GPIOD->AFR[0] = 0x000000CC;
+ GPIOD->AFR[1] = 0xCC000CCC;
+ /* Configure PDx pins in Alternate function mode */
+ GPIOD->MODER = 0xAFEAFFFA;
+ /* Configure PDx pins speed to 50 MHz */
+ GPIOD->OSPEEDR = 0xA02A000A;
+ /* Configure PDx pins Output type to push-pull */
+ GPIOD->OTYPER = 0x00000000;
+ /* No pull-up, pull-down for PDx pins */
+ GPIOD->PUPDR = 0x55555505;
+ /* Connect PEx pins to FMC Alternate function */
+ GPIOE->AFR[0] = 0xC00000CC;
+ GPIOE->AFR[1] = 0xCCCCCCCC;
+ /* Configure PEx pins in Alternate function mode */
+ GPIOE->MODER = 0xAAAABFFA;
+ /* Configure PEx pins speed to 50 MHz */
+ GPIOE->OSPEEDR = 0xAAAA800A;
+ /* Configure PEx pins Output type to push-pull */
+ GPIOE->OTYPER = 0x00000000;
+ /* No pull-up, pull-down for PEx pins */
+ GPIOE->PUPDR = 0x55554005;
+ /* Connect PFx pins to FMC Alternate function */
+ GPIOF->AFR[0] = 0x00CCCCCC;
+ GPIOF->AFR[1] = 0xCCCCC000;
+ /* Configure PFx pins in Alternate function mode */
+ GPIOF->MODER = 0xAABFFAAA;
+ /* Configure PFx pins speed to 50 MHz */
+ GPIOF->OSPEEDR = 0xAA800AAA;
+ /* Configure PFx pins Output type to push-pull */
+ GPIOF->OTYPER = 0x00000000;
+ /* No pull-up, pull-down for PFx pins */
+ GPIOF->PUPDR = 0x55400555;
+ /* Connect PGx pins to FMC Alternate function */
+ GPIOG->AFR[0] = 0x00CCCCCC;
+ GPIOG->AFR[1] = 0xC000000C;
+ /* Configure PGx pins in Alternate function mode */
+ GPIOG->MODER = 0xBFFEFAAA;
+ /* Configure PGx pins speed to 50 MHz */
+ GPIOG->OSPEEDR = 0x80020AAA;
+ /* Configure PGx pins Output type to push-pull */
+ GPIOG->OTYPER = 0x00000000;
+ /* No pull-up, pull-down for PGx pins */
+ GPIOG->PUPDR = 0x40010515;
+ /* Connect PHx pins to FMC Alternate function */
+ GPIOH->AFR[0] = 0xCCC00000;
+ GPIOH->AFR[1] = 0xCCCCCCCC;
+ /* Configure PHx pins in Alternate function mode */
+ GPIOH->MODER = 0xAAAAABFF;
+ /* Configure PHx pins speed to 50 MHz */
+ GPIOH->OSPEEDR = 0xAAAAA800;
+ /* Configure PHx pins Output type to push-pull */
+ GPIOH->OTYPER = 0x00000000;
+ /* No pull-up, pull-down for PHx pins */
+ GPIOH->PUPDR = 0x55555400;
+ /* Connect PIx pins to FMC Alternate function */
+ GPIOI->AFR[0] = 0xCCCCCCCC;
+ GPIOI->AFR[1] = 0x00000CC0;
+ /* Configure PIx pins in Alternate function mode */
+ GPIOI->MODER = 0xFFEBAAAA;
+ /* Configure PIx pins speed to 50 MHz */
+ GPIOI->OSPEEDR = 0x0028AAAA;
+ /* Configure PIx pins Output type to push-pull */
+ GPIOI->OTYPER = 0x00000000;
+ /* No pull-up, pull-down for PIx pins */
+ GPIOI->PUPDR = 0x00145555;
+/*-- FMC Configuration ------------------------------------------------------*/
+ /* Enable the FMC interface clock */
+ (RCC->AHB3ENR |= (RCC_AHB3ENR_FMCEN));
+ /*SDRAM Timing and access interface configuration*/
+ /*LoadToActiveDelay = 2
+ ExitSelfRefreshDelay = 6
+ SelfRefreshTime = 4
+ RowCycleDelay = 6
+ WriteRecoveryTime = 2
+ RPDelay = 2
+ RCDDelay = 2
+ SDBank = FMC_SDRAM_BANK2
+ ColumnBitsNumber = FMC_SDRAM_COLUMN_BITS_NUM_9
+ RowBitsNumber = FMC_SDRAM_ROW_BITS_NUM_12
+ MemoryDataWidth = FMC_SDRAM_MEM_BUS_WIDTH_32
+ InternalBankNumber = FMC_SDRAM_INTERN_BANKS_NUM_4
+ CASLatency = FMC_SDRAM_CAS_LATENCY_2
+ WriteProtection = FMC_SDRAM_WRITE_PROTECTION_DISABLE
+ SDClockPeriod = FMC_SDRAM_CLOCK_PERIOD_2
+ ReadBurst = FMC_SDRAM_RBURST_ENABLE
+ ReadPipeDelay = FMC_SDRAM_RPIPE_DELAY_0*/
+
+ FMC_Bank5_6->SDCR[0] = 0x00001800;
+ FMC_Bank5_6->SDCR[1] = 0x00000165;
+ FMC_Bank5_6->SDTR[0] = 0x00105000;
+ FMC_Bank5_6->SDTR[1] = 0x01010351;
+
+ /* SDRAM initialization sequence */
+ /* Clock enable command */
+ FMC_Bank5_6->SDCMR = 0x00000009;
+ tmpreg = FMC_Bank5_6->SDSR & 0x00000020;
+ while((tmpreg != 0) && (timeout-- > 0))
+ {
+ tmpreg = FMC_Bank5_6->SDSR & 0x00000020;
+ }
+
+ /* Delay */
+ for (index = 0; index<1000; index++);
+
+ /* PALL command */
+ FMC_Bank5_6->SDCMR = 0x0000000A;
+ timeout = 0xFFFF;
+ while((tmpreg != 0) && (timeout-- > 0))
+ {
+ tmpreg = FMC_Bank5_6->SDSR & 0x00000020;
+ }
+
+ FMC_Bank5_6->SDCMR = 0x000000EB;
+ timeout = 0xFFFF;
+ while((tmpreg != 0) && (timeout-- > 0))
+ {
+ tmpreg = FMC_Bank5_6->SDSR & 0x00000020;
+ }
+
+ FMC_Bank5_6->SDCMR = 0x0004400C;
+ timeout = 0xFFFF;
+ while((tmpreg != 0) && (timeout-- > 0))
+ {
+ tmpreg = FMC_Bank5_6->SDSR & 0x00000020;
+ }
+ /* Set refresh count */
+ tmpreg = FMC_Bank5_6->SDRTR;
+ FMC_Bank5_6->SDRTR = (tmpreg | (0x00000603<<1));
+
+ /* Disable write protection */
+ tmpreg = FMC_Bank5_6->SDCR[1];
+ FMC_Bank5_6->SDCR[1] = (tmpreg & 0xFFFFFDFF);
+
+ /*FMC controller Enable*/
+ FMC_Bank1->BTCR[0] |= 0x80000000;
+
+
+#endif /* DATA_IN_ExtSDRAM */
+
+#if defined(DATA_IN_ExtSRAM)
+/*-- GPIOs Configuration -----------------------------------------------------*/
+ /* Enable GPIOD, GPIOE, GPIOF and GPIOG interface clock */
+ RCC->AHB4ENR |= 0x00000078;
+
+ /* Connect PDx pins to FMC Alternate function */
+ GPIOD->AFR[0] = 0x00CCC0CC;
+ GPIOD->AFR[1] = 0xCCCCCCCC;
+ /* Configure PDx pins in Alternate function mode */
+ GPIOD->MODER = 0xAAAA0A8A;
+ /* Configure PDx pins speed to 100 MHz */
+ GPIOD->OSPEEDR = 0xFFFF0FCF;
+ /* Configure PDx pins Output type to push-pull */
+ GPIOD->OTYPER = 0x00000000;
+ /* No pull-up, pull-down for PDx pins */
+ GPIOD->PUPDR = 0x55550545;
+
+ /* Connect PEx pins to FMC Alternate function */
+ GPIOE->AFR[0] = 0xC00CC0CC;
+ GPIOE->AFR[1] = 0xCCCCCCCC;
+ /* Configure PEx pins in Alternate function mode */
+ GPIOE->MODER = 0xAAAA828A;
+ /* Configure PEx pins speed to 100 MHz */
+ GPIOE->OSPEEDR = 0xFFFFC3CF;
+ /* Configure PEx pins Output type to push-pull */
+ GPIOE->OTYPER = 0x00000000;
+ /* No pull-up, pull-down for PEx pins */
+ GPIOE->PUPDR = 0x55554145;
+
+ /* Connect PFx pins to FMC Alternate function */
+ GPIOF->AFR[0] = 0x00CCCCCC;
+ GPIOF->AFR[1] = 0xCCCC0000;
+ /* Configure PFx pins in Alternate function mode */
+ GPIOF->MODER = 0xAA000AAA;
+ /* Configure PFx pins speed to 100 MHz */
+ GPIOF->OSPEEDR = 0xFF000FFF;
+ /* Configure PFx pins Output type to push-pull */
+ GPIOF->OTYPER = 0x00000000;
+ /* No pull-up, pull-down for PFx pins */
+ GPIOF->PUPDR = 0x55000555;
+
+ /* Connect PGx pins to FMC Alternate function */
+ GPIOG->AFR[0] = 0x00CCCCCC;
+ GPIOG->AFR[1] = 0x000000C0;
+ /* Configure PGx pins in Alternate function mode */
+ GPIOG->MODER = 0x00200AAA;
+ /* Configure PGx pins speed to 100 MHz */
+ GPIOG->OSPEEDR = 0x00300FFF;
+ /* Configure PGx pins Output type to push-pull */
+ GPIOG->OTYPER = 0x00000000;
+ /* No pull-up, pull-down for PGx pins */
+ GPIOG->PUPDR = 0x00100555;
+
+/*-- FMC/FSMC Configuration --------------------------------------------------*/
+ /* Enable the FMC/FSMC interface clock */
+ (RCC->AHB3ENR |= (RCC_AHB3ENR_FMCEN));
+
+ /* Configure and enable Bank1_SRAM2 */
+ FMC_Bank1->BTCR[4] = 0x00001091;
+ FMC_Bank1->BTCR[5] = 0x00110212;
+ FMC_Bank1E->BWTR[4] = 0x0FFFFFFF;
+
+ /*FMC controller Enable*/
+ FMC_Bank1->BTCR[0] |= 0x80000000;
+
+
+#endif /* DATA_IN_ExtSRAM */
+}
+#endif /* DATA_IN_ExtSRAM || DATA_IN_ExtSDRAM */
+
+
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/src/portable/st/stm32h7/dcd_stm32h7.c b/src/portable/st/stm32h7/dcd_stm32h7.c
new file mode 100644
index 000000000..4d6551706
--- /dev/null
+++ b/src/portable/st/stm32h7/dcd_stm32h7.c
@@ -0,0 +1,118 @@
+/*
+ * The MIT License (MIT)
+ *
+ * Copyright (c) 2019 William D. Jones for Adafruit Industries
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to deal
+ * in the Software without restriction, including without limitation the rights
+ * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
+ * copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
+ * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
+ * THE SOFTWARE.
+ *
+ * This file is part of the TinyUSB stack.
+ */
+
+#include "tusb_option.h"
+
+#if TUSB_OPT_DEVICE_ENABLED && CFG_TUSB_MCU == OPT_MCU_STM32H7
+
+#include "device/dcd.h"
+#include "stm32h7xx.h"
+
+/*------------------------------------------------------------------*/
+/* MACRO TYPEDEF CONSTANT ENUM
+ *------------------------------------------------------------------*/
+
+/*------------------------------------------------------------------*/
+/* Controller API
+ *------------------------------------------------------------------*/
+void dcd_init (uint8_t rhport)
+{
+ (void) rhport;
+}
+
+void dcd_int_enable (uint8_t rhport)
+{
+ (void) rhport;
+ NVIC_EnableIRQ(OTG_FS_IRQn);
+}
+
+void dcd_int_disable (uint8_t rhport)
+{
+ (void) rhport;
+ NVIC_DisableIRQ(OTG_FS_IRQn);
+}
+
+void dcd_set_address (uint8_t rhport, uint8_t dev_addr)
+{
+ (void) rhport;
+ (void) dev_addr;
+}
+
+void dcd_set_config (uint8_t rhport, uint8_t config_num)
+{
+ (void) rhport;
+ (void) config_num;
+ // Nothing to do
+}
+
+void dcd_remote_wakeup(uint8_t rhport)
+{
+ (void) rhport;
+}
+
+/*------------------------------------------------------------------*/
+/* DCD Endpoint port
+ *------------------------------------------------------------------*/
+bool dcd_edpt_open (uint8_t rhport, tusb_desc_endpoint_t const * desc_edpt)
+{
+ (void) rhport;
+ (void) desc_edpt;
+
+ return false;
+}
+
+bool dcd_edpt_xfer (uint8_t rhport, uint8_t ep_addr, uint8_t * buffer, uint16_t total_bytes)
+{
+ (void) rhport;
+ (void) ep_addr;
+ (void) buffer;
+ (void) total_bytes;
+
+ return false;
+}
+
+// TODO: The logic for STALLing and disabling an endpoint is very similar
+// (send STALL versus NAK handshakes back). Refactor into resuable function.
+void dcd_edpt_stall (uint8_t rhport, uint8_t ep_addr)
+{
+ (void) rhport;
+ (void) ep_addr;
+}
+
+void dcd_edpt_clear_stall (uint8_t rhport, uint8_t ep_addr)
+{
+ (void) rhport;
+ (void) ep_addr;
+}
+
+/*------------------------------------------------------------------*/
+
+void OTG_FS_IRQHandler (void)
+{
+
+}
+
+#endif
diff --git a/src/tusb_option.h b/src/tusb_option.h
index a273d59b3..7fc06a8cb 100644
--- a/src/tusb_option.h
+++ b/src/tusb_option.h
@@ -1,4 +1,4 @@
-/*
+/*
* The MIT License (MIT)
*
* Copyright (c) 2019 Ha Thach (tinyusb.org)
@@ -50,6 +50,7 @@
#define OPT_MCU_STM32F4 300 ///< ST STM32F4
#define OPT_MCU_STM32F3 301 ///< ST STM32F3
+#define OPT_MCU_STM32H7 302 ///< ST STM32H7
/** @} */