diff --git a/make/mcu/STM32H7.mk b/make/mcu/STM32H7.mk new file mode 100644 index 0000000000..c14bf8d1e2 --- /dev/null +++ b/make/mcu/STM32H7.mk @@ -0,0 +1,252 @@ +# +# H7 Make file include +# + +# Override LINKER_DIR until H7 merge is complete +LINKER_DIR = $(ROOT)/src/main/target/link + +ifeq ($(DEBUG_HARDFAULTS),H7) +CFLAGS += -DDEBUG_HARDFAULTS +endif + +#CMSIS +CMSIS_DIR := $(ROOT)/lib/main/CMSIS + +#STDPERIPH +STDPERIPH_DIR = $(ROOT)/lib/main/STM32H7/Drivers/STM32H7xx_HAL_Driver +STDPERIPH_SRC = $(notdir $(wildcard $(STDPERIPH_DIR)/Src/*.c)) + +EXCLUDES = \ + #stm32h7xx_hal.c \ + #stm32h7xx_hal_adc.c \ + #stm32h7xx_hal_adc_ex.c \ + stm32h7xx_hal_cec.c \ + stm32h7xx_hal_comp.c \ + #stm32h7xx_hal_cortex.c \ + stm32h7xx_hal_crc.c \ + stm32h7xx_hal_crc_ex.c \ + stm32h7xx_hal_cryp.c \ + stm32h7xx_hal_cryp_ex.c \ + stm32h7xx_hal_dac.c \ + stm32h7xx_hal_dac_ex.c \ + stm32h7xx_hal_dcmi.c \ + stm32h7xx_hal_dfsdm.c \ + #stm32h7xx_hal_dma.c \ + stm32h7xx_hal_dma2d.c \ + #stm32h7xx_hal_dma_ex.c \ + stm32h7xx_hal_eth.c \ + stm32h7xx_hal_eth_ex.c \ + stm32h7xx_hal_fdcan.c \ + #stm32h7xx_hal_flash.c \ + #stm32h7xx_hal_flash_ex.c \ + #stm32h7xx_hal_gpio.c \ + stm32h7xx_hal_hash.c \ + stm32h7xx_hal_hash_ex.c \ + stm32h7xx_hal_hcd.c \ + stm32h7xx_hal_hrtim.c \ + stm32h7xx_hal_hsem.c \ + #stm32h7xx_hal_i2c.c \ + #stm32h7xx_hal_i2c_ex.c \ + stm32h7xx_hal_i2s.c \ + stm32h7xx_hal_i2s_ex.c \ + stm32h7xx_hal_irda.c \ + stm32h7xx_hal_iwdg.c \ + stm32h7xx_hal_jpeg.c \ + stm32h7xx_hal_lptim.c \ + stm32h7xx_hal_ltdc.c \ + stm32h7xx_hal_mdios.c \ + stm32h7xx_hal_mdma.c \ + stm32h7xx_hal_mmc.c \ + stm32h7xx_hal_mmc_ex.c \ + stm32h7xx_hal_nand.c \ + stm32h7xx_hal_nor.c \ + stm32h7xx_hal_opamp.c \ + stm32h7xx_hal_opamp_ex.c \ + #stm32h7xx_hal_pcd.c \ + #stm32h7xx_hal_pcd_ex.c \ + #stm32h7xx_hal_pwr.c \ + #stm32h7xx_hal_pwr_ex.c \ + stm32h7xx_hal_qspi.c \ + #stm32h7xx_hal_rcc.c \ + #stm32h7xx_hal_rcc_ex.c \ + stm32h7xx_hal_rng.c \ + stm32h7xx_hal_rtc.c \ + stm32h7xx_hal_rtc_ex.c \ + stm32h7xx_hal_sai.c \ + stm32h7xx_hal_sai_ex.c \ + stm32h7xx_hal_sd.c \ + stm32h7xx_hal_sd_ex.c \ + stm32h7xx_hal_sdram.c \ + stm32h7xx_hal_smartcard.c \ + stm32h7xx_hal_smartcard_ex.c \ + stm32h7xx_hal_smbus.c \ + stm32h7xx_hal_spdifrx.c \ + #stm32h7xx_hal_spi.c \ + #stm32h7xx_hal_spi_ex.c \ + stm32h7xx_hal_sram.c \ + stm32h7xx_hal_swpmi.c \ + #stm32h7xx_hal_tim.c \ + #stm32h7xx_hal_tim_ex.c \ + #stm32h7xx_hal_uart.c \ + #stm32h7xx_hal_uart_ex.c \ + stm32h7xx_hal_usart.c \ + stm32h7xx_hal_wwdg.c \ + stm32h7xx_ll_delayblock.c \ + stm32h7xx_ll_fmc.c \ + stm32h7xx_ll_sdmmc.c \ + #stm32h7xx_ll_usb.c + +STDPERIPH_SRC := $(filter-out ${EXCLUDES}, $(STDPERIPH_SRC)) + +#USB +USBCORE_DIR = $(ROOT)/lib/main/STM32H7/Middlewares/ST/STM32_USB_Device_Library/Core +USBCORE_SRC = $(notdir $(wildcard $(USBCORE_DIR)/Src/*.c)) +EXCLUDES = usbd_conf_template.c +USBCORE_SRC := $(filter-out ${EXCLUDES}, $(USBCORE_SRC)) + +USBCDC_DIR = $(ROOT)/lib/main/STM32H7/Middlewares/ST/STM32_USB_Device_Library/Class/CDC +USBCDC_SRC = $(notdir $(wildcard $(USBCDC_DIR)/Src/*.c)) +EXCLUDES = usbd_cdc_if_template.c +USBCDC_SRC := $(filter-out ${EXCLUDES}, $(USBCDC_SRC)) + +USBHID_DIR = $(ROOT)/lib/main/STM32H7/Middlewares/ST/STM32_USB_Device_Library/Class/HID +USBHID_SRC = $(notdir $(wildcard $(USBHID_DIR)/Src/*.c)) + +USBMSC_DIR = $(ROOT)/lib/main/STM32H7/Middlewares/ST/STM32_USB_Device_Library/Class/MSC +USBMSC_SRC = $(notdir $(wildcard $(USBMSC_DIR)/Src/*.c)) +EXCLUDES = usbd_msc_storage_template.c usbd_msc_scsi.c +USBMSC_SRC := $(filter-out ${EXCLUDES}, $(USBMSC_SRC)) + +VPATH := $(VPATH):$(USBCDC_DIR)/Src:$(USBCORE_DIR)/Src:$(USBHID_DIR)/Src:$(USBMSC_DIR)/Src + +DEVICE_STDPERIPH_SRC := $(STDPERIPH_SRC) \ + $(USBCORE_SRC) \ + $(USBCDC_SRC) \ + $(USBHID_SRC) \ + $(USBMSC_SRC) + +#CMSIS +VPATH := $(VPATH):$(CMSIS_DIR)/Include:$(CMSIS_DIR)/Device/ST/STM32H7xx +VPATH := $(VPATH):$(STDPERIPH_DIR)/Src +CMSIS_SRC := +INCLUDE_DIRS := $(INCLUDE_DIRS) \ + $(STDPERIPH_DIR)/Inc \ + $(USBCORE_DIR)/Inc \ + $(USBCDC_DIR)/Inc \ + $(USBHID_DIR)/Inc \ + $(USBMSC_DIR)/Inc \ + $(CMSIS_DIR)/Core/Include \ + $(ROOT)/lib/main/STM32H7/Drivers/CMSIS/Device/ST/STM32H7xx/Include \ + $(ROOT)/src/main/vcph7 + +ifneq ($(filter SDCARD_SPI,$(FEATURES)),) +INCLUDE_DIRS := $(INCLUDE_DIRS) \ + $(FATFS_DIR) +VPATH := $(VPATH):$(FATFS_DIR) +endif + +ifneq ($(filter SDCARD_SDIO,$(FEATURES)),) +INCLUDE_DIRS := $(INCLUDE_DIRS) \ + $(FATFS_DIR) +VPATH := $(VPATH):$(FATFS_DIR) +endif + +#Flags +ARCH_FLAGS = -mthumb -mcpu=cortex-m7 -mfloat-abi=hard -mfpu=fpv5-sp-d16 -fsingle-precision-constant -Wdouble-promotion + +DEVICE_FLAGS = -DUSE_HAL_DRIVER -DUSE_DMA_RAM + +# +# H743xI : 2M FLASH, 1M RAM (H753xI also) +# H743xG : 1M FLASH, 1M RAM (H753xG also) +# H750xB : 128K FLASH, 1M RAM +# +ifeq ($(TARGET),$(filter $(TARGET),$(H743xI_TARGETS))) +DEVICE_FLAGS += -DSTM32H743xx +LD_SCRIPT = $(LINKER_DIR)/stm32_flash_h743_2m.ld +STARTUP_SRC = startup_stm32h743xx.s +TARGET_FLASH := 2048 +else ifeq ($(TARGET),$(filter $(TARGET),$(H750xB_TARGETS))) +DEVICE_FLAGS += -DSTM32H750xx +LD_SCRIPT = $(LINKER_DIR)/stm32_flash_h750.ld +STARTUP_SRC = startup_stm32h743xx.s +TARGET_FLASH := 128 + +ifneq ($(DEBUG),GDB) +OPTIMISE_DEFAULT := -Os +OPTIMISE_SPEED := -Os +OPTIMISE_SIZE := -Os + +LTO_FLAGS := $(OPTIMISATION_BASE) $(OPTIMISE_DEFAULT) +endif + +else +$(error Unknown MCU for H7 target) +endif + +ifneq ($(FIRMWARE_SIZE),) +DEVICE_FLAGS += -DFIRMWARE_SIZE=$(FIRMWARE_SIZE) +endif + +DEVICE_FLAGS += -DHSE_VALUE=$(HSE_VALUE) -DHSE_STARTUP_TIMEOUT=1000 + +TARGET_FLAGS = -D$(TARGET) + +VCP_SRC = \ + vcph7/usbd_desc.c \ + vcph7/usbd_conf.c \ + vcph7/usbd_cdc_hid.c \ + vcph7/usbd_cdc_interface.c \ + drivers/serial_usb_vcp.c \ + drivers/usb_io.c + +MCU_COMMON_SRC = \ + target/system_stm32h7xx.c \ + drivers/system_stm32h7xx.c \ + drivers/timer_hal.c \ + drivers/timer_stm32h7xx.c \ + drivers/serial_uart_stm32h7xx.c \ + drivers/serial_uart_hal.c \ + drivers/bus_quadspi_hal.c \ + drivers/bus_spi_hal.c \ + drivers/dma_stm32h7xx.c \ + drivers/light_ws2811strip_hal.c \ + drivers/adc_stm32h7xx.c \ + drivers/bus_i2c_hal.c \ + drivers/pwm_output_dshot_hal_hal.c \ + drivers/persistent.c \ + drivers/transponder_ir_io_hal.c \ + drivers/audio_stm32h7xx.c \ + #drivers/accgyro/accgyro_mpu.c \ + +MCU_EXCLUDES = \ + drivers/bus_i2c.c \ + drivers/timer.c \ + drivers/serial_uart.c + +#MSC_SRC = \ +# drivers/usb_msc_h7xx.c \ +# msc/usbd_storage.c + +ifneq ($(filter SDCARD_SDIO,$(FEATURES)),) +MCU_COMMON_SRC += \ + drivers/sdio_h7xx.c +MSC_SRC += \ + msc/usbd_storage_sdio.c +endif + +#ifneq ($(filter SDCARD_SPI,$(FEATURES)),) +#MSC_SRC += \ +# msc/usbd_storage_sd_spi.c +#endif + +#ifneq ($(filter ONBOARDFLASH,$(FEATURES)),) +#MSC_SRC += \ +# msc/usbd_storage_emfat.c \ +# msc/emfat.c \ +# msc/emfat_file.c +#endif + +DSP_LIB := $(ROOT)/lib/main/CMSIS/DSP +DEVICE_FLAGS += -DARM_MATH_MATRIX_CHECK -DARM_MATH_ROUNDING -D__FPU_PRESENT=1 -DUNALIGNED_SUPPORT_DISABLE -DARM_MATH_CM7 + diff --git a/make/source.mk b/make/source.mk index eceef2714d..478b3583a8 100644 --- a/make/source.mk +++ b/make/source.mk @@ -15,6 +15,7 @@ COMMON_SRC = \ drivers/bus_i2c_config.c \ drivers/bus_i2c_busdev.c \ drivers/bus_i2c_soft.c \ + drivers/bus_quadspi.c \ drivers/bus_spi.c \ drivers/bus_spi_config.c \ drivers/bus_spi_pinconfig.c \ @@ -214,6 +215,7 @@ SPEED_OPTIMISED_SRC := $(SPEED_OPTIMISED_SRC) \ drivers/adc.c \ drivers/buf_writer.c \ drivers/bus.c \ + drivers/bus_quadspi.c \ drivers/bus_spi.c \ drivers/exti.c \ drivers/io.c \ diff --git a/make/targets.mk b/make/targets.mk index 99d9ee844e..3456cbc27f 100644 --- a/make/targets.mk +++ b/make/targets.mk @@ -19,13 +19,14 @@ endif F4_TARGETS := $(F405_TARGETS) $(F411_TARGETS) $(F446_TARGETS) F7_TARGETS := $(F7X2RE_TARGETS) $(F7X5XE_TARGETS) $(F7X5XG_TARGETS) $(F7X5XI_TARGETS) $(F7X6XG_TARGETS) +H7_TARGETS := $(H743xI_TARGETS) $(H750xB_TARGETS) ifeq ($(filter $(TARGET),$(VALID_TARGETS)),) $(error Target '$(TARGET)' is not valid, must be one of $(VALID_TARGETS). Have you prepared a valid target.mk?) endif -ifeq ($(filter $(TARGET),$(F1_TARGETS) $(F3_TARGETS) $(F4_TARGETS) $(F7_TARGETS) $(SITL_TARGETS)),) -$(error Target '$(TARGET)' has not specified a valid STM group, must be one of F1, F3, F405, F411 or F7x5. Have you prepared a valid target.mk?) +ifeq ($(filter $(TARGET),$(F1_TARGETS) $(F3_TARGETS) $(F4_TARGETS) $(F7_TARGETS) $(H7_TARGETS) $(SITL_TARGETS)),) +$(error Target '$(TARGET)' has not specified a valid STM group, must be one of F1, F3, F405, F411, F446, F7X2RE, F7X5XE, F7X5XG, F7X5XI, F7X6XG or H7X3XI. Have you prepared a valid target.mk?) endif ifeq ($(TARGET),$(filter $(TARGET),$(F3_TARGETS))) @@ -37,6 +38,9 @@ TARGET_MCU := STM32F4 else ifeq ($(TARGET),$(filter $(TARGET), $(F7_TARGETS))) TARGET_MCU := STM32F7 +else ifeq ($(TARGET),$(filter $(TARGET), $(H7_TARGETS))) +TARGET_MCU := STM32H7 + else ifeq ($(TARGET),$(filter $(TARGET), $(SITL_TARGETS))) TARGET_MCU := SITL SIMULATOR_BUILD = yes diff --git a/src/main/cli/settings.c b/src/main/cli/settings.c index 57958501c7..2a65b8d0c3 100644 --- a/src/main/cli/settings.c +++ b/src/main/cli/settings.c @@ -1160,6 +1160,9 @@ const clivalue_t valueTable[] = { { "osd_rssi_alarm", VAR_UINT8 | MASTER_VALUE, .config.minmaxUnsigned = { 0, 100 }, PG_OSD_CONFIG, offsetof(osdConfig_t, rssi_alarm) }, #ifdef USE_RX_LINK_QUALITY_INFO { "osd_link_quality_alarm", VAR_UINT16 | MASTER_VALUE, .config.minmaxUnsigned = { 0, 300 }, PG_OSD_CONFIG, offsetof(osdConfig_t, link_quality_alarm) }, +#endif +#ifdef USE_RX_RSSI_DBM + { "osd_rssi_dbm_alarm", VAR_UINT8 | MASTER_VALUE, .config.minmaxUnsigned = { 0, 130 }, PG_OSD_CONFIG, offsetof(osdConfig_t, rssi_dbm_alarm) }, #endif { "osd_cap_alarm", VAR_UINT16 | MASTER_VALUE, .config.minmaxUnsigned = { 0, 20000 }, PG_OSD_CONFIG, offsetof(osdConfig_t, cap_alarm) }, { "osd_alt_alarm", VAR_UINT16 | MASTER_VALUE, .config.minmaxUnsigned = { 0, 10000 }, PG_OSD_CONFIG, offsetof(osdConfig_t, alt_alarm) }, @@ -1181,6 +1184,9 @@ const clivalue_t valueTable[] = { { "osd_rssi_pos", VAR_UINT16 | MASTER_VALUE, .config.minmaxUnsigned = { 0, OSD_POSCFG_MAX }, PG_OSD_CONFIG, offsetof(osdConfig_t, item_pos[OSD_RSSI_VALUE]) }, #ifdef USE_RX_LINK_QUALITY_INFO { "osd_link_quality_pos", VAR_UINT16 | MASTER_VALUE, .config.minmaxUnsigned = { 0, OSD_POSCFG_MAX }, PG_OSD_CONFIG, offsetof(osdConfig_t, item_pos[OSD_LINK_QUALITY]) }, +#endif +#ifdef USE_RX_RSSI_DBM + { "osd_rssi_dbm_pos", VAR_UINT8 | MASTER_VALUE, .config.minmaxUnsigned = { 0, OSD_POSCFG_MAX }, PG_OSD_CONFIG, offsetof(osdConfig_t, item_pos[OSD_RSSI_DBM_VALUE]) }, #endif { "osd_tim_1_pos", VAR_UINT16 | MASTER_VALUE, .config.minmaxUnsigned = { 0, OSD_POSCFG_MAX }, PG_OSD_CONFIG, offsetof(osdConfig_t, item_pos[OSD_ITEM_TIMER_1]) }, { "osd_tim_2_pos", VAR_UINT16 | MASTER_VALUE, .config.minmaxUnsigned = { 0, OSD_POSCFG_MAX }, PG_OSD_CONFIG, offsetof(osdConfig_t, item_pos[OSD_ITEM_TIMER_2]) }, @@ -1280,6 +1286,9 @@ const clivalue_t valueTable[] = { { "osd_stat_total_time", VAR_UINT32 | MASTER_VALUE | MODE_BITSET, .config.bitpos = OSD_STAT_TOTAL_TIME, PG_OSD_CONFIG, offsetof(osdConfig_t, enabled_stats)}, { "osd_stat_total_dist", VAR_UINT32 | MASTER_VALUE | MODE_BITSET, .config.bitpos = OSD_STAT_TOTAL_DIST, PG_OSD_CONFIG, offsetof(osdConfig_t, enabled_stats)}, #endif +#ifdef USE_RX_RSSI_DBM + { "osd_stat_min_rssi_dbm", VAR_UINT32 | MASTER_VALUE | MODE_BITSET, .config.bitpos = OSD_STAT_MIN_RSSI_DBM, PG_OSD_CONFIG, offsetof(osdConfig_t, enabled_stats)}, +#endif #ifdef USE_OSD_PROFILES { "osd_profile", VAR_UINT8 | MASTER_VALUE, .config.minmaxUnsigned = { 1, OSD_PROFILE_COUNT }, PG_OSD_CONFIG, offsetof(osdConfig_t, osdProfileIndex) }, diff --git a/src/main/cms/cms.c b/src/main/cms/cms.c index 052e28a760..045f14776e 100644 --- a/src/main/cms/cms.c +++ b/src/main/cms/cms.c @@ -776,8 +776,9 @@ long cmsMenuExit(displayPort_t *pDisplay, const void *ptr) cmsTraverseGlobalExit(&menuMain); - if (currentCtx.menu->onExit) + if (currentCtx.menu->onExit) { currentCtx.menu->onExit((OSD_Entry *)NULL); // Forced exit + } if ((exitType == CMS_POPUP_SAVE) || (exitType == CMS_POPUP_SAVEREBOOT)) { // traverse through the menu stack and call their onExit functions @@ -800,7 +801,7 @@ long cmsMenuExit(displayPort_t *pDisplay, const void *ptr) displayRelease(pDisplay); currentCtx.menu = NULL; - if ((exitType == CMS_EXIT_SAVEREBOOT) || (exitType == CMS_POPUP_SAVEREBOOT)) { + if ((exitType == CMS_EXIT_SAVEREBOOT) || (exitType == CMS_POPUP_SAVEREBOOT) || (exitType == CMS_POPUP_EXITREBOOT)) { displayClearScreen(pDisplay); displayWrite(pDisplay, 5, 3, "REBOOTING..."); @@ -832,8 +833,9 @@ STATIC_UNIT_TESTED uint16_t cmsHandleKey(displayPort_t *pDisplay, cms_key_e key) uint16_t res = BUTTON_TIME; const OSD_Entry *p; - if (!currentCtx.menu) + if (!currentCtx.menu) { return res; + } if (key == CMS_KEY_MENU) { cmsMenuOpen(); @@ -851,7 +853,11 @@ STATIC_UNIT_TESTED uint16_t cmsHandleKey(displayPort_t *pDisplay, cms_key_e key) if (key == CMS_KEY_SAVEMENU) { osdElementEditing = false; - cmsMenuChange(pDisplay, &cmsx_menuSaveExit); + if (getRebootRequired()) { + cmsMenuChange(pDisplay, &cmsx_menuSaveExitReboot); + } else { + cmsMenuChange(pDisplay, &cmsx_menuSaveExit); + } return BUTTON_PAUSE; } @@ -868,8 +874,9 @@ STATIC_UNIT_TESTED uint16_t cmsHandleKey(displayPort_t *pDisplay, cms_key_e key) currentCtx.cursorRow--; // Skip non-title labels - if ((pageTop + currentCtx.cursorRow)->type == OME_Label && currentCtx.cursorRow > 0) + if ((pageTop + currentCtx.cursorRow)->type == OME_Label && currentCtx.cursorRow > 0) { currentCtx.cursorRow--; + } if (currentCtx.cursorRow == -1 || (pageTop + currentCtx.cursorRow)->type == OME_Label) { // Goto previous page @@ -878,8 +885,9 @@ STATIC_UNIT_TESTED uint16_t cmsHandleKey(displayPort_t *pDisplay, cms_key_e key) } } - if ((key == CMS_KEY_DOWN || key == CMS_KEY_UP) && (!osdElementEditing)) + if ((key == CMS_KEY_DOWN || key == CMS_KEY_UP) && (!osdElementEditing)) { return res; + } p = pageTop + currentCtx.cursorRow; @@ -895,8 +903,9 @@ STATIC_UNIT_TESTED uint16_t cmsHandleKey(displayPort_t *pDisplay, cms_key_e key) long retval; if (p->func && key == CMS_KEY_RIGHT) { retval = p->func(pDisplay, p->data); - if (retval == MENU_CHAIN_BACK) + if (retval == MENU_CHAIN_BACK) { cmsMenuBack(pDisplay); + } res = BUTTON_PAUSE; } break; @@ -917,11 +926,12 @@ STATIC_UNIT_TESTED uint16_t cmsHandleKey(displayPort_t *pDisplay, cms_key_e key) case OME_Bool: if (p->data) { uint8_t *val = p->data; - if (key == CMS_KEY_RIGHT) - *val = 1; - else - *val = 0; + const uint8_t previousValue = *val; + *val = (key == CMS_KEY_RIGHT) ? 1 : 0; SET_PRINTVALUE(runtimeEntryFlags[currentCtx.cursorRow]); + if ((p->flags & REBOOT_REQUIRED) && (*val != previousValue)) { + setRebootRequired(); + } } break; @@ -929,6 +939,7 @@ STATIC_UNIT_TESTED uint16_t cmsHandleKey(displayPort_t *pDisplay, cms_key_e key) case OME_VISIBLE: if (p->data) { uint16_t *val = (uint16_t *)p->data; + const uint16_t previousValue = *val; if ((key == CMS_KEY_RIGHT) && (!osdElementEditing)) { osdElementEditing = true; osdProfileCursor = 1; @@ -953,6 +964,9 @@ STATIC_UNIT_TESTED uint16_t cmsHandleKey(displayPort_t *pDisplay, cms_key_e key) } } SET_PRINTVALUE(runtimeEntryFlags[currentCtx.cursorRow]); + if ((p->flags & REBOOT_REQUIRED) && (*val != previousValue)) { + setRebootRequired(); + } } break; #endif @@ -961,15 +975,21 @@ STATIC_UNIT_TESTED uint16_t cmsHandleKey(displayPort_t *pDisplay, cms_key_e key) case OME_FLOAT: if (p->data) { OSD_UINT8_t *ptr = p->data; + const uint16_t previousValue = *ptr->val; if (key == CMS_KEY_RIGHT) { - if (*ptr->val < ptr->max) + if (*ptr->val < ptr->max) { *ptr->val += ptr->step; + } } else { - if (*ptr->val > ptr->min) + if (*ptr->val > ptr->min) { *ptr->val -= ptr->step; + } } SET_PRINTVALUE(runtimeEntryFlags[currentCtx.cursorRow]); + if ((p->flags & REBOOT_REQUIRED) && (*ptr->val != previousValue)) { + setRebootRequired(); + } if (p->func) { p->func(pDisplay, p); } @@ -979,33 +999,44 @@ STATIC_UNIT_TESTED uint16_t cmsHandleKey(displayPort_t *pDisplay, cms_key_e key) case OME_TAB: if (p->type == OME_TAB) { OSD_TAB_t *ptr = p->data; + const uint8_t previousValue = *ptr->val; if (key == CMS_KEY_RIGHT) { - if (*ptr->val < ptr->max) + if (*ptr->val < ptr->max) { *ptr->val += 1; - } - else { - if (*ptr->val > 0) + } + } else { + if (*ptr->val > 0) { *ptr->val -= 1; + } } - if (p->func) + if (p->func) { p->func(pDisplay, p->data); + } SET_PRINTVALUE(runtimeEntryFlags[currentCtx.cursorRow]); + if ((p->flags & REBOOT_REQUIRED) && (*ptr->val != previousValue)) { + setRebootRequired(); + } } break; case OME_INT8: if (p->data) { OSD_INT8_t *ptr = p->data; + const int8_t previousValue = *ptr->val; if (key == CMS_KEY_RIGHT) { - if (*ptr->val < ptr->max) + if (*ptr->val < ptr->max) { *ptr->val += ptr->step; - } - else { - if (*ptr->val > ptr->min) + } + } else { + if (*ptr->val > ptr->min) { *ptr->val -= ptr->step; + } } SET_PRINTVALUE(runtimeEntryFlags[currentCtx.cursorRow]); + if ((p->flags & REBOOT_REQUIRED) && (*ptr->val != previousValue)) { + setRebootRequired(); + } if (p->func) { p->func(pDisplay, p); } @@ -1015,15 +1046,20 @@ STATIC_UNIT_TESTED uint16_t cmsHandleKey(displayPort_t *pDisplay, cms_key_e key) case OME_UINT16: if (p->data) { OSD_UINT16_t *ptr = p->data; + const uint16_t previousValue = *ptr->val; if (key == CMS_KEY_RIGHT) { - if (*ptr->val < ptr->max) + if (*ptr->val < ptr->max) { *ptr->val += ptr->step; - } - else { - if (*ptr->val > ptr->min) + } + } else { + if (*ptr->val > ptr->min) { *ptr->val -= ptr->step; + } } SET_PRINTVALUE(runtimeEntryFlags[currentCtx.cursorRow]); + if ((p->flags & REBOOT_REQUIRED) && (*ptr->val != previousValue)) { + setRebootRequired(); + } if (p->func) { p->func(pDisplay, p); } @@ -1033,15 +1069,20 @@ STATIC_UNIT_TESTED uint16_t cmsHandleKey(displayPort_t *pDisplay, cms_key_e key) case OME_INT16: if (p->data) { OSD_INT16_t *ptr = p->data; + const int16_t previousValue = *ptr->val; if (key == CMS_KEY_RIGHT) { - if (*ptr->val < ptr->max) + if (*ptr->val < ptr->max) { *ptr->val += ptr->step; - } - else { - if (*ptr->val > ptr->min) + } + } else { + if (*ptr->val > ptr->min) { *ptr->val -= ptr->step; + } } SET_PRINTVALUE(runtimeEntryFlags[currentCtx.cursorRow]); + if ((p->flags & REBOOT_REQUIRED) && (*ptr->val != previousValue)) { + setRebootRequired(); + } if (p->func) { p->func(pDisplay, p); } diff --git a/src/main/cms/cms.h b/src/main/cms/cms.h index 39d290f619..aea6b1261b 100644 --- a/src/main/cms/cms.h +++ b/src/main/cms/cms.h @@ -62,4 +62,5 @@ void cmsSetExternKey(cms_key_e extKey); #define CMS_EXIT_SAVEREBOOT (2) #define CMS_POPUP_SAVE (3) #define CMS_POPUP_SAVEREBOOT (4) +#define CMS_POPUP_EXITREBOOT (5) diff --git a/src/main/cms/cms_menu_blackbox.c b/src/main/cms/cms_menu_blackbox.c index 18b4a72a73..66235e8a04 100644 --- a/src/main/cms/cms_menu_blackbox.c +++ b/src/main/cms/cms_menu_blackbox.c @@ -200,11 +200,11 @@ static long cmsx_Blackbox_onExit(const OSD_Entry *self) static const OSD_Entry cmsx_menuBlackboxEntries[] = { { "-- BLACKBOX --", OME_Label, NULL, NULL, 0}, - { "DEVICE", OME_TAB, NULL, &cmsx_BlackboxDeviceTable, 0 }, + { "DEVICE", OME_TAB, NULL, &cmsx_BlackboxDeviceTable, REBOOT_REQUIRED }, { "(STATUS)", OME_String, NULL, &cmsx_BlackboxStatus, 0 }, { "(USED)", OME_String, NULL, &cmsx_BlackboxDeviceStorageUsed, 0 }, { "(FREE)", OME_String, NULL, &cmsx_BlackboxDeviceStorageFree, 0 }, - { "P RATIO", OME_UINT16, NULL, &(OSD_UINT16_t){ &blackboxConfig_p_ratio, 1, INT16_MAX, 1 },0 }, + { "P RATIO", OME_UINT16, NULL, &(OSD_UINT16_t){ &blackboxConfig_p_ratio, 1, INT16_MAX, 1 }, REBOOT_REQUIRED }, #ifdef USE_FLASHFS { "ERASE FLASH", OME_Funcall, cmsx_EraseFlash, NULL, 0 }, diff --git a/src/main/cms/cms_menu_builtin.c b/src/main/cms/cms_menu_builtin.c index 4eb7cf1370..db9aa01632 100644 --- a/src/main/cms/cms_menu_builtin.c +++ b/src/main/cms/cms_menu_builtin.c @@ -40,11 +40,12 @@ #include "cms/cms_menu_imu.h" #include "cms/cms_menu_blackbox.h" -#include "cms/cms_menu_osd.h" +#include "cms/cms_menu_failsafe.h" #include "cms/cms_menu_ledstrip.h" #include "cms/cms_menu_misc.h" +#include "cms/cms_menu_osd.h" #include "cms/cms_menu_power.h" -#include "cms/cms_menu_failsafe.h" +#include "cms/cms_menu_saveexit.h" // VTX supplied menus @@ -54,6 +55,8 @@ #include "drivers/system.h" +#include "fc/config.h" + #include "msp/msp_protocol.h" // XXX for FC identification... not available elsewhere #include "cms_menu_builtin.h" @@ -139,6 +142,18 @@ static CMS_Menu menuFeatures = { .entries = menuFeaturesEntries, }; +static long cmsx_SaveExitMenu(displayPort_t *pDisplay, const void *ptr) +{ + UNUSED(ptr); + + if (getRebootRequired()) { + cmsMenuChange(pDisplay, &cmsx_menuSaveExitReboot); + } else { + cmsMenuChange(pDisplay, &cmsx_menuSaveExit); + } + return 0; +} + // Main static const OSD_Entry menuMainEntries[] = @@ -152,9 +167,7 @@ static const OSD_Entry menuMainEntries[] = #endif {"FC&FW INFO", OME_Submenu, cmsMenuChange, &menuInfo, 0}, {"MISC", OME_Submenu, cmsMenuChange, &cmsx_menuMisc, 0}, - {"EXIT", OME_OSD_Exit, cmsMenuExit, (void *)CMS_EXIT, 0}, - {"SAVE&EXIT", OME_OSD_Exit, cmsMenuExit, (void *)CMS_EXIT_SAVE, 0}, - {"SAVE&REBOOT", OME_OSD_Exit, cmsMenuExit, (void *)CMS_EXIT_SAVEREBOOT, 0}, + {"SAVE/EXIT", OME_Funcall, cmsx_SaveExitMenu, NULL, 0}, #ifdef CMS_MENU_DEBUG {"ERR SAMPLE", OME_Submenu, cmsMenuChange, &menuInfoEntries[0], 0}, #endif diff --git a/src/main/cms/cms_menu_misc.c b/src/main/cms/cms_menu_misc.c index debe25cdb4..fce15b5931 100644 --- a/src/main/cms/cms_menu_misc.c +++ b/src/main/cms/cms_menu_misc.c @@ -123,8 +123,8 @@ static const OSD_Entry menuMiscEntries[]= { { "-- MISC --", OME_Label, NULL, NULL, 0 }, - { "MIN THR", OME_UINT16, NULL, &(OSD_UINT16_t){ &motorConfig_minthrottle, 1000, 2000, 1 }, 0 }, - { "DIGITAL IDLE", OME_UINT8, NULL, &(OSD_UINT8_t) { &motorConfig_digitalIdleOffsetValue, 0, 200, 1 }, 0 }, + { "MIN THR", OME_UINT16, NULL, &(OSD_UINT16_t){ &motorConfig_minthrottle, 1000, 2000, 1 }, REBOOT_REQUIRED }, + { "DIGITAL IDLE", OME_UINT8, NULL, &(OSD_UINT8_t) { &motorConfig_digitalIdleOffsetValue, 0, 200, 1 }, REBOOT_REQUIRED }, { "DEBUG MODE", OME_TAB, NULL, &(OSD_TAB_t) { &systemConfig_debug_mode, DEBUG_COUNT - 1, debugModeNames }, 0 }, { "RC PREV", OME_Submenu, cmsMenuChange, &cmsx_menuRcPreview, 0}, diff --git a/src/main/cms/cms_menu_osd.c b/src/main/cms/cms_menu_osd.c index ae3604945a..24f11b4861 100644 --- a/src/main/cms/cms_menu_osd.c +++ b/src/main/cms/cms_menu_osd.c @@ -67,6 +67,9 @@ const OSD_Entry menuOsdActiveElemsEntries[] = { {"--- ACTIV ELEM ---", OME_Label, NULL, NULL, 0}, {"RSSI", OME_VISIBLE, NULL, &osdConfig_item_pos[OSD_RSSI_VALUE], DYNAMIC}, +#ifdef USE_RX_RSSI_DBM + {"RSSI DBM", OME_VISIBLE, NULL, &osdConfig_item_pos[OSD_RSSI_DBM_VALUE], DYNAMIC}, +#endif {"BATTERY VOLTAGE", OME_VISIBLE, NULL, &osdConfig_item_pos[OSD_MAIN_BATT_VOLTAGE], DYNAMIC}, {"BATTERY USAGE", OME_VISIBLE, NULL, &osdConfig_item_pos[OSD_MAIN_BATT_USAGE], DYNAMIC}, {"AVG CELL VOLTAGE", OME_VISIBLE, NULL, &osdConfig_item_pos[OSD_AVG_CELL_VOLTAGE], DYNAMIC}, @@ -160,6 +163,7 @@ CMS_Menu menuOsdActiveElems = { static uint8_t osdConfig_rssi_alarm; static uint16_t osdConfig_link_quality_alarm; +static uint8_t osdConfig_rssi_dbm_alarm; static uint16_t osdConfig_cap_alarm; static uint16_t osdConfig_alt_alarm; static uint8_t batteryConfig_vbatDurationForWarning; @@ -169,6 +173,7 @@ static long menuAlarmsOnEnter(void) { osdConfig_rssi_alarm = osdConfig()->rssi_alarm; osdConfig_link_quality_alarm = osdConfig()->link_quality_alarm; + osdConfig_rssi_dbm_alarm = osdConfig()->rssi_dbm_alarm; osdConfig_cap_alarm = osdConfig()->cap_alarm; osdConfig_alt_alarm = osdConfig()->alt_alarm; batteryConfig_vbatDurationForWarning = batteryConfig()->vbatDurationForWarning; @@ -183,6 +188,7 @@ static long menuAlarmsOnExit(const OSD_Entry *self) osdConfigMutable()->rssi_alarm = osdConfig_rssi_alarm; osdConfigMutable()->link_quality_alarm = osdConfig_link_quality_alarm; + osdConfigMutable()->rssi_dbm_alarm = osdConfig_rssi_dbm_alarm; osdConfigMutable()->cap_alarm = osdConfig_cap_alarm; osdConfigMutable()->alt_alarm = osdConfig_alt_alarm; batteryConfigMutable()->vbatDurationForWarning = batteryConfig_vbatDurationForWarning; @@ -196,6 +202,7 @@ const OSD_Entry menuAlarmsEntries[] = {"--- ALARMS ---", OME_Label, NULL, NULL, 0}, {"RSSI", OME_UINT8, NULL, &(OSD_UINT8_t){&osdConfig_rssi_alarm, 5, 90, 5}, 0}, {"LINK QUALITY", OME_UINT16, NULL, &(OSD_UINT16_t){&osdConfig_link_quality_alarm, 5, 300, 5}, 0}, + {"RSSI DBM", OME_UINT8, NULL, &(OSD_UINT8_t){&osdConfig_rssi_dbm_alarm, 5, 130, 5}, 0}, {"MAIN BAT", OME_UINT16, NULL, &(OSD_UINT16_t){&osdConfig_cap_alarm, 50, 30000, 50}, 0}, {"MAX ALT", OME_UINT16, NULL, &(OSD_UINT16_t){&osdConfig_alt_alarm, 1, 200, 1}, 0}, {"VBAT WARN DUR", OME_UINT8, NULL, &(OSD_UINT8_t){ &batteryConfig_vbatDurationForWarning, 0, 200, 1 }, 0 }, diff --git a/src/main/cms/cms_menu_saveexit.c b/src/main/cms/cms_menu_saveexit.c index 7777d7d5d7..f8b860f375 100644 --- a/src/main/cms/cms_menu_saveexit.c +++ b/src/main/cms/cms_menu_saveexit.c @@ -37,9 +37,9 @@ static const OSD_Entry cmsx_menuSaveExitEntries[] = { { "-- SAVE/EXIT --", OME_Label, NULL, NULL, 0}, - {"EXIT", OME_OSD_Exit, cmsMenuExit, (void *)CMS_EXIT, 0}, - {"SAVE&EXIT", OME_OSD_Exit, cmsMenuExit, (void *)CMS_POPUP_SAVE, 0}, - {"SAVE&REBOOT", OME_OSD_Exit, cmsMenuExit, (void *)CMS_POPUP_SAVEREBOOT, 0}, + { "EXIT", OME_OSD_Exit, cmsMenuExit, (void *)CMS_EXIT, 0}, + { "SAVE&EXIT", OME_OSD_Exit, cmsMenuExit, (void *)CMS_POPUP_SAVE, 0}, + { "SAVE&REBOOT", OME_OSD_Exit, cmsMenuExit, (void *)CMS_POPUP_SAVEREBOOT, 0}, { "BACK", OME_Back, NULL, NULL, 0 }, { NULL, OME_END, NULL, NULL, 0 } }; @@ -52,4 +52,22 @@ CMS_Menu cmsx_menuSaveExit = { .entries = cmsx_menuSaveExitEntries }; +static const OSD_Entry cmsx_menuSaveExitRebootEntries[] = +{ + { "-- SAVE/EXIT (REBOOT REQD)", OME_Label, NULL, NULL, 0}, + { "EXIT&REBOOT", OME_OSD_Exit, cmsMenuExit, (void *)CMS_POPUP_EXITREBOOT, 0}, + { "SAVE&REBOOT", OME_OSD_Exit, cmsMenuExit, (void *)CMS_POPUP_SAVEREBOOT, 0}, + { "BACK", OME_Back, NULL, NULL, 0 }, + { NULL, OME_END, NULL, NULL, 0 } +}; + +CMS_Menu cmsx_menuSaveExitReboot = { +#ifdef CMS_MENU_DEBUG + .GUARD_text = "MENUSAVE", + .GUARD_type = OME_MENU, +#endif + .entries = cmsx_menuSaveExitRebootEntries +}; + + #endif diff --git a/src/main/cms/cms_menu_saveexit.h b/src/main/cms/cms_menu_saveexit.h index 48dec53083..24de8e7d89 100644 --- a/src/main/cms/cms_menu_saveexit.h +++ b/src/main/cms/cms_menu_saveexit.h @@ -21,3 +21,4 @@ #pragma once extern CMS_Menu cmsx_menuSaveExit; +extern CMS_Menu cmsx_menuSaveExitReboot; diff --git a/src/main/cms/cms_types.h b/src/main/cms/cms_types.h index dc5745fcc2..1e6b8e06ca 100644 --- a/src/main/cms/cms_types.h +++ b/src/main/cms/cms_types.h @@ -70,6 +70,7 @@ typedef struct #define PRINT_LABEL 0x02 // Text label should be printed #define DYNAMIC 0x04 // Value should be updated dynamically #define OPTSTRING 0x08 // (Temporary) Flag for OME_Submenu, indicating func should be called to get a string to display. +#define REBOOT_REQUIRED 0x10 // Reboot is required if the value is changed #define IS_PRINTVALUE(x) ((x) & PRINT_VALUE) #define SET_PRINTVALUE(x) do { (x) |= PRINT_VALUE; } while (0) diff --git a/src/main/drivers/system_stm32h7xx.c b/src/main/drivers/system_stm32h7xx.c new file mode 100644 index 0000000000..108f200439 --- /dev/null +++ b/src/main/drivers/system_stm32h7xx.c @@ -0,0 +1,312 @@ +/* + * This file is part of Cleanflight. + * + * Cleanflight is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * Cleanflight is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with Cleanflight. If not, see . + */ + +#include +#include +#include +#include + +#include "platform.h" + +#include "drivers/accgyro/accgyro_mpu.h" +#include "drivers/exti.h" +#include "drivers/nvic.h" +#include "drivers/persistent.h" +#include "drivers/system.h" + + +void SystemClock_Config(void); + + +void enablePeripherialClocks(void) +{ + __HAL_RCC_MDMA_CLK_ENABLE(); + __HAL_RCC_QSPI_CLK_ENABLE(); + + // AHB1 + __HAL_RCC_DMA1_CLK_ENABLE(); + __HAL_RCC_DMA2_CLK_ENABLE(); + __HAL_RCC_ADC12_CLK_ENABLE(); + // USB clock will be enabled by vcpXXX/usbd_conf.c + // Note that enabling both ULPI and non-ULPI does not work. + + // AHB2 + __HAL_RCC_D2SRAM1_CLK_ENABLE(); + __HAL_RCC_D2SRAM2_CLK_ENABLE(); + __HAL_RCC_D2SRAM3_CLK_ENABLE(); + + // AHB4 + __HAL_RCC_GPIOA_CLK_ENABLE(); + __HAL_RCC_GPIOB_CLK_ENABLE(); + __HAL_RCC_GPIOC_CLK_ENABLE(); + __HAL_RCC_GPIOD_CLK_ENABLE(); + __HAL_RCC_GPIOE_CLK_ENABLE(); + __HAL_RCC_GPIOF_CLK_ENABLE(); + __HAL_RCC_GPIOG_CLK_ENABLE(); + __HAL_RCC_GPIOH_CLK_ENABLE(); + __HAL_RCC_GPIOI_CLK_ENABLE(); + __HAL_RCC_GPIOJ_CLK_ENABLE(); + __HAL_RCC_GPIOK_CLK_ENABLE(); + __HAL_RCC_BDMA_CLK_ENABLE(); + __HAL_RCC_ADC3_CLK_ENABLE(); + + // APB3 + + // APB1 + __HAL_RCC_TIM2_CLK_ENABLE(); + __HAL_RCC_TIM3_CLK_ENABLE(); + __HAL_RCC_TIM4_CLK_ENABLE(); + __HAL_RCC_TIM5_CLK_ENABLE(); + __HAL_RCC_TIM6_CLK_ENABLE(); + __HAL_RCC_TIM7_CLK_ENABLE(); + __HAL_RCC_TIM12_CLK_ENABLE(); + __HAL_RCC_TIM13_CLK_ENABLE(); + __HAL_RCC_TIM14_CLK_ENABLE(); + __HAL_RCC_LPTIM1_CLK_ENABLE(); + __HAL_RCC_SPI2_CLK_ENABLE(); + __HAL_RCC_SPI3_CLK_ENABLE(); + __HAL_RCC_USART2_CLK_ENABLE(); + __HAL_RCC_USART3_CLK_ENABLE(); + __HAL_RCC_UART4_CLK_ENABLE(); + __HAL_RCC_UART5_CLK_ENABLE(); + __HAL_RCC_I2C1_CLK_ENABLE(); + __HAL_RCC_I2C2_CLK_ENABLE(); + __HAL_RCC_I2C3_CLK_ENABLE(); + __HAL_RCC_DAC12_CLK_ENABLE(); + __HAL_RCC_UART7_CLK_ENABLE(); + __HAL_RCC_UART8_CLK_ENABLE(); + __HAL_RCC_CRS_CLK_ENABLE(); + + // APB2 + __HAL_RCC_TIM1_CLK_ENABLE(); + __HAL_RCC_TIM8_CLK_ENABLE(); + __HAL_RCC_USART1_CLK_ENABLE(); + __HAL_RCC_USART6_CLK_ENABLE(); + __HAL_RCC_SPI1_CLK_ENABLE(); + __HAL_RCC_SPI4_CLK_ENABLE(); + __HAL_RCC_TIM15_CLK_ENABLE(); + __HAL_RCC_TIM16_CLK_ENABLE(); + __HAL_RCC_TIM17_CLK_ENABLE(); + __HAL_RCC_SPI5_CLK_ENABLE(); + + // APB4 + __HAL_RCC_SYSCFG_CLK_ENABLE(); + __HAL_RCC_LPUART1_CLK_ENABLE(); + __HAL_RCC_SPI6_CLK_ENABLE(); + __HAL_RCC_I2C4_CLK_ENABLE(); + __HAL_RCC_LPTIM2_CLK_ENABLE(); + __HAL_RCC_LPTIM3_CLK_ENABLE(); + __HAL_RCC_LPTIM4_CLK_ENABLE(); + __HAL_RCC_LPTIM5_CLK_ENABLE(); + __HAL_RCC_COMP12_CLK_ENABLE(); + __HAL_RCC_VREF_CLK_ENABLE(); +} + +void enableGPIOPowerUsageAndNoiseReductions(void) +{ + // GPIO initialization, copied from drivers/system_stm32f7xx.c + // ... It was commented out. + // Where does F7 initializes the GPIO pins? It doesn't do it at all??? + +// +// GPIO_InitTypeDef GPIO_InitStructure; +// GPIO_StructInit(&GPIO_InitStructure); +// GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_UP; // default is un-pulled input +// +// GPIO_InitStructure.GPIO_Pin = GPIO_Pin_All; +// GPIO_InitStructure.GPIO_Pin &= ~(GPIO_Pin_11 | GPIO_Pin_12); // leave USB D+/D- alone +// +// GPIO_InitStructure.GPIO_Pin &= ~(GPIO_Pin_13 | GPIO_Pin_14); // leave JTAG pins alone +// GPIO_Init(GPIOA, &GPIO_InitStructure); +// +// GPIO_InitStructure.GPIO_Pin = GPIO_Pin_All; +// GPIO_Init(GPIOB, &GPIO_InitStructure); +// +// GPIO_InitStructure.GPIO_Pin = GPIO_Pin_All; +// GPIO_Init(GPIOC, &GPIO_InitStructure); +// GPIO_Init(GPIOD, &GPIO_InitStructure); +// GPIO_Init(GPIOE, &GPIO_InitStructure); + +} + +void configureMasterClockOutputs(void) +{ + // Initialize pins for MCO1 and MCO2 for clock testing/verification + + GPIO_InitTypeDef GPIO_InitStruct; + + GPIO_InitStruct.Pin = GPIO_PIN_8; + GPIO_InitStruct.Mode = GPIO_MODE_AF_PP; + GPIO_InitStruct.Pull = GPIO_NOPULL; + GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_VERY_HIGH; + GPIO_InitStruct.Alternate = GPIO_AF0_MCO; + + HAL_GPIO_Init(GPIOA, &GPIO_InitStruct); + + GPIO_InitStruct.Pin = GPIO_PIN_9; + GPIO_InitStruct.Mode = GPIO_MODE_AF_PP; + GPIO_InitStruct.Pull = GPIO_NOPULL; + GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_VERY_HIGH; + GPIO_InitStruct.Alternate = GPIO_AF0_MCO; + + HAL_GPIO_Init(GPIOC, &GPIO_InitStruct); +} + +bool isMPUSoftReset(void) +{ + if (cachedRccCsrValue & RCC_RSR_SFTRSTF) + return true; + else + return false; +} + +void systemInit(void) +{ +#ifdef USE_ITCM_RAM + // Mark ITCM-RAM as read-only + HAL_MPU_Disable(); + + // "For Cortex®-M7, TCMs memories always behave as Non-cacheable, Non-shared normal memories, irrespectiveof the memory type attributes defined in the MPU for a memory region containing addresses held in the TCM" + // See AN4838 + + MPU_Region_InitTypeDef MPU_InitStruct; + MPU_InitStruct.Enable = MPU_REGION_ENABLE; + MPU_InitStruct.BaseAddress = 0x00000000; + MPU_InitStruct.Size = MPU_REGION_SIZE_64KB; + MPU_InitStruct.AccessPermission = MPU_REGION_PRIV_RO_URO; + MPU_InitStruct.IsBufferable = MPU_ACCESS_BUFFERABLE; + MPU_InitStruct.IsCacheable = MPU_ACCESS_NOT_CACHEABLE; + MPU_InitStruct.IsShareable = MPU_ACCESS_NOT_SHAREABLE; + MPU_InitStruct.Number = MPU_REGION_NUMBER0; + MPU_InitStruct.TypeExtField = MPU_TEX_LEVEL0; + MPU_InitStruct.SubRegionDisable = 0x00; + MPU_InitStruct.DisableExec = MPU_INSTRUCTION_ACCESS_ENABLE; + HAL_MPU_ConfigRegion(&MPU_InitStruct); + + HAL_MPU_Enable(MPU_PRIVILEGED_DEFAULT); +#endif + + + // Configure NVIC preempt/priority groups + HAL_NVIC_SetPriorityGrouping(NVIC_PRIORITY_GROUPING); + + // cache RCC->RSR value to use it in isMPUSoftReset() and others + cachedRccCsrValue = RCC->RSR; + + /* Accounts for OP Bootloader, set the Vector Table base address as specified in .ld file */ + //extern void *isr_vector_table_base; + //NVIC_SetVectorTable((uint32_t)&isr_vector_table_base, 0x0); + //__HAL_RCC_USB_OTG_FS_CLK_DISABLE; + + //RCC_ClearFlag(); + + enablePeripherialClocks(); + + enableGPIOPowerUsageAndNoiseReductions(); + +#ifdef USE_MCO_OUTPUTS + configureMasterClockOutputs(); +#endif + + // Init cycle counter + cycleCounterInit(); + + // SysTick is updated whenever HAL_RCC_ClockConfig is called. +} + +void systemReset(void) +{ +#if 0 +#ifdef USE_GYRO + if (mpuResetFn) { + mpuResetFn(); + } +#endif +#endif + + SCB_DisableDCache(); + SCB_DisableICache(); + + __disable_irq(); + NVIC_SystemReset(); +} + +void forcedSystemResetWithoutDisablingCaches(void) +{ + persistentObjectWrite(PERSISTENT_OBJECT_RESET_REASON, RESET_FORCED); + + __disable_irq(); + NVIC_SystemReset(); +} + +void systemResetToBootloader(void) +{ +#if 0 +#ifdef USE_GYRO + if (mpuResetFn) { + mpuResetFn(); + } +#endif +#endif + persistentObjectWrite(PERSISTENT_OBJECT_RESET_REASON, RESET_BOOTLOADER_REQUEST); + __disable_irq(); + NVIC_SystemReset(); +} + +static uint32_t bootloaderRequest; + +bool systemIsFlashBootloaderRequested(void) +{ + return (bootloaderRequest == RESET_FLASH_BOOTLOADER_REQUEST); +} + +void systemCheckResetReason(void) +{ + bootloaderRequest = persistentObjectRead(PERSISTENT_OBJECT_RESET_REASON); + + switch (bootloaderRequest) { + case RESET_BOOTLOADER_REQUEST: + persistentObjectWrite(PERSISTENT_OBJECT_RESET_REASON, RESET_BOOTLOADER_POST); + break; + + case RESET_FORCED: + persistentObjectWrite(PERSISTENT_OBJECT_RESET_REASON, RESET_NONE); + return; + + case RESET_NONE: + if (!(RCC->RSR & RCC_RSR_SFTRSTF)) { + // Direct hard reset case + return; + } + // Soft reset; boot loader may have been active with BOOT pin pulled high. + FALLTHROUGH; + + case RESET_BOOTLOADER_POST: + // Boot loader activity magically prevents SysTick from interrupting. + // Issue a soft reset to prevent the condition. + forcedSystemResetWithoutDisablingCaches(); // observed that disabling dcache after cold boot with BOOT pin high causes segfault. + } + + void (*SysMemBootJump)(void); + __SYSCFG_CLK_ENABLE(); + + uint32_t p = (*((uint32_t *) 0x1ff09800)); + __set_MSP(p); //Set the main stack pointer to its defualt values + SysMemBootJump = (void (*)(void)) (*((uint32_t *) 0x1ff09804)); // Point the PC to the System Memory reset vector (+4) + SysMemBootJump(); + while (1); +} diff --git a/src/main/osd/osd.c b/src/main/osd/osd.c index 153319130e..6bd2d13467 100644 --- a/src/main/osd/osd.c +++ b/src/main/osd/osd.c @@ -244,6 +244,7 @@ void pgResetFn_osdConfig(osdConfig_t *osdConfig) // turn off RSSI & Link Quality warnings by default osdWarnSetState(OSD_WARNING_RSSI, false); osdWarnSetState(OSD_WARNING_LINK_QUALITY, false); + osdWarnSetState(OSD_WARNING_RSSI_DBM, false); osdConfig->timers[OSD_TIMER_1] = osdTimerDefault[OSD_TIMER_1]; osdConfig->timers[OSD_TIMER_2] = osdTimerDefault[OSD_TIMER_2]; @@ -264,10 +265,10 @@ void pgResetFn_osdConfig(osdConfig_t *osdConfig) osdConfig->osdProfileIndex = 1; osdConfig->ahInvert = false; - for (int i=0; i < OSD_PROFILE_COUNT; i++) { osdConfig->profile[i][0] = '\0'; } + osdConfig->rssi_dbm_alarm = 60; } static void osdDrawLogo(int x, int y) @@ -346,6 +347,7 @@ static void osdResetStats(void) stats.max_esc_temp = 0; stats.max_esc_rpm = 0; stats.min_link_quality = (linkQualitySource == LQ_SOURCE_RX_PROTOCOL_CRSF) ? 300 : 99; // CRSF : percent + stats.min_rssi_dbm = 0; } static void osdUpdateStats(void) @@ -392,6 +394,13 @@ static void osdUpdateStats(void) } #endif +#ifdef USE_RX_RSSI_DBM + value = getRssiDbm(); + if (stats.min_rssi_dbm < value) { + stats.min_rssi_dbm = value; + } +#endif + #ifdef USE_GPS if (STATE(GPS_FIX) && STATE(GPS_FIX_HOME)) { value = GPS_distanceToHome; @@ -635,6 +644,13 @@ static uint8_t osdShowStats(uint16_t endBatteryVoltage, int statsRowCount) } #endif +#ifdef USE_RX_RSSI_DBM + if (osdStatGetState(OSD_STAT_MIN_RSSI_DBM)) { + tfp_sprintf(buff, "%3d", stats.min_rssi_dbm * -1); + osdDisplayStatisticLabel(top++, "MIN RSSI DBM", buff); + } +#endif + #ifdef USE_PERSISTENT_STATS if (osdStatGetState(OSD_STAT_TOTAL_FLIGHTS)) { itoa(statsConfig()->stats_total_flights, buff, 10); diff --git a/src/main/osd/osd.h b/src/main/osd/osd.h index 8b2112ef7a..df4f549ff1 100644 --- a/src/main/osd/osd.h +++ b/src/main/osd/osd.h @@ -131,6 +131,7 @@ typedef enum { OSD_RATE_PROFILE_NAME, OSD_PID_PROFILE_NAME, OSD_PROFILE_NAME, + OSD_RSSI_DBM_VALUE, OSD_ITEM_COUNT // MUST BE LAST } osd_items_e; @@ -167,6 +168,7 @@ typedef enum { OSD_STAT_TOTAL_FLIGHTS, OSD_STAT_TOTAL_TIME, OSD_STAT_TOTAL_DIST, + OSD_STAT_MIN_RSSI_DBM, OSD_STAT_COUNT // MUST BE LAST } osd_stats_e; @@ -215,6 +217,7 @@ typedef enum { OSD_WARNING_GPS_RESCUE_DISABLED, OSD_WARNING_RSSI, OSD_WARNING_LINK_QUALITY, + OSD_WARNING_RSSI_DBM, OSD_WARNING_COUNT // MUST BE LAST } osdWarningsFlags_e; @@ -254,6 +257,7 @@ typedef struct osdConfig_s { uint8_t overlay_radio_mode; char profile[OSD_PROFILE_COUNT][OSD_PROFILE_NAME_LENGTH + 1]; uint16_t link_quality_alarm; + uint8_t rssi_dbm_alarm; } osdConfig_t; PG_DECLARE(osdConfig_t, osdConfig); @@ -270,6 +274,7 @@ typedef struct statistic_s { int16_t max_esc_temp; int32_t max_esc_rpm; uint16_t min_link_quality; + uint8_t min_rssi_dbm; } statistic_t; extern timeUs_t resumeRefreshAt; diff --git a/src/main/osd/osd_elements.c b/src/main/osd/osd_elements.c index a479a6b0fb..9011f2c533 100644 --- a/src/main/osd/osd_elements.c +++ b/src/main/osd/osd_elements.c @@ -1026,6 +1026,13 @@ static void osdElementRtcTime(osdElementParms_t *element) } #endif // USE_RTC_TIME +#ifdef USE_RX_RSSI_DBM +static void osdElementRssiDbm(osdElementParms_t *element) +{ + tfp_sprintf(element->buff, "%c%3d", SYM_RSSI, getRssiDbm() * -1); +} +#endif // USE_RX_RSSI_DBM + #ifdef USE_OSD_STICK_OVERLAY static void osdElementStickOverlay(osdElementParms_t *element) { @@ -1193,6 +1200,14 @@ static void osdElementWarnings(osdElementParms_t *element) SET_BLINK(OSD_WARNINGS); return; } +#ifdef USE_RX_RSSI_DBM + // rssi dbm + if (osdWarnGetState(OSD_WARNING_RSSI_DBM) && (getRssiDbm() > osdConfig()->rssi_dbm_alarm)) { + osdFormatMessage(element->buff, OSD_FORMAT_MESSAGE_BUFFER_SIZE, "RSSI DBM"); + SET_BLINK(OSD_WARNINGS); + return; + } +#endif // USE_RX_RSSI_DBM #ifdef USE_RX_LINK_QUALITY_INFO // Link Quality @@ -1396,6 +1411,9 @@ static const uint8_t osdElementDisplayOrder[] = { #ifdef USE_RX_LINK_QUALITY_INFO OSD_LINK_QUALITY, #endif +#ifdef USE_RX_RSSI_DBM + OSD_RSSI_DBM_VALUE, +#endif #ifdef USE_OSD_STICK_OVERLAY OSD_STICK_OVERLAY_LEFT, OSD_STICK_OVERLAY_RIGHT, @@ -1510,6 +1528,9 @@ const osdElementDrawFn osdElementDrawFunction[OSD_ITEM_COUNT] = { #ifdef USE_OSD_PROFILES [OSD_PROFILE_NAME] = osdElementOsdProfileName, #endif +#ifdef USE_RX_RSSI_DBM + [OSD_RSSI_DBM_VALUE] = osdElementRssiDbm, +#endif }; static void osdAddActiveElement(osd_items_e element) diff --git a/src/main/platform.h b/src/main/platform.h index fc83953e8e..1a1989f692 100644 --- a/src/main/platform.h +++ b/src/main/platform.h @@ -26,7 +26,21 @@ #pragma GCC poison sprintf snprintf #endif -#if defined(STM32F722xx) || defined(STM32F745xx) || defined(STM32F746xx) || defined(STM32F765xx) +#if defined(STM32H743xx) || defined(STM32H750xx) +#include "stm32h7xx.h" +#include "stm32h7xx_hal.h" +#include "system_stm32h7xx.h" + +// Chip Unique ID on H7 +#define U_ID_0 (*(uint32_t*)0x1FF1E800) +#define U_ID_1 (*(uint32_t*)0x1FF1E804) +#define U_ID_2 (*(uint32_t*)0x1FF1E808) + +#ifndef STM32H7 +#define STM32H7 +#endif + +#elif defined(STM32F722xx) || defined(STM32F745xx) || defined(STM32F746xx) || defined(STM32F765xx) #include "stm32f7xx.h" #include "stm32f7xx_hal.h" #include "system_stm32f7xx.h" @@ -139,6 +153,12 @@ #elif defined(STM32F765xx) #define MCU_TYPE_ID 9 #define MCU_TYPE_NAME "F765" +#elif defined(STM32H750xx) +#define MCU_TYPE_ID 10 +#define MCU_TYPE_NAME "H750" +#elif defined(STM32H743xx) +#define MCU_TYPE_ID 11 +#define MCU_TYPE_NAME "H743" #else #define MCU_TYPE_ID 255 #define MCU_TYPE_NAME "Unknown MCU" diff --git a/src/main/rx/crsf.c b/src/main/rx/crsf.c index 2e2a912767..a9be3259ee 100644 --- a/src/main/rx/crsf.c +++ b/src/main/rx/crsf.c @@ -160,6 +160,9 @@ static void handleCrsfLinkStatisticsFrame(const crsfLinkStatistics_t* statsPtr, lastLinkStatisticsFrameUs = currentTimeUs; if (rssiSource == RSSI_SOURCE_RX_PROTOCOL_CRSF) { const uint8_t rssiDbm = stats.active_antenna ? stats.uplink_RSSI_2 : stats.uplink_RSSI_1; +#ifdef USE_RX_RSSI_DBM + setRssiDbm(rssiDbm, RSSI_SOURCE_RX_PROTOCOL_CRSF); +#endif const uint16_t rssiPercentScaled = scaleRange(rssiDbm, 130, 0, 0, RSSI_MAX_VALUE); setRssi(rssiPercentScaled, RSSI_SOURCE_RX_PROTOCOL_CRSF); } @@ -198,6 +201,9 @@ static void crsfCheckRssi(uint32_t currentTimeUs) { if (cmpTimeUs(currentTimeUs, lastLinkStatisticsFrameUs) > CRSF_LINK_STATUS_UPDATE_TIMEOUT_US) { if (rssiSource == RSSI_SOURCE_RX_PROTOCOL_CRSF) { setRssiDirect(0, RSSI_SOURCE_RX_PROTOCOL_CRSF); +#ifdef USE_RX_RSSI_DBM + setRssiDbmDirect(130, RSSI_SOURCE_RX_PROTOCOL_CRSF); +#endif } #ifdef USE_RX_LINK_QUALITY_INFO if (linkQualitySource == LQ_SOURCE_RX_PROTOCOL_CRSF) { diff --git a/src/main/rx/rx.c b/src/main/rx/rx.c index d5e4a7098d..65b7e92ea8 100644 --- a/src/main/rx/rx.c +++ b/src/main/rx/rx.c @@ -72,6 +72,7 @@ const char rcChannelLetters[] = "AERT12345678abcdefgh"; static uint16_t rssi = 0; // range: [0;1023] +static uint8_t rssi_dbm = 130; // range: [0;130] display 0 to -130 static timeUs_t lastMspRssiUpdateUs = 0; static pt1Filter_t frameErrFilter; @@ -757,6 +758,43 @@ uint8_t getRssiPercent(void) return scaleRange(getRssi(), 0, RSSI_MAX_VALUE, 0, 100); } +uint8_t getRssiDbm(void) +{ + return rssi_dbm; +} + +#define RSSI_SAMPLE_COUNT_DBM 16 + +static uint8_t updateRssiDbmSamples(uint8_t value) +{ + static uint16_t samplesdbm[RSSI_SAMPLE_COUNT_DBM]; + static uint8_t sampledbmIndex = 0; + static unsigned sumdbm = 0; + + sumdbm += value - samplesdbm[sampledbmIndex]; + samplesdbm[sampledbmIndex] = value; + sampledbmIndex = (sampledbmIndex + 1) % RSSI_SAMPLE_COUNT_DBM; + return sumdbm / RSSI_SAMPLE_COUNT_DBM; +} + +void setRssiDbm(uint8_t rssiDbmValue, rssiSource_e source) +{ + if (source != rssiSource) { + return; + } + + rssi_dbm = updateRssiDbmSamples(rssiDbmValue); +} + +void setRssiDbmDirect(uint8_t newRssiDbm, rssiSource_e source) +{ + if (source != rssiSource) { + return; + } + + rssi_dbm = newRssiDbm; +} + #ifdef USE_RX_LINK_QUALITY_INFO uint16_t rxGetLinkQuality(void) { diff --git a/src/main/rx/rx.h b/src/main/rx/rx.h index 051f0080c3..a71efd6db9 100644 --- a/src/main/rx/rx.h +++ b/src/main/rx/rx.h @@ -183,6 +183,10 @@ uint16_t rxGetLinkQuality(void); void setLinkQualityDirect(uint16_t linkqualityValue); uint16_t rxGetLinkQualityPercent(void); +uint8_t getRssiDbm(void); +void setRssiDbm(uint8_t newRssiDbm, rssiSource_e source); +void setRssiDbmDirect(uint8_t newRssiDbm, rssiSource_e source); + void resetAllRxChannelRangeConfigurations(rxChannelRangeConfig_t *rxChannelRangeConfig); void suspendRxPwmPpmSignal(void); diff --git a/src/main/startup/startup_stm32h743xx.s b/src/main/startup/startup_stm32h743xx.s new file mode 100755 index 0000000000..b316a79591 --- /dev/null +++ b/src/main/startup/startup_stm32h743xx.s @@ -0,0 +1,789 @@ +/** + ****************************************************************************** + * @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 */ + + bl persistentObjectInit + +/* Copy the data segment initializers from flash to SRAM */ + movs r1, #0 + b LoopCopyDataInit + +CopyDataInit: + ldr r3, =_sidata + ldr r3, [r3, r1] + str r3, [r0, r1] + adds r1, r1, #4 + +LoopCopyDataInit: + ldr r0, =_sdata + ldr r3, =_edata + adds r2, r0, r1 + cmp r2, r3 + bcc CopyDataInit + ldr r2, =_sbss + b LoopFillZerobss +/* Zero fill the bss segment. */ +FillZerobss: + movs r3, #0 + str r3, [r2], #4 + +LoopFillZerobss: + ldr r3, = _ebss + cmp r2, r3 + bcc FillZerobss + +/*-----*/ + ldr r2, =_ssram2 + b LoopFillZerosram2 +/* Zero fill the sram2 segment. */ +FillZerosram2: + movs r3, #0 + str r3, [r2], #4 + +LoopFillZerosram2: + ldr r3, = _esram2 + cmp r2, r3 + bcc FillZerosram2 + + ldr r2, =_sfastram_bss + b LoopFillZerofastram_bss +/* Zero fill the fastram_bss segment. */ +FillZerofastram_bss: + movs r3, #0 + str r3, [r2], #4 + +LoopFillZerofastram_bss: + ldr r3, = _efastram_bss + cmp r2, r3 + bcc FillZerofastram_bss +/*-----*/ + +/* 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/src/main/target/common_post.h b/src/main/target/common_post.h index 6a032749ad..8eabd1dac3 100644 --- a/src/main/target/common_post.h +++ b/src/main/target/common_post.h @@ -94,6 +94,7 @@ #if !defined(USE_SERIALRX_CRSF) #undef USE_TELEMETRY_CRSF #undef USE_CRSF_LINK_STATISTICS +#undef USE_RX_RSSI_DBM #endif #if !defined(USE_TELEMETRY_CRSF) || !defined(USE_CMS) diff --git a/src/main/target/common_pre.h b/src/main/target/common_pre.h index 72bffcca93..37fb445b8d 100644 --- a/src/main/target/common_pre.h +++ b/src/main/target/common_pre.h @@ -98,10 +98,15 @@ #endif // STM32F7 #ifdef STM32H7 +#define USE_ITCM_RAM +#define USE_FAST_RAM +#define USE_DSHOT +#define USE_GYRO_DATA_ANALYSE +#define USE_ADC_INTERNAL #define USE_USB_CDC_HID #endif -#if defined(STM32F4) || defined(STM32F7) +#if defined(STM32F4) || defined(STM32F7) || defined(STM32H7) #define TASK_GYROPID_DESIRED_PERIOD 125 // 125us = 8kHz #define SCHEDULER_DELAY_LIMIT 10 #else @@ -131,7 +136,7 @@ #define FAST_RAM #endif // USE_FAST_RAM -#ifdef STM32F4 +#if defined(STM32F4) || defined (STM32H7) // Data in RAM which is guaranteed to not be reset on hot reboot #define PERSISTENT __attribute__ ((section(".persistent_data"), aligned(4))) #endif @@ -142,6 +147,12 @@ #define SRAM2 #endif +#ifdef USE_DMA_RAM +#define DMA_RAM __attribute__((section(".DMA_RAM"))) +#else +#define DMA_RAM +#endif + #define USE_BRUSHED_ESC_AUTODETECT // Detect if brushed motors are connected and set defaults appropriately to avoid motors spinning on boot #define USE_PWM_OUTPUT @@ -271,6 +282,7 @@ #define USE_ESC_SENSOR_INFO #define USE_CRSF_CMS_TELEMETRY #define USE_CRSF_LINK_STATISTICS +#define USE_RX_RSSI_DBM #endif #endif // FLASH_SIZE > 128 @@ -313,4 +325,3 @@ #define USE_PERSISTENT_STATS #define USE_PROFILE_NAMES #endif - diff --git a/src/main/target/link/stm32_flash_h743_2m.ld b/src/main/target/link/stm32_flash_h743_2m.ld new file mode 100644 index 0000000000..392a0c02c1 --- /dev/null +++ b/src/main/target/link/stm32_flash_h743_2m.ld @@ -0,0 +1,276 @@ +/* +***************************************************************************** +** +** File : stm32_flash_h7x3_2m.ld +** +** Abstract : Linker script for STM32H743xI Device with +** 512K AXI-RAM mapped onto AXI bus on D1 domain +** 128K SRAM1 mapped on D2 domain +** 128K SRAM2 mapped on D2 domain +** 32K SRAM3 mapped on D2 domain +** 64K SRAM4 mapped on D3 domain +** 64K ITCM +** 128K DTCM +** +***************************************************************************** +*/ + +/* Entry Point */ +ENTRY(Reset_Handler) + +/* +0x00000000 to 0x0000FFFF 64K ITCM +0x20000000 to 0x2001FFFF 128K DTCM +0x24000000 to 0x2407FFFF 512K AXI SRAM, D1 domain, main RAM +0x30000000 to 0x3001FFFF 128K SRAM1, D2 domain, unused +0x30020000 to 0x3003FFFF 128K SRAM2, D2 domain, unused +0x30040000 to 0x30047FFF 32K SRAM3, D2 domain, unused +0x38000000 to 0x3800FFFF 64K SRAM4, D3 domain, unused +0x38800000 to 0x38800FFF 4K BACKUP SRAM, Backup domain, unused + +0x08000000 to 0x081FFFFF 2048K full flash, +0x08000000 to 0x0801FFFF 128K isr vector, startup code, +0x08020000 to 0x0803FFFF 128K config, // FLASH_Sector_1 +0x08040000 to 0x081FFFFF 1792K firmware, +*/ + +/* Specify the memory areas */ +MEMORY +{ + FLASH (rx) : ORIGIN = 0x08000000, LENGTH = 128K + FLASH_CONFIG (r) : ORIGIN = 0x08020000, LENGTH = 128K + FLASH1 (rx) : ORIGIN = 0x08040000, LENGTH = 1792K + + ITCM_RAM (rwx) : ORIGIN = 0x00000000, LENGTH = 64K + DTCM_RAM (rwx) : ORIGIN = 0x20000000, LENGTH = 128K + RAM (rwx) : ORIGIN = 0x24000000, LENGTH = 512K + + D2_RAM (rwx) : ORIGIN = 0x30000000, LENGTH = 256K /* SRAM1 + SRAM2 */ + + MEMORY_B1 (rx) : ORIGIN = 0x60000000, LENGTH = 0K +} + +REGION_ALIAS("STACKRAM", DTCM_RAM) +REGION_ALIAS("FASTRAM", DTCM_RAM) + +/* INCLUDE "stm32_flash_f7_split.ld" */ +/* +***************************************************************************** +** +** File : stm32_flash_f7_split.ld +** +** Abstract : Common linker script for STM32 devices. +** +***************************************************************************** +*/ + +/* Entry Point */ +ENTRY(Reset_Handler) + +/* Highest address of the user mode stack */ +_estack = ORIGIN(STACKRAM) + LENGTH(STACKRAM) - 8; /* Reserve 2 x 4bytes for info across reset */ + +/* Base address where the config is stored. */ +__config_start = ORIGIN(FLASH_CONFIG); +__config_end = ORIGIN(FLASH_CONFIG) + LENGTH(FLASH_CONFIG); + +/* Generate a link error if heap and stack don't fit into RAM */ +_Min_Heap_Size = 0; /* required amount of heap */ +_Min_Stack_Size = 0x800; /* required amount of stack */ + +/* Define output sections */ +SECTIONS +{ + /* The startup code goes first into FLASH */ + .isr_vector : + { + . = ALIGN(512); + PROVIDE (isr_vector_table_base = .); + KEEP(*(.isr_vector)) /* Startup code */ + . = ALIGN(4); + } >FLASH + + /* The program code and other data goes into FLASH */ + .text : + { + . = ALIGN(4); + *(.text) /* .text sections (code) */ + *(.text*) /* .text* sections (code) */ + *(.rodata) /* .rodata sections (constants, strings, etc.) */ + *(.rodata*) /* .rodata* sections (constants, strings, etc.) */ + *(.glue_7) /* glue arm to thumb code */ + *(.glue_7t) /* glue thumb to arm code */ + *(.eh_frame) + + KEEP (*(.init)) + KEEP (*(.fini)) + + . = ALIGN(4); + _etext = .; /* define a global symbols at end of code */ + } >FLASH1 + + /* Critical program code goes into ITCM RAM */ + /* Copy specific fast-executing code to ITCM RAM */ + tcm_code = LOADADDR(.tcm_code); + .tcm_code : + { + . = ALIGN(4); + tcm_code_start = .; + *(.tcm_code) + *(.tcm_code*) + . = ALIGN(4); + tcm_code_end = .; + } >ITCM_RAM AT >FLASH1 + + .ARM.extab : + { + *(.ARM.extab* .gnu.linkonce.armextab.*) + } >FLASH + + .ARM : + { + __exidx_start = .; + *(.ARM.exidx*) __exidx_end = .; + } >FLASH + + .pg_registry : + { + PROVIDE_HIDDEN (__pg_registry_start = .); + KEEP (*(.pg_registry)) + KEEP (*(SORT(.pg_registry.*))) + PROVIDE_HIDDEN (__pg_registry_end = .); + } >FLASH + + .pg_resetdata : + { + PROVIDE_HIDDEN (__pg_resetdata_start = .); + KEEP (*(.pg_resetdata)) + PROVIDE_HIDDEN (__pg_resetdata_end = .); + } >FLASH + + /* used by the startup to initialize data */ + _sidata = LOADADDR(.data); + + /* Initialized data sections goes into RAM, load LMA copy after code */ + .data : + { + . = ALIGN(4); + _sdata = .; /* create a global symbol at data start */ + *(.data) /* .data sections */ + *(.data*) /* .data* sections */ + + . = ALIGN(4); + _edata = .; /* define a global symbol at data end */ + } >RAM AT >FLASH + + /* Uninitialized data section */ + . = ALIGN(4); + .bss (NOLOAD) : + { + /* This is used by the startup in order to initialize the .bss secion */ + _sbss = .; /* define a global symbol at bss start */ + __bss_start__ = _sbss; + *(.bss) + *(SORT_BY_ALIGNMENT(.bss*)) + *(COMMON) + + . = ALIGN(4); + _ebss = .; /* define a global symbol at bss end */ + __bss_end__ = _ebss; + } >RAM + + /* Uninitialized data section */ + . = ALIGN(4); + .sram2 (NOLOAD) : + { + /* This is used by the startup in order to initialize the .sram2 secion */ + _ssram2 = .; /* define a global symbol at sram2 start */ + __sram2_start__ = _ssram2; + *(.sram2) + *(SORT_BY_ALIGNMENT(.sram2*)) + + . = ALIGN(4); + _esram2 = .; /* define a global symbol at sram2 end */ + __sram2_end__ = _esram2; + } >RAM + + /* used during startup to initialized fastram_data */ + _sfastram_idata = LOADADDR(.fastram_data); + + /* Initialized FAST_RAM section for unsuspecting developers */ + .fastram_data : + { + . = ALIGN(4); + _sfastram_data = .; /* create a global symbol at data start */ + *(.fastram_data) /* .data sections */ + *(.fastram_data*) /* .data* sections */ + + . = ALIGN(4); + _efastram_data = .; /* define a global symbol at data end */ + } >FASTRAM AT >FLASH + + . = ALIGN(4); + .fastram_bss (NOLOAD) : + { + _sfastram_bss = .; + __fastram_bss_start__ = _sfastram_bss; + *(.fastram_bss) + *(SORT_BY_ALIGNMENT(.fastram_bss*)) + + . = ALIGN(4); + _efastram_bss = .; + __fastram_bss_end__ = _efastram_bss; + } >FASTRAM + + .DMA_RAM (NOLOAD) : + { + _sdmaram = .; + _dmaram_start__ = _sdmaram; + KEEP(*(.DMA_RAM)) + _edmaram = .; + _dmaram_end__ = _edmaram; + } >D2_RAM + + .persistent_data (NOLOAD) : + { + __persistent_data_start__ = .; + *(.persistent_data) + . = ALIGN(4); + __persistent_data_end__ = .; + } >RAM + + + /* User_heap_stack section, used to check that there is enough RAM left */ + _heap_stack_end = ORIGIN(STACKRAM)+LENGTH(STACKRAM) - 8; /* 8 bytes to allow for alignment */ + _heap_stack_begin = _heap_stack_end - _Min_Stack_Size - _Min_Heap_Size; + . = _heap_stack_begin; + ._user_heap_stack : + { + . = ALIGN(4); + PROVIDE ( end = . ); + PROVIDE ( _end = . ); + . = . + _Min_Heap_Size; + . = . + _Min_Stack_Size; + . = ALIGN(4); + } >STACKRAM = 0xa5 + + /* MEMORY_bank1 section, code must be located here explicitly */ + /* Example: extern int foo(void) __attribute__ ((section (".mb1text"))); */ + .memory_b1_text : + { + *(.mb1text) /* .mb1text sections (code) */ + *(.mb1text*) /* .mb1text* sections (code) */ + *(.mb1rodata) /* read-only data (constants) */ + *(.mb1rodata*) + } >MEMORY_B1 + + /* Remove information from the standard libraries */ + /DISCARD/ : + { + libc.a ( * ) + libm.a ( * ) + libgcc.a ( * ) + } + + .ARM.attributes 0 : { *(.ARM.attributes) } +} diff --git a/src/main/target/link/stm32_flash_h750.ld b/src/main/target/link/stm32_flash_h750.ld new file mode 100644 index 0000000000..e7b42516ba --- /dev/null +++ b/src/main/target/link/stm32_flash_h750.ld @@ -0,0 +1,277 @@ +/* +***************************************************************************** +** +** File : stm32_flash_h7x3_2m.ld +** +** Abstract : Linker script for STM32H743xI Device with +** 512K AXI-RAM mapped onto AXI bus on D1 domain +** 128K SRAM1 mapped on D2 domain +** 128K SRAM2 mapped on D2 domain +** 32K SRAM3 mapped on D2 domain +** 64K SRAM4 mapped on D3 domain +** 64K ITCM +** 128K DTCM +** +***************************************************************************** +*/ + +/* Entry Point */ +ENTRY(Reset_Handler) + +/* +0x00000000 to 0x0000FFFF 64K ITCM +0x20000000 to 0x2001FFFF 128K DTCM +0x24000000 to 0x2407FFFF 512K AXI SRAM, D1 domain, main RAM +0x30000000 to 0x3001FFFF 128K SRAM1, D2 domain, unused +0x30020000 to 0x3003FFFF 128K SRAM2, D2 domain, unused +0x30040000 to 0x30047FFF 32K SRAM3, D2 domain, unused +0x38000000 to 0x3800FFFF 64K SRAM4, D3 domain, unused +0x38800000 to 0x38800FFF 4K BACKUP SRAM, Backup domain, unused + +0x08000000 to 0x0801FFFF 128K isr vector, startup code, firmware, no config! // FLASH_Sector_0 +*/ + +/* Specify the memory areas */ +MEMORY +{ + FLASH (rx) : ORIGIN = 0x08000000, LENGTH = 128K + + ITCM_RAM (rwx) : ORIGIN = 0x00000000, LENGTH = 64K + DTCM_RAM (rwx) : ORIGIN = 0x20000000, LENGTH = 128K + RAM (rwx) : ORIGIN = 0x24000000, LENGTH = 512K + + D2_RAM (rwx) : ORIGIN = 0x30000000, LENGTH = 256K /* SRAM1 + SRAM2 */ + + MEMORY_B1 (rx) : ORIGIN = 0x60000000, LENGTH = 0K + QUADSPI (rx) : ORIGIN = 0x90000000, LENGTH = 0K +} + +REGION_ALIAS("STACKRAM", DTCM_RAM) +REGION_ALIAS("FASTRAM", DTCM_RAM) + +/* INCLUDE "stm32_flash_f7_split.ld" */ +/* +***************************************************************************** +** +** File : stm32_flash_f7_split.ld +** +** Abstract : Common linker script for STM32 devices. +** +***************************************************************************** +*/ + +/* Entry Point */ +ENTRY(Reset_Handler) + +/* Highest address of the user mode stack */ +_estack = ORIGIN(STACKRAM) + LENGTH(STACKRAM); /* end of RAM */ + +/* Base address where the config is stored. */ +/* +__config_start = ORIGIN(FLASH_CONFIG); +__config_end = ORIGIN(FLASH_CONFIG) + LENGTH(FLASH_CONFIG); +*/ + +/* Base address where the quad spi. */ +__quad_spi_start = ORIGIN(QUADSPI); + +/* Generate a link error if heap and stack don't fit into RAM */ +_Min_Heap_Size = 0; /* required amount of heap */ +_Min_Stack_Size = 0x800; /* required amount of stack */ + +/* Define output sections */ +SECTIONS +{ + /* The startup code goes first into FLASH */ + .isr_vector : + { + . = ALIGN(512); + PROVIDE (isr_vector_table_base = .); + KEEP(*(.isr_vector)) /* Startup code */ + . = ALIGN(4); + } >FLASH + + /* The program code and other data goes into FLASH */ + .text : + { + . = ALIGN(4); + *(.text) /* .text sections (code) */ + *(.text*) /* .text* sections (code) */ + *(.rodata) /* .rodata sections (constants, strings, etc.) */ + *(.rodata*) /* .rodata* sections (constants, strings, etc.) */ + *(.glue_7) /* glue arm to thumb code */ + *(.glue_7t) /* glue thumb to arm code */ + *(.eh_frame) + + KEEP (*(.init)) + KEEP (*(.fini)) + + . = ALIGN(4); + _etext = .; /* define a global symbols at end of code */ + } >FLASH + + /* Critical program code goes into ITCM RAM */ + /* Copy specific fast-executing code to ITCM RAM */ + tcm_code = LOADADDR(.tcm_code); + .tcm_code : + { + . = ALIGN(4); + tcm_code_start = .; + *(.tcm_code) + *(.tcm_code*) + . = ALIGN(4); + tcm_code_end = .; + } >ITCM_RAM AT >FLASH + + .ARM.extab : + { + *(.ARM.extab* .gnu.linkonce.armextab.*) + } >FLASH + + .ARM : + { + __exidx_start = .; + *(.ARM.exidx*) __exidx_end = .; + } >FLASH + + .pg_registry : + { + PROVIDE_HIDDEN (__pg_registry_start = .); + KEEP (*(.pg_registry)) + KEEP (*(SORT(.pg_registry.*))) + PROVIDE_HIDDEN (__pg_registry_end = .); + } >FLASH + + .pg_resetdata : + { + PROVIDE_HIDDEN (__pg_resetdata_start = .); + KEEP (*(.pg_resetdata)) + PROVIDE_HIDDEN (__pg_resetdata_end = .); + } >FLASH + + /* used by the startup to initialize data */ + _sidata = LOADADDR(.data); + + /* Initialized data sections goes into RAM, load LMA copy after code */ + .data : + { + . = ALIGN(4); + _sdata = .; /* create a global symbol at data start */ + *(.data) /* .data sections */ + *(.data*) /* .data* sections */ + + . = ALIGN(4); + _edata = .; /* define a global symbol at data end */ + } >RAM AT >FLASH + + /* Uninitialized data section */ + . = ALIGN(4); + .bss (NOLOAD) : + { + /* This is used by the startup in order to initialize the .bss secion */ + _sbss = .; /* define a global symbol at bss start */ + __bss_start__ = _sbss; + *(.bss) + *(SORT_BY_ALIGNMENT(.bss*)) + *(COMMON) + + . = ALIGN(4); + _ebss = .; /* define a global symbol at bss end */ + __bss_end__ = _ebss; + } >RAM + + /* Uninitialized data section */ + . = ALIGN(4); + .sram2 (NOLOAD) : + { + /* This is used by the startup in order to initialize the .sram2 secion */ + _ssram2 = .; /* define a global symbol at sram2 start */ + __sram2_start__ = _ssram2; + *(.sram2) + *(SORT_BY_ALIGNMENT(.sram2*)) + + . = ALIGN(4); + _esram2 = .; /* define a global symbol at sram2 end */ + __sram2_end__ = _esram2; + } >RAM + + /* used during startup to initialized fastram_data */ + _sfastram_idata = LOADADDR(.fastram_data); + + /* Initialized FAST_RAM section for unsuspecting developers */ + .fastram_data : + { + . = ALIGN(4); + _sfastram_data = .; /* create a global symbol at data start */ + *(.fastram_data) /* .data sections */ + *(.fastram_data*) /* .data* sections */ + + . = ALIGN(4); + _efastram_data = .; /* define a global symbol at data end */ + } >FASTRAM AT >FLASH + + . = ALIGN(4); + .fastram_bss (NOLOAD) : + { + _sfastram_bss = .; + __fastram_bss_start__ = _sfastram_bss; + *(.fastram_bss) + *(SORT_BY_ALIGNMENT(.fastram_bss*)) + + . = ALIGN(4); + _efastram_bss = .; + __fastram_bss_end__ = _efastram_bss; + } >FASTRAM + + .DMA_RAM (NOLOAD) : + { + _sdmaram = .; + _dmaram_start__ = _sdmaram; + KEEP(*(.DMA_RAM)) + _edmaram = .; + _dmaram_end__ = _edmaram; + } >D2_RAM + + .persistent_data (NOLOAD) : + { + __persistent_data_start__ = .; + *(.persistent_data) + . = ALIGN(4); + __persistent_data_end__ = .; + } >RAM + + + /* User_heap_stack section, used to check that there is enough RAM left */ + _heap_stack_end = ORIGIN(STACKRAM)+LENGTH(STACKRAM) - 8; /* 8 bytes to allow for alignment */ + _heap_stack_begin = _heap_stack_end - _Min_Stack_Size - _Min_Heap_Size; + . = _heap_stack_begin; + ._user_heap_stack : + { + . = ALIGN(4); + PROVIDE ( end = . ); + PROVIDE ( _end = . ); + . = . + _Min_Heap_Size; + . = . + _Min_Stack_Size; + . = ALIGN(4); + } >STACKRAM = 0xa5 + + /* MEMORY_bank1 section, code must be located here explicitly */ + /* Example: extern int foo(void) __attribute__ ((section (".mb1text"))); */ + .memory_b1_text : + { + *(.mb1text) /* .mb1text sections (code) */ + *(.mb1text*) /* .mb1text* sections (code) */ + *(.mb1rodata) /* read-only data (constants) */ + *(.mb1rodata*) + } >MEMORY_B1 + + /* Remove information from the standard libraries */ + /DISCARD/ : + { + libc.a ( * ) + libm.a ( * ) + libgcc.a ( * ) + } + + .ARM.attributes 0 : { *(.ARM.attributes) } +} diff --git a/src/main/target/stm32h7xx_hal_conf.h b/src/main/target/stm32h7xx_hal_conf.h new file mode 100755 index 0000000000..9e96a5924e --- /dev/null +++ b/src/main/target/stm32h7xx_hal_conf.h @@ -0,0 +1,432 @@ +/** + ****************************************************************************** + * @file stm32h7xx_hal_conf_template.h + * @author MCD Application Team + * @brief HAL configuration template file. + * This file should be copied to the application folder and renamed + * to stm32h7xx_hal_conf.h. + ****************************************************************************** + * @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. + * + ****************************************************************************** + */ + +/* 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_CEC_MODULE_ENABLED +//#define HAL_COMP_MODULE_ENABLED +#define HAL_CORTEX_MODULE_ENABLED +//#define HAL_CRC_MODULE_ENABLED +//#define HAL_CRYP_MODULE_ENABLED +#define HAL_DAC_MODULE_ENABLED +//#define HAL_DCMI_MODULE_ENABLED +//#define HAL_DFSDM_MODULE_ENABLED +#define HAL_DMA_MODULE_ENABLED +//#define HAL_DMA2D_MODULE_ENABLED +//#define HAL_ETH_MODULE_ENABLED +//#define HAL_FDCAN_MODULE_ENABLED +#define HAL_FLASH_MODULE_ENABLED +#define HAL_GPIO_MODULE_ENABLED +//#define HAL_HASH_MODULE_ENABLED +//#define HAL_HCD_MODULE_ENABLED +//#define HAL_HRTIM_MODULE_ENABLED +//#define HAL_HSEM_MODULE_ENABLED +#define HAL_I2C_MODULE_ENABLED +//#define HAL_I2S_MODULE_ENABLED +//#define HAL_IRDA_MODULE_ENABLED +//#define HAL_IWDG_MODULE_ENABLED +//#define HAL_JPEG_MODULE_ENABLED +//#define HAL_LPTIM_MODULE_ENABLED +//#define HAL_LTDC_MODULE_ENABLED +//#define HAL_MDIOS_MODULE_ENABLED +#define HAL_MDMA_MODULE_ENABLED +//#define HAL_MMC_MODULE_ENABLED +//#define HAL_NAND_MODULE_ENABLED +//#define HAL_NOR_MODULE_ENABLED +//#define HAL_OPAMP_MODULE_ENABLED +#define HAL_PCD_MODULE_ENABLED +#define HAL_PWR_MODULE_ENABLED +#define HAL_QSPI_MODULE_ENABLED +#define HAL_RCC_MODULE_ENABLED +//#define HAL_RNG_MODULE_ENABLED +#define HAL_RTC_MODULE_ENABLED +//#define HAL_SAI_MODULE_ENABLED +#define HAL_SD_MODULE_ENABLED +//#define HAL_SDRAM_MODULE_ENABLED +//#define HAL_SMARTCARD_MODULE_ENABLED +//#define HAL_SMBUS_MODULE_ENABLED +//#define HAL_SPDIFRX_MODULE_ENABLED +#define HAL_SPI_MODULE_ENABLED +//#define HAL_SRAM_MODULE_ENABLED +//#define HAL_SWPMI_MODULE_ENABLED +#define HAL_TIM_MODULE_ENABLED +#define HAL_UART_MODULE_ENABLED +#define HAL_USART_MODULE_ENABLED +//#define HAL_WWDG_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)25000000) /*!< Value of the External oscillator in Hz */ +#endif /* HSE_VALUE */ + +#if !defined (HSE_STARTUP_TIMEOUT) + #define HSE_STARTUP_TIMEOUT ((uint32_t)5000) /*!< 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)32768) /*!< Value of the External oscillator in Hz*/ +#endif /* LSE_VALUE */ + + +#if !defined (LSE_STARTUP_TIMEOUT) + #define LSE_STARTUP_TIMEOUT ((uint32_t)5000) /*!< 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)3300) /*!< Value of VDD in mv */ +#define TICK_INT_PRIORITY ((uint32_t)0x00) /*!< tick interrupt priority */ +#define USE_RTOS 0 +#define USE_SD_TRANSCEIVER 0U /*!< use uSD Transceiver */ + +/* ########################### Ethernet Configuration ######################### */ +#define ETH_TX_DESC_CNT 4 /* number of Ethernet Tx DMA descriptors */ +#define ETH_RX_DESC_CNT 4 /* number of Ethernet Rx DMA descriptors */ + +#define ETH_MAC_ADDR0 ((uint8_t)0x02) +#define ETH_MAC_ADDR1 ((uint8_t)0x00) +#define ETH_MAC_ADDR2 ((uint8_t)0x00) +#define ETH_MAC_ADDR3 ((uint8_t)0x00) +#define ETH_MAC_ADDR4 ((uint8_t)0x00) +#define ETH_MAC_ADDR5 ((uint8_t)0x00) + +/* ########################## Assert Selection ############################## */ +/** + * @brief Uncomment the line below to expanse the "assert_param" macro in the + * HAL drivers code + */ +/* #define USE_FULL_ASSERT 1 */ + +/* ################## SPI peripheral configuration ########################## */ +/** + * @brief Used to activate CRC feature inside HAL SPI Driver + * Activated (1U): CRC code is compiled within HAL SPI driver + * Deactivated (0U): CRC code excluded from HAL SPI driver + */ + +#define USE_SPI_CRC 1U + + +/* Includes ------------------------------------------------------------------*/ +/** + * @brief Include module's header file + */ + +#ifdef HAL_RCC_MODULE_ENABLED + #include "stm32h7xx_hal_rcc.h" +#endif /* HAL_RCC_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_MMC_MODULE_ENABLED + #include "stm32h7xx_hal_mmc.h" +#endif /* HAL_MMC_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_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/src/main/target/system_stm32h7xx.c b/src/main/target/system_stm32h7xx.c new file mode 100644 index 0000000000..2bd8895391 --- /dev/null +++ b/src/main/target/system_stm32h7xx.c @@ -0,0 +1,966 @@ +/** + ****************************************************************************** + * @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" +#include "drivers/system.h" +#include "platform.h" + +#include "build/debug.h" + +void forcedSystemResetWithoutDisablingCaches(void); + +#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 + * @{ + */ + +static void Error_Handler(void) +{ + while (1); +} + +void HandleStuckSysTick(void) +{ + uint32_t tickStart = HAL_GetTick(); + uint32_t tickEnd = 0; + + int attemptsRemaining = 80 * 1000; + while (((tickEnd = HAL_GetTick()) == tickStart) && --attemptsRemaining) { + // H7 at 400Mhz - attemptsRemaining was reduced by debug build: 5,550, release build: 33,245 + } + + if (tickStart == tickEnd) { + forcedSystemResetWithoutDisablingCaches(); + } +} + +// HSE clock configuration taken from +// STM32Cube_FW_H7_V1.3.0/Projects/STM32H743ZI-Nucleo/Examples/RCC/RCC_ClockConfig/Src/main.c + +/** + * @brief Switch the PLL source from CSI to HSE , and select the PLL as SYSCLK + * source. + * System Clock source = PLL (HSE BYPASS) + * SYSCLK(Hz) = 400000000 (CPU Clock) + * HCLK(Hz) = 200000000 (AXI and AHBs Clock) + * AHB Prescaler = 2 + * D1 APB3 Prescaler = 2 (APB3 Clock 100MHz) + * D2 APB1 Prescaler = 2 (APB1 Clock 100MHz) + * D2 APB2 Prescaler = 2 (APB2 Clock 100MHz) + * D3 APB4 Prescaler = 2 (APB4 Clock 100MHz) + * HSE Frequency(Hz) = 8000000 + * PLL_M = 4 + * PLL_N = 400 + * PLL_P = 2 + * PLL_Q = 5 + * PLL_R = 8 + * VDD(V) = 3.3 + * Flash Latency(WS) = 4 + * @param None + * @retval None + */ +static void SystemClockHSE_Config(void) +{ + RCC_ClkInitTypeDef RCC_ClkInitStruct = {0}; + RCC_OscInitTypeDef RCC_OscInitStruct = {0}; + +#ifdef notdef + // CSI has been disabled at SystemInit(). + // HAL_RCC_ClockConfig() will fail because CSIRDY is off. + + /* -1- Select CSI as system clock source to allow modification of the PLL configuration */ + + RCC_ClkInitStruct.ClockType = RCC_CLOCKTYPE_SYSCLK; + RCC_ClkInitStruct.SYSCLKSource = RCC_SYSCLKSOURCE_CSI; + if (HAL_RCC_ClockConfig(&RCC_ClkInitStruct, FLASH_LATENCY_1) != HAL_OK) { + /* Initialization Error */ + Error_Handler(); + } +#endif + + /* -2- Enable HSE Oscillator, select it as PLL source and finally activate the PLL */ + +#define USE_H7_HSERDY_SLOW_WORKAROUND +#ifdef USE_H7_HSERDY_SLOW_WORKAROUND + + // With reference to 2.3.22 in the ES0250 Errata for the L476. + // Applying the same workaround here in the vain hopes that it improves startup times. + // Randomly the HSERDY bit takes AGES, over 10 seconds, to be set. + + __HAL_RCC_GPIOH_CLK_ENABLE(); + + HAL_GPIO_WritePin(GPIOH, GPIO_PIN_0 | GPIO_PIN_1, GPIO_PIN_RESET); + + GPIO_InitTypeDef gpio_initstruct; + gpio_initstruct.Pin = GPIO_PIN_0 | GPIO_PIN_1; + gpio_initstruct.Mode = GPIO_MODE_OUTPUT_PP; + gpio_initstruct.Pull = GPIO_NOPULL; + gpio_initstruct.Speed = GPIO_SPEED_FREQ_VERY_HIGH; + + HAL_GPIO_Init(GPIOH, &gpio_initstruct); +#endif + + RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_HSE; + RCC_OscInitStruct.HSEState = RCC_HSE_ON; // Even Nucleo-H473 work without RCC_HSE_BYPASS + + RCC_OscInitStruct.PLL.PLLState = RCC_PLL_ON; + RCC_OscInitStruct.PLL.PLLSource = RCC_PLLSOURCE_HSE; + RCC_OscInitStruct.PLL.PLLM = 4; + RCC_OscInitStruct.PLL.PLLN = 400; // 8M / 4 * 400 = 800 (PLL1N output) + RCC_OscInitStruct.PLL.PLLP = 2; // 400 + RCC_OscInitStruct.PLL.PLLQ = 8; // 100, SPI123 + RCC_OscInitStruct.PLL.PLLR = 5; // 160, no particular usage yet. (See note on PLL2/3 below) + + RCC_OscInitStruct.PLL.PLLVCOSEL = RCC_PLL1VCOWIDE; + RCC_OscInitStruct.PLL.PLLRGE = RCC_PLL1VCIRANGE_2; + + HAL_StatusTypeDef status = HAL_RCC_OscConfig(&RCC_OscInitStruct); + +#define USE_H7_HSE_TIMEOUT_WORKAROUND +#ifdef USE_H7_HSE_TIMEOUT_WORKAROUND + if (status == HAL_TIMEOUT) { + forcedSystemResetWithoutDisablingCaches(); // DC - sometimes HSERDY gets stuck, waiting longer doesn't help. + } +#endif + + if (status != HAL_OK) { + /* Initialization Error */ + Error_Handler(); + } + + // Configure PLL2 and PLL3 + // Use of PLL2 and PLL3 are not determined yet. + // A review of total system wide clock requirements is necessary. + + + // Configure SCGU (System Clock Generation Unit) + // Select PLL as system clock source and configure bus clock dividers. + // + // Clock type and divider member names do not have direct visual correspondence. + // Here is how these correspond: + // RCC_CLOCKTYPE_SYSCLK sys_ck + // RCC_CLOCKTYPE_HCLK AHBx (rcc_hclk1,rcc_hclk2,rcc_hclk3,rcc_hclk4) + // RCC_CLOCKTYPE_D1PCLK1 APB3 (rcc_pclk3) + // RCC_CLOCKTYPE_PCLK1 APB1 (rcc_pclk1) + // RCC_CLOCKTYPE_PCLK2 APB2 (rcc_pclk2) + // RCC_CLOCKTYPE_D3PCLK1 APB4 (rcc_pclk4) + + RCC_ClkInitStruct.ClockType = ( \ + RCC_CLOCKTYPE_SYSCLK | \ + RCC_CLOCKTYPE_HCLK | \ + RCC_CLOCKTYPE_D1PCLK1 | \ + RCC_CLOCKTYPE_PCLK1 | \ + RCC_CLOCKTYPE_PCLK2 | \ + RCC_CLOCKTYPE_D3PCLK1); + RCC_ClkInitStruct.SYSCLKSource = RCC_SYSCLKSOURCE_PLLCLK; // = PLL1P = 400 + RCC_ClkInitStruct.SYSCLKDivider = RCC_SYSCLK_DIV1; // = PLL1P(400) / 1 = 400 + RCC_ClkInitStruct.AHBCLKDivider = RCC_HCLK_DIV2; // = SYSCLK(400) / 2 = 200 + RCC_ClkInitStruct.APB3CLKDivider = RCC_APB3_DIV2; // = HCLK(200) / 2 = 100 + RCC_ClkInitStruct.APB1CLKDivider = RCC_APB1_DIV2; // = HCLK(200) / 2 = 100 + RCC_ClkInitStruct.APB2CLKDivider = RCC_APB2_DIV2; // = HCLK(200) / 2 = 100 + RCC_ClkInitStruct.APB4CLKDivider = RCC_APB4_DIV2; // = HCLK(200) / 2 = 100 + + // For HCLK=200MHz with VOS1 range, ST recommended flash latency is 2WS. + // RM0433 (Rev.5) Table 12. FLASH recommended number of wait states and programming delay + + if (HAL_RCC_ClockConfig(&RCC_ClkInitStruct, FLASH_LATENCY_2) != HAL_OK) { + /* Initialization Error */ + Error_Handler(); + } + + /* -4- Optional: Disable CSI Oscillator (if the HSI is no more needed by the application)*/ + RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_CSI; + RCC_OscInitStruct.CSIState = RCC_CSI_OFF; + RCC_OscInitStruct.PLL.PLLState = RCC_PLL_NONE; + if (HAL_RCC_OscConfig(&RCC_OscInitStruct) != HAL_OK) { + /* Initialization Error */ + Error_Handler(); + } +} + +void SystemClock_Config(void) +{ + + /**Supply configuration update enable + */ + MODIFY_REG(PWR->CR3, PWR_CR3_SCUEN, 0); + + /**Configure the main internal regulator output voltage + */ + __HAL_PWR_VOLTAGESCALING_CONFIG(PWR_REGULATOR_VOLTAGE_SCALE1); + + while ((PWR->D3CR & (PWR_D3CR_VOSRDY)) != PWR_D3CR_VOSRDY) + { + } + + + SystemClockHSE_Config(); + + /*activate CSI clock mondatory for I/O Compensation Cell*/ + __HAL_RCC_CSI_ENABLE() ; + + /* Enable SYSCFG clock mondatory for I/O Compensation Cell */ + __HAL_RCC_SYSCFG_CLK_ENABLE() ; + /* Enables the I/O Compensation Cell */ + HAL_EnableCompensationCell(); + + HandleStuckSysTick(); + + HAL_Delay(10); + + // Configure peripheral clocks + + RCC_PeriphCLKInitTypeDef RCC_PeriphClkInit; + + // Configure HSI48 as peripheral clock for USB + + RCC_PeriphClkInit.PeriphClockSelection = RCC_PERIPHCLK_USB; + RCC_PeriphClkInit.UsbClockSelection = RCC_USBCLKSOURCE_HSI48; + HAL_RCCEx_PeriphCLKConfig(&RCC_PeriphClkInit); + + // Configure CRS for dynamic calibration of HSI48 + // While ES0392 Rev 5 "STM32H742xI/G and STM32H743xI/G device limitations" states CRS not working for REV.Y, + // it is always turned on as it seems that it has no negative effect on clock accuracy. + + RCC_CRSInitTypeDef crsInit = { + .Prescaler = RCC_CRS_SYNC_DIV1, + .Source = RCC_CRS_SYNC_SOURCE_USB2, + .Polarity = RCC_CRS_SYNC_POLARITY_RISING, + .ReloadValue = RCC_CRS_RELOADVALUE_DEFAULT, + .ErrorLimitValue = RCC_CRS_ERRORLIMIT_DEFAULT, + .HSI48CalibrationValue = RCC_CRS_HSI48CALIBRATION_DEFAULT, + }; + + __HAL_RCC_CRS_CLK_ENABLE(); + HAL_RCCEx_CRSConfig(&crsInit); + +#ifdef USE_CRS_INTERRUPTS + // Turn on USE_CRS_INTERRUPTS to see CRS in action + HAL_NVIC_SetPriority(CRS_IRQn, 6, 0); + HAL_NVIC_EnableIRQ(CRS_IRQn); + __HAL_RCC_CRS_ENABLE_IT(RCC_CRS_IT_SYNCOK|RCC_CRS_IT_SYNCWARN|RCC_CRS_IT_ESYNC|RCC_CRS_IT_ERR); +#endif + +#if 0 + // XXX This is currently done in serial_uart_hal.c, but should be done here, + // XXX where all clock distribution can be centrally managed. + + // Configure peripheral clocks for UARTs + // + // Possible sources: + // D2PCLK1 (pclk1 for APB1 = USART234578) + // D2PCLK2 (pclk2 for APB2 = USART16) + // PLL2 (pll2_q_ck) + // PLL3 (pll3_q_ck), + // HSI (hsi_ck), + // CSI (csi_ck),LSE(lse_ck); + + RCC_PeriphClkInit.PeriphClockSelection = RCC_PERIPHCLK_USART16|RCC_PERIPHCLK_USART234578; + RCC_PeriphClkInit.Usart16ClockSelection = RCC_USART16CLKSOURCE_D2PCLK2; + RCC_PeriphClkInit.Usart234578ClockSelection = RCC_USART234578CLKSOURCE_D2PCLK1; + HAL_RCCEx_PeriphCLKConfig(&RCC_PeriphClkInit); +#endif + + // Configure SPI clock sources + // + // Possible sources for SPI123: + // PLL (pll1_q_ck) + // PLL2 (pll2_p_ck) + // PLL3 (pll3_p_ck) + // PIN (I2S_CKIN) + // CLKP (per_ck) + // Possible sources for SPI45: + // D2PCLK1 (rcc_pclk2 = APB1) 100MHz + // PLL2 (pll2_q_ck) + // PLL3 (pll3_q_ck) + // HSI (hsi_ker_ck) + // CSI (csi_ker_ck) + // HSE (hse_ck) + // Possible sources for SPI6: + // D3PCLK1 (rcc_pclk4 = APB4) 100MHz + // PLL2 (pll2_q_ck) + // PLL3 (pll3_q_ck) + // HSI (hsi_ker_ck) + // CSI (csi_ker_ck) + // HSE (hse_ck) + + // For the first cut, we use 100MHz from various sources + + RCC_PeriphClkInit.PeriphClockSelection = RCC_PERIPHCLK_SPI123|RCC_PERIPHCLK_SPI45|RCC_PERIPHCLK_SPI6; + RCC_PeriphClkInit.Spi123ClockSelection = RCC_SPI123CLKSOURCE_PLL; + RCC_PeriphClkInit.Spi45ClockSelection = RCC_SPI45CLKSOURCE_D2PCLK1; + RCC_PeriphClkInit.Spi6ClockSelection = RCC_SPI6CLKSOURCE_D3PCLK1; + HAL_RCCEx_PeriphCLKConfig(&RCC_PeriphClkInit); + +#ifdef USE_SDCARD_SDIO + RCC_PeriphClkInit.PeriphClockSelection = RCC_PERIPHCLK_SDMMC; + RCC_PeriphClkInit.PLL2.PLL2M = 5; + RCC_PeriphClkInit.PLL2.PLL2N = 500; + RCC_PeriphClkInit.PLL2.PLL2P = 2; // 500Mhz + RCC_PeriphClkInit.PLL2.PLL2Q = 3; // 266Mhz - 133Mhz can be derived from this for for QSPI if flash chip supports the speed. + RCC_PeriphClkInit.PLL2.PLL2R = 4; // 200Mhz HAL LIBS REQUIRE 200MHZ SDMMC CLOCK, see HAL_SD_ConfigWideBusOperation, SDMMC_HSpeed_CLK_DIV, SDMMC_NSpeed_CLK_DIV + RCC_PeriphClkInit.PLL2.PLL2RGE = RCC_PLL2VCIRANGE_0; + RCC_PeriphClkInit.PLL2.PLL2VCOSEL = RCC_PLL2VCOWIDE; + RCC_PeriphClkInit.PLL2.PLL2FRACN = 0; + RCC_PeriphClkInit.SdmmcClockSelection = RCC_SDMMCCLKSOURCE_PLL2; + HAL_RCCEx_PeriphCLKConfig(&RCC_PeriphClkInit); +#endif + + // Configure MCO clocks for clock test/verification + + // Possible sources for MCO1: + // RCC_MCO1SOURCE_HSI (hsi_ck) + // RCC_MCO1SOURCE_LSE (?) + // RCC_MCO1SOURCE_HSE (hse_ck) + // RCC_MCO1SOURCE_PLL1QCLK (pll1_q_ck) + // RCC_MCO1SOURCE_HSI48 (hsi48_ck) + + // HAL_RCC_MCOConfig(RCC_MCO1, RCC_MCO1SOURCE_HSE, RCC_MCODIV_1); // HSE(8M) / 1 = 1M + HAL_RCC_MCOConfig(RCC_MCO1, RCC_MCO1SOURCE_HSI48, RCC_MCODIV_4); // HSI48(48M) / 4 = 12M + + // Possible sources for MCO2: + // RCC_MCO2SOURCE_SYSCLK (sys_ck) + // RCC_MCO2SOURCE_PLL2PCLK (pll2_p_ck) + // RCC_MCO2SOURCE_HSE (hse_ck) + // RCC_MCO2SOURCE_PLLCLK (pll1_p_ck) + // RCC_MCO2SOURCE_CSICLK (csi_ck) + // RCC_MCO2SOURCE_LSICLK (lsi_ck) + + HAL_RCC_MCOConfig(RCC_MCO2, RCC_MCO2SOURCE_PLLCLK, RCC_MCODIV_15); // PLL1P(400M) / 15 = 26.67M +} + +#ifdef USE_CRS_INTERRUPTS +static uint32_t crs_syncok = 0; +static uint32_t crs_syncwarn = 0; +static uint32_t crs_expectedsync = 0; +static uint32_t crs_error = 0; + +void HAL_RCCEx_CRS_SyncOkCallback(void) +{ + ++crs_syncok; +} + +void HAL_RCCEx_CRS_SyncWarnCallback(void) +{ + ++crs_syncwarn; +} + +void HAL_RCCEx_CRS_ExpectedSyncCallback(void) +{ + ++crs_expectedsync; +} + +void HAL_RCCEx_CRS_ErrorCallback(uint32_t Error) +{ + ++crs_error; +} + +void CRS_IRQHandler(void) +{ + HAL_RCCEx_CRS_IRQHandler(); +} +#endif + +void MPU_Config() +{ + MPU_Region_InitTypeDef MPU_InitStruct; + + HAL_MPU_Disable(); + + MPU_InitStruct.Enable = MPU_REGION_ENABLE; + + // XXX FIXME Entire D2 SRAM1 region is setup as non-bufferable (write-through) and non-cachable. + // Ideally, DMA buffer region should be prepared based on read and write activities, + // and DMA buffers should be assigned to different region based on read/write activity on + // the buffer. + // XXX FIXME Further more, sizes of DMA buffer regions should tracked and size set as appropriate + // using __start__ and __end__. + + MPU_InitStruct.BaseAddress = 0x30000000; + MPU_InitStruct.Size = MPU_REGION_SIZE_128KB; + + MPU_InitStruct.AccessPermission = MPU_REGION_FULL_ACCESS; + + // As described in p.10 of AN4838. + + // Write through & no-cache config + MPU_InitStruct.TypeExtField = MPU_TEX_LEVEL0; + MPU_InitStruct.IsCacheable = MPU_ACCESS_NOT_CACHEABLE; + MPU_InitStruct.IsBufferable = MPU_ACCESS_NOT_BUFFERABLE; + MPU_InitStruct.IsShareable = MPU_ACCESS_SHAREABLE; + + MPU_InitStruct.Number = MPU_REGION_NUMBER1; + MPU_InitStruct.SubRegionDisable = 0x00; + MPU_InitStruct.DisableExec = MPU_INSTRUCTION_ACCESS_ENABLE; + + HAL_MPU_ConfigRegion(&MPU_InitStruct); + +#ifdef USE_SDCARD_SDIO + // The Base Address 0x24000000 is the SRAM1 accessible by the SDIO internal DMA. + MPU_InitStruct.Enable = MPU_REGION_ENABLE; + MPU_InitStruct.BaseAddress = 0x24000000; + MPU_InitStruct.Size = MPU_REGION_SIZE_512KB; + MPU_InitStruct.AccessPermission = MPU_REGION_FULL_ACCESS; + MPU_InitStruct.IsBufferable = MPU_ACCESS_NOT_BUFFERABLE; + MPU_InitStruct.IsCacheable = MPU_ACCESS_CACHEABLE; + MPU_InitStruct.IsShareable = MPU_ACCESS_NOT_SHAREABLE; + MPU_InitStruct.Number = MPU_REGION_NUMBER2; + MPU_InitStruct.TypeExtField = MPU_TEX_LEVEL0; + MPU_InitStruct.SubRegionDisable = 0x00; + MPU_InitStruct.DisableExec = MPU_INSTRUCTION_ACCESS_ENABLE; + HAL_MPU_ConfigRegion(&MPU_InitStruct); +#endif + + HAL_MPU_Enable(MPU_PRIVILEGED_DEFAULT); +} + +/** + * @brief Setup the microcontroller system + * Initialize the FPU setting, vector table location and External memory + * configuration. + * @param None + * @retval None + */ +void systemCheckResetReason(void); + +void resetMPU(void) +{ + MPU_Region_InitTypeDef MPU_InitStruct; + + /* Disable the MPU */ + HAL_MPU_Disable(); + + uint8_t highestRegion = MPU_REGION_NUMBER15; + + // disable all existing regions + for (uint8_t region = MPU_REGION_NUMBER0; region <= highestRegion; region++) { + MPU_InitStruct.Enable = MPU_REGION_DISABLE; + MPU_InitStruct.Number = region; + HAL_MPU_ConfigRegion(&MPU_InitStruct); + } + HAL_MPU_Enable(MPU_PRIVILEGED_DEFAULT); +} + +void SystemInit (void) +{ + resetMPU(); + + initialiseMemorySections(); + + systemCheckResetReason(); + + // 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 + + // XXX Don't do this until we are established with clock handling + // RCC->CR &= (uint32_t)0xEAF6ED7F; + + // Instead, we explicitly turn those on + RCC->CR |= RCC_CR_CSION; + RCC->CR |= RCC_CR_HSION; + RCC->CR |= RCC_CR_HSEON; + RCC->CR |= RCC_CR_HSI48ON; + + /* 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 ------------------*/ +#if defined(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 + + SystemClock_Config(); + SystemCoreClockUpdate(); + + // Configure MPU + + MPU_Config(); + + // Enable CPU L1-Cache + SCB_EnableICache(); + SCB_EnableDCache(); +} + +/** + * @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) +{ + SystemCoreClock = HAL_RCC_GetSysClockFreq(); +} + +#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/main/target/system_stm32h7xx.h b/src/main/target/system_stm32h7xx.h new file mode 100755 index 0000000000..c22d942c37 --- /dev/null +++ b/src/main/target/system_stm32h7xx.h @@ -0,0 +1,121 @@ +/** + ****************************************************************************** + * @file system_stm32h7xx.h + * @author MCD Application Team + * @brief CMSIS Cortex-Mx Device System Source File for STM32H7xx devices. + ****************************************************************************** + * @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 + * @{ + */ + +/** + * @brief Define to prevent recursive inclusion + */ +#ifndef SYSTEM_STM32H7XX_H +#define SYSTEM_STM32H7XX_H + +#ifdef __cplusplus + extern "C" { +#endif + +/** @addtogroup STM32H7xx_System_Includes + * @{ + */ + +/** + * @} + */ + + +/** @addtogroup STM32H7xx_System_Exported_types + * @{ + */ + /* This variable is updated in three ways: + 1) by calling CMSIS function SystemCoreClockUpdate() + 2) by calling HAL API function HAL_RCC_GetSysClockFreq() + 3) each time HAL_RCC_ClockConfig() is called to configure the system clock frequency + Note: If you use this function to configure the system clock; then there + is no need to call the 2 first functions listed above, since SystemCoreClock + variable is updated automatically. + */ +extern uint32_t SystemCoreClock; /*!< System Domain1 Clock Frequency */ +extern uint32_t SystemD2Clock; /*!< System Domain2 Clock Frequency */ +extern const uint8_t D1CorePrescTable[16] ; /*!< D1CorePrescTable prescalers table values */ + +/** + * @} + */ + +/** @addtogroup STM32H7xx_System_Exported_Constants + * @{ + */ + +/** + * @} + */ + +/** @addtogroup STM32H7xx_System_Exported_Macros + * @{ + */ + +/** + * @} + */ + +/** @addtogroup STM32H7xx_System_Exported_Functions + * @{ + */ + +extern void SystemInit(void); +extern void SystemCoreClockUpdate(void); +/** + * @} + */ + +#ifdef __cplusplus +} +#endif + +#endif /* SYSTEM_STM32H7XX_H */ + +/** + * @} + */ + +/** + * @} + */ +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/src/test/unit/cms_unittest.cc b/src/test/unit/cms_unittest.cc index 2a41308993..1e00c050dd 100644 --- a/src/test/unit/cms_unittest.cc +++ b/src/test/unit/cms_unittest.cc @@ -147,4 +147,6 @@ void systemReset(void) {} void setArmingDisabled(armingDisableFlags_e flag) { UNUSED(flag); } void unsetArmingDisabled(armingDisableFlags_e flag) { UNUSED(flag); } bool IS_RC_MODE_ACTIVE(boxId_e) { return false; } +void setRebootRequired(void) {} +bool getRebootRequired(void) { return false; } }