From 39d2c219b5deb5378786a06fcbd6d3848f2c846e Mon Sep 17 00:00:00 2001 From: hathach Date: Wed, 13 Jan 2021 15:52:54 +0700 Subject: [PATCH] add stlinkv3mini to f7 group --- hw/bsp/stlinkv3mini/board.mk | 63 ---- hw/bsp/stlinkv3mini/stlinkv3mini.c | 298 ------------------ .../boards}/stlinkv3mini/STM32F723xE_FLASH.ld | 0 hw/bsp/stm32f7/boards/stlinkv3mini/board.h | 94 ++++++ hw/bsp/stm32f7/boards/stlinkv3mini/board.mk | 14 + .../boards}/stlinkv3mini/stm32f7xx_hal_conf.h | 0 hw/bsp/stm32f7/family.c | 3 +- 7 files changed, 110 insertions(+), 362 deletions(-) delete mode 100644 hw/bsp/stlinkv3mini/board.mk delete mode 100644 hw/bsp/stlinkv3mini/stlinkv3mini.c rename hw/bsp/{ => stm32f7/boards}/stlinkv3mini/STM32F723xE_FLASH.ld (100%) create mode 100644 hw/bsp/stm32f7/boards/stlinkv3mini/board.h create mode 100644 hw/bsp/stm32f7/boards/stlinkv3mini/board.mk rename hw/bsp/{ => stm32f7/boards}/stlinkv3mini/stm32f7xx_hal_conf.h (100%) diff --git a/hw/bsp/stlinkv3mini/board.mk b/hw/bsp/stlinkv3mini/board.mk deleted file mode 100644 index fb8b6b29..00000000 --- a/hw/bsp/stlinkv3mini/board.mk +++ /dev/null @@ -1,63 +0,0 @@ -# Only OTG-HS has a connector on this board - -SPEED ?= high - -CFLAGS += \ - -flto \ - -mthumb \ - -mabi=aapcs \ - -mcpu=cortex-m7 \ - -mfloat-abi=hard \ - -mfpu=fpv5-d16 \ - -nostdlib -nostartfiles \ - -DSTM32F723xx \ - -DHSE_VALUE=25000000 \ - -DCFG_TUSB_MCU=OPT_MCU_STM32F7 \ - -DBOARD_DEVICE_RHPORT_NUM=1 - -ifeq ($(SPEED), high) - CFLAGS += -DBOARD_DEVICE_RHPORT_SPEED=OPT_MODE_HIGH_SPEED - $(info "Using OTG_HS in HighSpeed mode") -else - CFLAGS += -DBOARD_DEVICE_RHPORT_SPEED=OPT_MODE_FULL_SPEED - $(info "Using OTG_HS in FullSpeed mode") -endif - -# mcu driver cause following warnings -CFLAGS += -Wno-error=shadow -Wno-error=cast-align - -ST_FAMILY = f7 -ST_CMSIS = hw/mcu/st/cmsis_device_$(ST_FAMILY) -ST_HAL_DRIVER = hw/mcu/st/stm32$(ST_FAMILY)xx_hal_driver - -# All source paths should be relative to the top level. -LD_FILE = hw/bsp/$(BOARD)/STM32F723xE_FLASH.ld - -SRC_C += \ - $(ST_CMSIS)/Source/Templates/system_stm32$(ST_FAMILY)xx.c \ - $(ST_HAL_DRIVER)/Src/stm32$(ST_FAMILY)xx_hal.c \ - $(ST_HAL_DRIVER)/Src/stm32$(ST_FAMILY)xx_hal_cortex.c \ - $(ST_HAL_DRIVER)/Src/stm32$(ST_FAMILY)xx_hal_rcc.c \ - $(ST_HAL_DRIVER)/Src/stm32$(ST_FAMILY)xx_hal_rcc_ex.c \ - $(ST_HAL_DRIVER)/Src/stm32$(ST_FAMILY)xx_hal_gpio.c \ - $(ST_HAL_DRIVER)/Src/stm32$(ST_FAMILY)xx_hal_uart.c \ - $(ST_HAL_DRIVER)/Src/stm32$(ST_FAMILY)xx_hal_pwr_ex.c - -SRC_S += \ - $(ST_CMSIS)/Source/Templates/gcc/startup_stm32f723xx.s - -INC += \ - $(TOP)/lib/CMSIS_5/CMSIS/Core/Include \ - $(TOP)/$(ST_CMSIS)/Include \ - $(TOP)/$(ST_HAL_DRIVER)/Inc \ - $(TOP)/hw/bsp/$(BOARD) - -# For TinyUSB port source -VENDOR = st -CHIP_FAMILY = synopsys - -# For freeRTOS port source -FREERTOS_PORT = ARM_CM7/r0p1 - -# flash target using on-board stlink -flash: flash-stlink diff --git a/hw/bsp/stlinkv3mini/stlinkv3mini.c b/hw/bsp/stlinkv3mini/stlinkv3mini.c deleted file mode 100644 index 03babcfa..00000000 --- a/hw/bsp/stlinkv3mini/stlinkv3mini.c +++ /dev/null @@ -1,298 +0,0 @@ -/* - * The MIT License (MIT) - * - * Copyright (c) 2020 Uwe Bonnes (bon@elektron.ikp.physik.tu-darmstadt.de), - * Ha Thach (tinyusb.org) - * - * Permission is hereby granted, free of charge, to any person obtaining a copy - * of this software and associated documentation files (the "Software"), to deal - * in the Software without restriction, including without limitation the rights - * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell - * copies of the Software, and to permit persons to whom the Software is - * furnished to do so, subject to the following conditions: - * - * The above copyright notice and this permission notice shall be included in - * all copies or substantial portions of the Software. - * - * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR - * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, - * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE - * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER - * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, - * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN - * THE SOFTWARE. - * - * This file is part of the TinyUSB stack. - */ - -#include "../board.h" - -#include "stm32f7xx_hal.h" - -//--------------------------------------------------------------------+ -// Forward USB interrupt events to TinyUSB IRQ Handler -//--------------------------------------------------------------------+ -void OTG_FS_IRQHandler(void) -{ - tud_int_handler(0); -} - -// Despite being call USB2_OTG -// OTG_HS is marked as RHPort1 by TinyUSB to be consistent across stm32 port -void OTG_HS_IRQHandler(void) -{ - tud_int_handler(1); -} - -// Pin configuartion with help from -// RadioOperator/CMSIS-DAP_for_STLINK-V3MINI.git -// CMSIS-DAP_for_STLINK-V3MINI/STLINK-V3MINI/Sch/STLINK-V3MINI_GPIOs.JPG - -//--------------------------------------------------------------------+ -// MACRO TYPEDEF CONSTANT ENUM -//--------------------------------------------------------------------+ - -#define LED_PORT GPIOA -#define LED_PIN GPIO_PIN_10 -#define LED_STATE_ON 1 - -/* No Buttom */ - -#define UARTx USART6 -#define UART_GPIO_PORT GPIOG -#define UART_GPIO_AF GPIO_AF8_USART6 -#define UART_TX_PIN GPIO_PIN_9 -#define UART_RX_PIN GPIO_PIN_14 - -UART_HandleTypeDef UartHandle; - -// enable all LED, Button, Uart, USB clock -static void all_rcc_clk_enable(void) -{ - __HAL_RCC_GPIOA_CLK_ENABLE(); // USB D+, D-, LED - __HAL_RCC_GPIOB_CLK_ENABLE(); // OTG_HS - __HAL_RCC_GPIOD_CLK_ENABLE(); // OTG_HS ID - __HAL_RCC_GPIOG_CLK_ENABLE(); // Uart TX, RX - __HAL_RCC_USART6_CLK_ENABLE(); // Uart module -} - -/** - * @brief System Clock Configuration - * The system Clock is configured as follow : - * System Clock source = PLL (HSE) - * SYSCLK(Hz) = 216000000 - * HCLK(Hz) = 216000000 - * AHB Prescaler = 1 - * APB1 Prescaler = 4 - * APB2 Prescaler = 2 - * HSE Frequency(Hz) = 25000000 - * PLL_M = HSE_VALUE/1000000 - * PLL_N = 432 - * PLL_P = 2 - * PLL_Q = 9 - * VDD(V) = 3.3 - * Main regulator output voltage = Scale1 mode - * Flash Latency(WS) = 7 - * The USB clock configuration from PLLSAI: - * PLLSAIP = 8 - * PLLSAIN = 384 - * PLLSAIQ = 7 - * @param None - * @retval None - */ -void SystemClock_Config(void) -{ - RCC_ClkInitTypeDef RCC_ClkInitStruct; - RCC_OscInitTypeDef RCC_OscInitStruct; - - /* Enable Power Control clock */ - __HAL_RCC_PWR_CLK_ENABLE(); - - /* The voltage scaling allows optimizing the power consumption when the device is - clocked below the maximum system frequency, to update the voltage scaling value - regarding system frequency refer to product datasheet. */ - __HAL_PWR_VOLTAGESCALING_CONFIG(PWR_REGULATOR_VOLTAGE_SCALE1); - - /* Enable HSE Oscillator and activate PLL with HSE as source */ - RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_HSE; - RCC_OscInitStruct.HSEState = RCC_HSE_BYPASS; - RCC_OscInitStruct.PLL.PLLState = RCC_PLL_ON; - RCC_OscInitStruct.PLL.PLLSource = RCC_PLLSOURCE_HSE; - RCC_OscInitStruct.PLL.PLLM = HSE_VALUE/1000000; - RCC_OscInitStruct.PLL.PLLN = 432; - RCC_OscInitStruct.PLL.PLLP = RCC_PLLP_DIV2; - RCC_OscInitStruct.PLL.PLLQ = 9; - HAL_RCC_OscConfig(&RCC_OscInitStruct); - - /* Activate the OverDrive to reach the 216 MHz Frequency */ - HAL_PWREx_EnableOverDrive(); - - /* Select PLL as system clock source and configure the HCLK, PCLK1 and PCLK2 clocks dividers */ - RCC_ClkInitStruct.ClockType = (RCC_CLOCKTYPE_SYSCLK | RCC_CLOCKTYPE_HCLK | RCC_CLOCKTYPE_PCLK1 | RCC_CLOCKTYPE_PCLK2); - RCC_ClkInitStruct.SYSCLKSource = RCC_SYSCLKSOURCE_PLLCLK; - RCC_ClkInitStruct.AHBCLKDivider = RCC_SYSCLK_DIV1; - RCC_ClkInitStruct.APB1CLKDivider = RCC_HCLK_DIV4; - RCC_ClkInitStruct.APB2CLKDivider = RCC_HCLK_DIV2; - - HAL_RCC_ClockConfig(&RCC_ClkInitStruct, FLASH_LATENCY_7); -} - -void board_init(void) -{ - - - SystemClock_Config(); - all_rcc_clk_enable(); - -#if CFG_TUSB_OS == OPT_OS_NONE - // 1ms tick timer - SysTick_Config(SystemCoreClock / 1000); -#endif - - GPIO_InitTypeDef GPIO_InitStruct; - - // LED - GPIO_InitStruct.Pin = LED_PIN; - GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_PP; - GPIO_InitStruct.Pull = GPIO_PULLUP; - GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_HIGH; - HAL_GPIO_Init(LED_PORT, &GPIO_InitStruct); - - // Uart - GPIO_InitStruct.Pin = UART_TX_PIN | UART_RX_PIN; - GPIO_InitStruct.Mode = GPIO_MODE_AF_PP; - GPIO_InitStruct.Pull = GPIO_PULLUP; - GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_HIGH; - GPIO_InitStruct.Alternate = UART_GPIO_AF; - HAL_GPIO_Init(UART_GPIO_PORT, &GPIO_InitStruct); - - UartHandle.Instance = UARTx; - UartHandle.Init.BaudRate = CFG_BOARD_UART_BAUDRATE; - UartHandle.Init.WordLength = UART_WORDLENGTH_8B; - UartHandle.Init.StopBits = UART_STOPBITS_1; - UartHandle.Init.Parity = UART_PARITY_NONE; - UartHandle.Init.HwFlowCtl = UART_HWCONTROL_NONE; - UartHandle.Init.Mode = UART_MODE_TX_RX; - UartHandle.Init.OverSampling = UART_OVERSAMPLING_16; - HAL_UART_Init(&UartHandle); - -#if BOARD_DEVICE_RHPORT_NUM == 0 - /* Configure USB FS GPIOs */ - /* Configure DM DP Pins */ - GPIO_InitStruct.Pin = (GPIO_PIN_11 | GPIO_PIN_12); - GPIO_InitStruct.Mode = GPIO_MODE_AF_PP; - GPIO_InitStruct.Pull = GPIO_NOPULL; - GPIO_InitStruct.Speed = GPIO_SPEED_HIGH; - GPIO_InitStruct.Alternate = GPIO_AF10_OTG_FS; - HAL_GPIO_Init(GPIOA, &GPIO_InitStruct); - - /* Configure VBUS Pin */ - GPIO_InitStruct.Pin = GPIO_PIN_9; - GPIO_InitStruct.Mode = GPIO_MODE_INPUT; - GPIO_InitStruct.Pull = GPIO_NOPULL; - HAL_GPIO_Init(GPIOA, &GPIO_InitStruct); - - /* Configure OTG-FS ID pin */ - GPIO_InitStruct.Pin = GPIO_PIN_10; - GPIO_InitStruct.Mode = GPIO_MODE_AF_OD; - GPIO_InitStruct.Pull = GPIO_PULLUP; - GPIO_InitStruct.Alternate = GPIO_AF10_OTG_FS; - HAL_GPIO_Init(GPIOA, &GPIO_InitStruct); - - /* Enable USB FS Clocks */ - __HAL_RCC_USB_OTG_FS_CLK_ENABLE(); - - // Enable VBUS sense (B device) via pin PA9 - USB_OTG_FS->GCCFG |= USB_OTG_GCCFG_VBDEN; - -#else - /* Configure USB HS GPIOs */ - /* Configure DM DP Pins */ - GPIO_InitStruct.Pin = (GPIO_PIN_14 | GPIO_PIN_15); - GPIO_InitStruct.Mode = GPIO_MODE_AF_PP; - GPIO_InitStruct.Pull = GPIO_NOPULL; - GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_HIGH; - GPIO_InitStruct.Alternate = GPIO_AF10_OTG_HS; - HAL_GPIO_Init(GPIOB, &GPIO_InitStruct); - - // Enable HS VBUS sense (B device) via pin PB13 - USB_OTG_HS->GCCFG |= USB_OTG_GCCFG_VBDEN; - - /* Configure OTG-HS ID pin */ - GPIO_InitStruct.Pin = GPIO_PIN_13; - GPIO_InitStruct.Mode = GPIO_MODE_AF_OD; - GPIO_InitStruct.Pull = GPIO_PULLUP; - GPIO_InitStruct.Alternate = GPIO_AF10_OTG_HS; - HAL_GPIO_Init(GPIOD, &GPIO_InitStruct); - - /* Enable PHYC Clocks */ - __HAL_RCC_OTGPHYC_CLK_ENABLE(); - - /* Enable USB HS Clocks */ - __HAL_RCC_USB_OTG_HS_CLK_ENABLE(); - __HAL_RCC_USB_OTG_HS_ULPI_CLK_ENABLE(); - - // Enable VBUS sense (B device) via pin PA9 - USB_OTG_HS->GCCFG &= ~USB_OTG_GCCFG_VBDEN; - - // B-peripheral session valid override enable - USB_OTG_HS->GOTGCTL |= USB_OTG_GOTGCTL_BVALOEN; - USB_OTG_HS->GOTGCTL |= USB_OTG_GOTGCTL_BVALOVAL; - - // Force device mode - USB_OTG_HS->GUSBCFG &= ~USB_OTG_GUSBCFG_FHMOD; - USB_OTG_HS->GUSBCFG |= USB_OTG_GUSBCFG_FDMOD; - -#endif -} - -//--------------------------------------------------------------------+ -// Board porting API -//--------------------------------------------------------------------+ - -void board_led_write(bool state) -{ - HAL_GPIO_WritePin(LED_PORT, LED_PIN, state); -} - -uint32_t board_button_read(void) -{ - return 0; -} - -int board_uart_read(uint8_t* buf, int len) -{ - (void) buf; (void) len; - return 0; -} - -int board_uart_write(void const * buf, int len) -{ - HAL_UART_Transmit(&UartHandle, (uint8_t*) buf, len, 0xffff); - return len; -} - -#if CFG_TUSB_OS == OPT_OS_NONE -volatile uint32_t system_ticks = 0; -void SysTick_Handler (void) -{ - system_ticks++; -} - -uint32_t board_millis(void) -{ - return system_ticks; -} -#endif - -void HardFault_Handler (void) -{ - asm("bkpt"); -} - -// Required by __libc_init_array in startup code if we are compiling using -// -nostdlib/-nostartfiles. -void _init(void) -{ - -} diff --git a/hw/bsp/stlinkv3mini/STM32F723xE_FLASH.ld b/hw/bsp/stm32f7/boards/stlinkv3mini/STM32F723xE_FLASH.ld similarity index 100% rename from hw/bsp/stlinkv3mini/STM32F723xE_FLASH.ld rename to hw/bsp/stm32f7/boards/stlinkv3mini/STM32F723xE_FLASH.ld diff --git a/hw/bsp/stm32f7/boards/stlinkv3mini/board.h b/hw/bsp/stm32f7/boards/stlinkv3mini/board.h new file mode 100644 index 00000000..df10312d --- /dev/null +++ b/hw/bsp/stm32f7/boards/stlinkv3mini/board.h @@ -0,0 +1,94 @@ +/* + * The MIT License (MIT) + * + * Copyright (c) 2021, Ha Thach (tinyusb.org) + * + * Permission is hereby granted, free of charge, to any person obtaining a copy + * of this software and associated documentation files (the "Software"), to deal + * in the Software without restriction, including without limitation the rights + * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell + * copies of the Software, and to permit persons to whom the Software is + * furnished to do so, subject to the following conditions: + * + * The above copyright notice and this permission notice shall be included in + * all copies or substantial portions of the Software. + * + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR + * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE + * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER + * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, + * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN + * THE SOFTWARE. + * + * This file is part of the TinyUSB stack. + */ + +#ifndef BOARD_H_ +#define BOARD_H_ + +#ifdef __cplusplus + extern "C" { +#endif + +#define LED_PORT GPIOA +#define LED_PIN GPIO_PIN_10 +#define LED_STATE_ON 1 + +// No physical button is populated +#define BUTTON_PORT GPIOA +#define BUTTON_PIN GPIO_PIN_0 +#define BUTTON_STATE_ACTIVE 1 + +#define UART_DEV USART6 +#define UART_CLK_EN __HAL_RCC_USART6_CLK_ENABLE +#define UART_GPIO_PORT GPIOG +#define UART_GPIO_AF GPIO_AF8_USART6 +#define UART_TX_PIN GPIO_PIN_9 +#define UART_RX_PIN GPIO_PIN_14 + +//--------------------------------------------------------------------+ +// RCC Clock +//--------------------------------------------------------------------+ +static inline void board_clock_init(void) +{ + RCC_ClkInitTypeDef RCC_ClkInitStruct; + RCC_OscInitTypeDef RCC_OscInitStruct; + + /* Enable Power Control clock */ + __HAL_RCC_PWR_CLK_ENABLE(); + + /* The voltage scaling allows optimizing the power consumption when the device is + clocked below the maximum system frequency, to update the voltage scaling value + regarding system frequency refer to product datasheet. */ + __HAL_PWR_VOLTAGESCALING_CONFIG(PWR_REGULATOR_VOLTAGE_SCALE1); + + /* Enable HSE Oscillator and activate PLL with HSE as source */ + RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_HSE; + RCC_OscInitStruct.HSEState = RCC_HSE_BYPASS; + RCC_OscInitStruct.PLL.PLLState = RCC_PLL_ON; + RCC_OscInitStruct.PLL.PLLSource = RCC_PLLSOURCE_HSE; + RCC_OscInitStruct.PLL.PLLM = HSE_VALUE/1000000; + RCC_OscInitStruct.PLL.PLLN = 432; + RCC_OscInitStruct.PLL.PLLP = RCC_PLLP_DIV2; + RCC_OscInitStruct.PLL.PLLQ = 9; + HAL_RCC_OscConfig(&RCC_OscInitStruct); + + /* Activate the OverDrive to reach the 216 MHz Frequency */ + HAL_PWREx_EnableOverDrive(); + + /* Select PLL as system clock source and configure the HCLK, PCLK1 and PCLK2 clocks dividers */ + RCC_ClkInitStruct.ClockType = (RCC_CLOCKTYPE_SYSCLK | RCC_CLOCKTYPE_HCLK | RCC_CLOCKTYPE_PCLK1 | RCC_CLOCKTYPE_PCLK2); + RCC_ClkInitStruct.SYSCLKSource = RCC_SYSCLKSOURCE_PLLCLK; + RCC_ClkInitStruct.AHBCLKDivider = RCC_SYSCLK_DIV1; + RCC_ClkInitStruct.APB1CLKDivider = RCC_HCLK_DIV4; + RCC_ClkInitStruct.APB2CLKDivider = RCC_HCLK_DIV2; + + HAL_RCC_ClockConfig(&RCC_ClkInitStruct, FLASH_LATENCY_7); +} + +#ifdef __cplusplus + } +#endif + +#endif /* BOARD_H_ */ diff --git a/hw/bsp/stm32f7/boards/stlinkv3mini/board.mk b/hw/bsp/stm32f7/boards/stlinkv3mini/board.mk new file mode 100644 index 00000000..a18b3231 --- /dev/null +++ b/hw/bsp/stm32f7/boards/stlinkv3mini/board.mk @@ -0,0 +1,14 @@ +# Only OTG-HS has a connector on this board +PORT ?= 1 +SPEED ?= high + +CFLAGS += \ + -DSTM32F723xx \ + -DHSE_VALUE=25000000 \ + +# All source paths should be relative to the top level. +LD_FILE = $(BOARD_PATH)/STM32F723xE_FLASH.ld +SRC_S += $(ST_CMSIS)/Source/Templates/gcc/startup_stm32f723xx.s + +# flash target using on-board stlink +flash: flash-stlink diff --git a/hw/bsp/stlinkv3mini/stm32f7xx_hal_conf.h b/hw/bsp/stm32f7/boards/stlinkv3mini/stm32f7xx_hal_conf.h similarity index 100% rename from hw/bsp/stlinkv3mini/stm32f7xx_hal_conf.h rename to hw/bsp/stm32f7/boards/stlinkv3mini/stm32f7xx_hal_conf.h diff --git a/hw/bsp/stm32f7/family.c b/hw/bsp/stm32f7/family.c index a52bbfa1..5356aebb 100644 --- a/hw/bsp/stm32f7/family.c +++ b/hw/bsp/stm32f7/family.c @@ -60,6 +60,7 @@ void board_init(void) __HAL_RCC_GPIOB_CLK_ENABLE(); __HAL_RCC_GPIOC_CLK_ENABLE(); __HAL_RCC_GPIOD_CLK_ENABLE(); + __HAL_RCC_GPIOG_CLK_ENABLE(); __HAL_RCC_GPIOH_CLK_ENABLE(); // ULPI NXT __HAL_RCC_GPIOI_CLK_ENABLE(); // ULPI NXT @@ -141,7 +142,7 @@ void board_init(void) #else // OTG_HS - #ifdef __HAL_RCC_OTGPHYC_CLK_ENABLE + #ifdef USB_HS_PHYC // MCU with built-in HS PHY such as F723, F733, F730 /* Configure DM DP Pins */