diff --git a/.github/workflows/cmake_arm.yml b/.github/workflows/cmake_arm.yml index 1a99d407f..44ada917f 100644 --- a/.github/workflows/cmake_arm.yml +++ b/.github/workflows/cmake_arm.yml @@ -49,6 +49,7 @@ jobs: - 'stm32f7' - 'stm32g0' - 'stm32g4' + - 'stm32h5' - 'stm32h7' - 'stm32l4' - 'stm32u5' diff --git a/.idea/cmake.xml b/.idea/cmake.xml index 101f08078..d12e44789 100644 --- a/.idea/cmake.xml +++ b/.idea/cmake.xml @@ -62,6 +62,7 @@ + diff --git a/.idea/runConfigurations/stlink.xml b/.idea/runConfigurations/stlink.xml index 92d94a80e..babb8b463 100644 --- a/.idea/runConfigurations/stlink.xml +++ b/.idea/runConfigurations/stlink.xml @@ -1,6 +1,6 @@ - - + + diff --git a/hw/bsp/board_mcu.h b/hw/bsp/board_mcu.h index 4ce5c4139..d40f33bbe 100644 --- a/hw/bsp/board_mcu.h +++ b/hw/bsp/board_mcu.h @@ -40,8 +40,8 @@ // Include order follows OPT_MCU_ number #if TU_CHECK_MCU(OPT_MCU_LPC11UXX, OPT_MCU_LPC13XX, OPT_MCU_LPC15XX) || \ - TU_CHECK_MCU(OPT_MCU_LPC175X_6X, OPT_MCU_LPC177X_8X, OPT_MCU_LPC18XX) || \ - TU_CHECK_MCU(OPT_MCU_LPC40XX, OPT_MCU_LPC43XX) + TU_CHECK_MCU(OPT_MCU_LPC175X_6X, OPT_MCU_LPC177X_8X, OPT_MCU_LPC18XX) || \ + TU_CHECK_MCU(OPT_MCU_LPC40XX, OPT_MCU_LPC43XX) #include "chip.h" #elif TU_CHECK_MCU(OPT_MCU_LPC51UXX, OPT_MCU_LPC54XXX, OPT_MCU_LPC55XX, OPT_MCU_MCXN9) @@ -54,8 +54,8 @@ #include "nrf.h" #elif CFG_TUSB_MCU == OPT_MCU_SAMD11 || CFG_TUSB_MCU == OPT_MCU_SAMD21 || \ - CFG_TUSB_MCU == OPT_MCU_SAMD51 || CFG_TUSB_MCU == OPT_MCU_SAME5X || \ - CFG_TUSB_MCU == OPT_MCU_SAML22 || CFG_TUSB_MCU == OPT_MCU_SAML21 + CFG_TUSB_MCU == OPT_MCU_SAMD51 || CFG_TUSB_MCU == OPT_MCU_SAME5X || \ + CFG_TUSB_MCU == OPT_MCU_SAML22 || CFG_TUSB_MCU == OPT_MCU_SAML21 #include "sam.h" #elif CFG_TUSB_MCU == OPT_MCU_SAMG @@ -83,6 +83,9 @@ #elif CFG_TUSB_MCU == OPT_MCU_STM32G4 #include "stm32g4xx.h" +#elif CFG_TUSB_MCU == OPT_MCU_STM32H5 + #include "stm32h5xx.h" + #elif CFG_TUSB_MCU == OPT_MCU_STM32H7 #include "stm32h7xx.h" diff --git a/hw/bsp/stm32g0/boards/stm32g0b1nucleo/board.h b/hw/bsp/stm32g0/boards/stm32g0b1nucleo/board.h index ae0820529..9ebaf73f0 100644 --- a/hw/bsp/stm32g0/boards/stm32g0b1nucleo/board.h +++ b/hw/bsp/stm32g0/boards/stm32g0b1nucleo/board.h @@ -2,7 +2,7 @@ * The MIT License (MIT) * * Copyright (c) 2020, Ha Thach (tinyusb.org) - * Copyright (c) 2034, HiFiPhile + * Copyright (c) 2023, HiFiPhile * * Permission is hereby granted, free of charge, to any person obtaining a copy * of this software and associated documentation files (the "Software"), to deal diff --git a/hw/bsp/stm32g4/family.mk b/hw/bsp/stm32g4/family.mk index 4b0c6922d..95cd84dbd 100644 --- a/hw/bsp/stm32g4/family.mk +++ b/hw/bsp/stm32g4/family.mk @@ -1,7 +1,5 @@ UF2_FAMILY_ID = 0x4c71240a ST_FAMILY = g4 -DEPS_SUBMODULES += lib/CMSIS_5 hw/mcu/st/cmsis_device_$(ST_FAMILY) hw/mcu/st/stm32$(ST_FAMILY)xx_hal_driver - ST_CMSIS = hw/mcu/st/cmsis_device_$(ST_FAMILY) ST_HAL_DRIVER = hw/mcu/st/stm32$(ST_FAMILY)xx_hal_driver diff --git a/hw/bsp/stm32h5/FreeRTOSConfig/FreeRTOSConfig.h b/hw/bsp/stm32h5/FreeRTOSConfig/FreeRTOSConfig.h new file mode 100644 index 000000000..34398c448 --- /dev/null +++ b/hw/bsp/stm32h5/FreeRTOSConfig/FreeRTOSConfig.h @@ -0,0 +1,165 @@ +/* + * FreeRTOS Kernel V10.0.0 + * Copyright (C) 2017 Amazon.com, Inc. or its affiliates. All Rights Reserved. + * + * 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. If you wish to use our Amazon + * FreeRTOS name, please do so in a fair use way that does not cause confusion. + * + * 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. + * + * http://www.FreeRTOS.org + * http://aws.amazon.com/freertos + * + * 1 tab == 4 spaces! + */ + + +#ifndef FREERTOS_CONFIG_H +#define FREERTOS_CONFIG_H + +/*----------------------------------------------------------- + * Application specific definitions. + * + * These definitions should be adjusted for your particular hardware and + * application requirements. + * + * THESE PARAMETERS ARE DESCRIBED WITHIN THE 'CONFIGURATION' SECTION OF THE + * FreeRTOS API DOCUMENTATION AVAILABLE ON THE FreeRTOS.org WEB SITE. + * + * See http://www.freertos.org/a00110.html. + *----------------------------------------------------------*/ + +// skip if included from IAR assembler +#ifndef __IASMARM__ + #include "stm32h5xx.h" +#endif + +/* Cortex M23/M33 port configuration. */ +#define configENABLE_MPU 0 +#define configENABLE_FPU 1 +#define configENABLE_TRUSTZONE 0 +#define configMINIMAL_SECURE_STACK_SIZE (1024) + +#define configUSE_PREEMPTION 1 +#define configUSE_PORT_OPTIMISED_TASK_SELECTION 0 +#define configCPU_CLOCK_HZ SystemCoreClock +#define configTICK_RATE_HZ ( 1000 ) +#define configMAX_PRIORITIES ( 5 ) +#define configMINIMAL_STACK_SIZE ( 128 ) +#define configTOTAL_HEAP_SIZE ( configSUPPORT_DYNAMIC_ALLOCATION*4*1024 ) +#define configMAX_TASK_NAME_LEN 16 +#define configUSE_16_BIT_TICKS 0 +#define configIDLE_SHOULD_YIELD 1 +#define configUSE_MUTEXES 1 +#define configUSE_RECURSIVE_MUTEXES 1 +#define configUSE_COUNTING_SEMAPHORES 1 +#define configQUEUE_REGISTRY_SIZE 4 +#define configUSE_QUEUE_SETS 0 +#define configUSE_TIME_SLICING 0 +#define configUSE_NEWLIB_REENTRANT 0 +#define configENABLE_BACKWARD_COMPATIBILITY 1 +#define configSTACK_ALLOCATION_FROM_SEPARATE_HEAP 0 + +#define configSUPPORT_STATIC_ALLOCATION 1 +#define configSUPPORT_DYNAMIC_ALLOCATION 0 + +/* Hook function related definitions. */ +#define configUSE_IDLE_HOOK 0 +#define configUSE_TICK_HOOK 0 +#define configUSE_MALLOC_FAILED_HOOK 0 // cause nested extern warning +#define configCHECK_FOR_STACK_OVERFLOW 2 + +/* Run time and task stats gathering related definitions. */ +#define configGENERATE_RUN_TIME_STATS 0 +#define configRECORD_STACK_HIGH_ADDRESS 1 +#define configUSE_TRACE_FACILITY 1 // legacy trace +#define configUSE_STATS_FORMATTING_FUNCTIONS 0 + +/* Co-routine definitions. */ +#define configUSE_CO_ROUTINES 0 +#define configMAX_CO_ROUTINE_PRIORITIES 2 + +/* Software timer related definitions. */ +#define configUSE_TIMERS 1 +#define configTIMER_TASK_PRIORITY (configMAX_PRIORITIES-2) +#define configTIMER_QUEUE_LENGTH 32 +#define configTIMER_TASK_STACK_DEPTH configMINIMAL_STACK_SIZE + +/* Optional functions - most linkers will remove unused functions anyway. */ +#define INCLUDE_vTaskPrioritySet 0 +#define INCLUDE_uxTaskPriorityGet 0 +#define INCLUDE_vTaskDelete 0 +#define INCLUDE_vTaskSuspend 1 // required for queue, semaphore, mutex to be blocked indefinitely with portMAX_DELAY +#define INCLUDE_xResumeFromISR 0 +#define INCLUDE_vTaskDelayUntil 1 +#define INCLUDE_vTaskDelay 1 +#define INCLUDE_xTaskGetSchedulerState 0 +#define INCLUDE_xTaskGetCurrentTaskHandle 1 +#define INCLUDE_uxTaskGetStackHighWaterMark 0 +#define INCLUDE_xTaskGetIdleTaskHandle 0 +#define INCLUDE_xTimerGetTimerDaemonTaskHandle 0 +#define INCLUDE_pcTaskGetTaskName 0 +#define INCLUDE_eTaskGetState 0 +#define INCLUDE_xEventGroupSetBitFromISR 0 +#define INCLUDE_xTimerPendFunctionCall 0 + +/* Define to trap errors during development. */ +// Halt CPU (breakpoint) when hitting error, only apply for Cortex M3, M4, M7 +#if defined(__ARM_ARCH_7M__) || defined (__ARM_ARCH_7EM__) +#define configASSERT(_exp) \ + do {\ + if ( !(_exp) ) { \ + volatile uint32_t* ARM_CM_DHCSR = ((volatile uint32_t*) 0xE000EDF0UL); /* Cortex M CoreDebug->DHCSR */ \ + if ( (*ARM_CM_DHCSR) & 1UL ) { /* Only halt mcu if debugger is attached */ \ + taskDISABLE_INTERRUPTS(); \ + __asm("BKPT #0\n"); \ + }\ + }\ + } while(0) +#else +#define configASSERT( x ) +#endif + +/* FreeRTOS hooks to NVIC vectors */ +#define xPortPendSVHandler PendSV_Handler +#define xPortSysTickHandler SysTick_Handler +#define vPortSVCHandler SVC_Handler + +//--------------------------------------------------------------------+ +// Interrupt nesting behavior configuration. +//--------------------------------------------------------------------+ + +// For Cortex-M specific: __NVIC_PRIO_BITS is defined in mcu header +#define configPRIO_BITS 4 + +/* The lowest interrupt priority that can be used in a call to a "set priority" function. */ +#define configLIBRARY_LOWEST_INTERRUPT_PRIORITY ((1<CTRL &= ~1U; + + // If freeRTOS is used, IRQ priority is limit by max syscall ( smaller is higher ) + NVIC_SetPriority(USB_DRD_FS_IRQn, configLIBRARY_MAX_SYSCALL_INTERRUPT_PRIORITY); + #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); + + board_led_write(false); + + // Button + GPIO_InitStruct.Pin = BUTTON_PIN; + GPIO_InitStruct.Mode = GPIO_MODE_INPUT; + GPIO_InitStruct.Pull = BUTTON_STATE_ACTIVE ? GPIO_PULLDOWN : GPIO_PULLUP; + GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_HIGH; + HAL_GPIO_Init(BUTTON_PORT, &GPIO_InitStruct); + + #ifdef UART_DEV + // 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 = (UART_HandleTypeDef) { + .Instance = UART_DEV, + .Init.BaudRate = CFG_BOARD_UART_BAUDRATE, + .Init.WordLength = UART_WORDLENGTH_8B, + .Init.StopBits = UART_STOPBITS_1, + .Init.Parity = UART_PARITY_NONE, + .Init.HwFlowCtl = UART_HWCONTROL_NONE, + .Init.Mode = UART_MODE_TX_RX, + .Init.OverSampling = UART_OVERSAMPLING_16, + .AdvancedInit.AdvFeatureInit = UART_ADVFEATURE_NO_INIT + }; + HAL_UART_Init(&UartHandle); + #endif + + // USB Pins TODO double check USB clock and pin setup + // Configure USB DM and DP pins. This is optional, and maintained only for user guidance. + GPIO_InitStruct.Pin = (GPIO_PIN_11 | GPIO_PIN_12); + GPIO_InitStruct.Mode = GPIO_MODE_INPUT; + GPIO_InitStruct.Pull = GPIO_NOPULL; + GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_HIGH; + HAL_GPIO_Init(GPIOA, &GPIO_InitStruct); + + /* Peripheral clock enable */ + __HAL_RCC_USB_CLK_ENABLE(); + + /* Enable VDDUSB */ + HAL_PWREx_EnableVddUSB(); +} + +//--------------------------------------------------------------------+ +// Board porting API +//--------------------------------------------------------------------+ + +void board_led_write(bool state) { + GPIO_PinState pin_state = (GPIO_PinState) (state ? LED_STATE_ON : (1 - LED_STATE_ON)); + HAL_GPIO_WritePin(LED_PORT, LED_PIN, pin_state); +} + +uint32_t board_button_read(void) { + return BUTTON_STATE_ACTIVE == HAL_GPIO_ReadPin(BUTTON_PORT, BUTTON_PIN); +} + +size_t board_get_unique_id(uint8_t id[], size_t max_len) { + (void) max_len; + volatile uint32_t* stm32_uuid = (volatile uint32_t*) UID_BASE; + uint32_t* id32 = (uint32_t*) (uintptr_t) id; + uint8_t const len = 12; + + id32[0] = stm32_uuid[0]; + id32[1] = stm32_uuid[1]; + id32[2] = stm32_uuid[2]; + + return len; +} + +int board_uart_read(uint8_t* buf, int len) { + (void) buf; + (void) len; + return 0; +} + +int board_uart_write(void const* buf, int len) { + #ifdef UART_DEV + HAL_UART_Transmit(&UartHandle, (uint8_t*) (uintptr_t) buf, len, 0xffff); + return len; + #else + (void) buf; + (void) len; + (void) UartHandle; + return 0; + #endif +} + +#if CFG_TUSB_OS == OPT_OS_NONE +volatile uint32_t system_ticks = 0; + +void SysTick_Handler(void) { + system_ticks++; + HAL_IncTick(); +} + +uint32_t board_millis(void) { + return system_ticks; +} + +#endif + +void HardFault_Handler(void) { + __asm("BKPT #0\n"); +} + +// Required by __libc_init_array in startup code if we are compiling using +// -nostdlib/-nostartfiles. +void _init(void) { + +} diff --git a/hw/bsp/stm32h5/family.cmake b/hw/bsp/stm32h5/family.cmake new file mode 100644 index 000000000..e5850f38d --- /dev/null +++ b/hw/bsp/stm32h5/family.cmake @@ -0,0 +1,116 @@ +include_guard() + +if (NOT BOARD) + message(FATAL_ERROR "BOARD not specified") +endif () + +set(ST_FAMILY h5) +set(ST_PREFIX stm32${ST_FAMILY}xx) + +set(ST_HAL_DRIVER ${TOP}/hw/mcu/st/stm32${ST_FAMILY}xx_hal_driver) +set(ST_CMSIS ${TOP}/hw/mcu/st/cmsis_device_${ST_FAMILY}) +set(CMSIS_5 ${TOP}/lib/CMSIS_5) + +# include board specific +include(${CMAKE_CURRENT_LIST_DIR}/boards/${BOARD}/board.cmake) + +# toolchain set up +set(CMAKE_SYSTEM_PROCESSOR cortex-m33 CACHE INTERNAL "System Processor") +set(CMAKE_TOOLCHAIN_FILE ${TOP}/examples/build_system/cmake/toolchain/arm_${TOOLCHAIN}.cmake) + +set(FAMILY_MCUS STM32H5 CACHE INTERNAL "") + + +#------------------------------------ +# BOARD_TARGET +#------------------------------------ +# only need to be built ONCE for all examples +function(add_board_target BOARD_TARGET) + if (TARGET ${BOARD_TARGET}) + return() + endif () + + # Startup & Linker script + set(STARTUP_FILE_GNU ${ST_CMSIS}/Source/Templates/gcc/startup_${MCU_VARIANT}.s) + set(STARTUP_FILE_IAR ${ST_CMSIS}/Source/Templates/iar/startup_${MCU_VARIANT}.s) + set(LD_FILE_IAR ${ST_CMSIS}/Source/Templates/iar/linker/${MCU_VARIANT}_flash.icf) + + string(REPLACE "stm32h" "STM32H" MCU_VARIANT_UPPER ${MCU_VARIANT}) + set(LD_FILE_GNU ${ST_CMSIS}/Source/Templates/gcc/linker/${MCU_VARIANT_UPPER}_FLASH.ld) + + add_library(${BOARD_TARGET} STATIC + ${ST_CMSIS}/Source/Templates/system_${ST_PREFIX}.c + ${ST_HAL_DRIVER}/Src/${ST_PREFIX}_hal.c + ${ST_HAL_DRIVER}/Src/${ST_PREFIX}_hal_cortex.c + ${ST_HAL_DRIVER}/Src/${ST_PREFIX}_hal_gpio.c + ${ST_HAL_DRIVER}/Src/${ST_PREFIX}_hal_pwr.c + ${ST_HAL_DRIVER}/Src/${ST_PREFIX}_hal_pwr_ex.c + ${ST_HAL_DRIVER}/Src/${ST_PREFIX}_hal_rcc.c + ${ST_HAL_DRIVER}/Src/${ST_PREFIX}_hal_rcc_ex.c + ${ST_HAL_DRIVER}/Src/${ST_PREFIX}_hal_uart.c + ${ST_HAL_DRIVER}/Src/${ST_PREFIX}_hal_uart_ex.c + ${ST_HAL_DRIVER}/Src/${ST_PREFIX}_hal_dma.c + ${STARTUP_FILE_${CMAKE_C_COMPILER_ID}} + ) + target_include_directories(${BOARD_TARGET} PUBLIC + ${CMAKE_CURRENT_FUNCTION_LIST_DIR} + ${CMSIS_5}/CMSIS/Core/Include + ${ST_CMSIS}/Include + ${ST_HAL_DRIVER}/Inc + ) + + update_board(${BOARD_TARGET}) + + if (CMAKE_C_COMPILER_ID STREQUAL "GNU") + target_link_options(${BOARD_TARGET} PUBLIC + "LINKER:--script=${LD_FILE_GNU}" + -nostartfiles + # nanolib + --specs=nosys.specs --specs=nano.specs + ) + elseif (CMAKE_C_COMPILER_ID STREQUAL "IAR") + target_link_options(${BOARD_TARGET} PUBLIC + "LINKER:--config=${LD_FILE_IAR}" + ) + endif () +endfunction() + + +#------------------------------------ +# Functions +#------------------------------------ +function(family_configure_example TARGET RTOS) + family_configure_common(${TARGET} ${RTOS}) + + # Board target + add_board_target(board_${BOARD}) + + #---------- Port Specific ---------- + # These files are built for each example since it depends on example's tusb_config.h + target_sources(${TARGET} PUBLIC + # BSP + ${CMAKE_CURRENT_FUNCTION_LIST_DIR}/family.c + ${CMAKE_CURRENT_FUNCTION_LIST_DIR}/../board.c + ) + target_include_directories(${TARGET} PUBLIC + # family, hw, board + ${CMAKE_CURRENT_FUNCTION_LIST_DIR} + ${CMAKE_CURRENT_FUNCTION_LIST_DIR}/../../ + ${CMAKE_CURRENT_FUNCTION_LIST_DIR}/boards/${BOARD} + ) + + # Add TinyUSB target and port source + family_add_tinyusb(${TARGET} OPT_MCU_STM32H5 ${RTOS}) + target_sources(${TARGET}-tinyusb PUBLIC + ${TOP}/src/portable/st/stm32_fsdev/dcd_stm32_fsdev.c + ${TOP}/src/portable/st/typec/typec_stm32.c + ) + target_link_libraries(${TARGET}-tinyusb PUBLIC board_${BOARD}) + + # Link dependencies + target_link_libraries(${TARGET} PUBLIC board_${BOARD} ${TARGET}-tinyusb) + + # Flashing + family_flash_stlink(${TARGET}) + family_flash_jlink(${TARGET}) +endfunction() diff --git a/hw/bsp/stm32h5/family.mk b/hw/bsp/stm32h5/family.mk new file mode 100644 index 000000000..270b1c465 --- /dev/null +++ b/hw/bsp/stm32h5/family.mk @@ -0,0 +1,62 @@ +ST_FAMILY = h5 +ST_CMSIS = hw/mcu/st/cmsis_device_$(ST_FAMILY) +ST_HAL_DRIVER = hw/mcu/st/stm32$(ST_FAMILY)xx_hal_driver + +include $(TOP)/$(BOARD_PATH)/board.mk +CPU_CORE ?= cortex-m33 + +MCU_VARIANT_UPPER = $(subst stm32h,STM32H,$(MCU_VARIANT)) + +# -------------- +# Compiler Flags +# -------------- +CFLAGS += \ + -DCFG_TUSB_MCU=OPT_MCU_STM32H5 + +# GCC Flags +CFLAGS_GCC += \ + -flto \ + -nostdlib -nostartfiles \ + +# suppress warning caused by vendor mcu driver +CFLAGS_GCC += \ + -Wno-error=cast-align \ + -Wno-error=undef \ + -Wno-error=unused-parameter \ + +LDFLAGS_GCC += -specs=nosys.specs -specs=nano.specs + +# ----------------- +# Sources & Include +# ----------------- + +SRC_C += \ + src/portable/st/stm32_fsdev/dcd_stm32_fsdev.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_pwr.c \ + $(ST_HAL_DRIVER)/Src/stm32$(ST_FAMILY)xx_hal_pwr_ex.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_uart.c \ + $(ST_HAL_DRIVER)/Src/stm32$(ST_FAMILY)xx_hal_uart_ex.c \ + $(ST_HAL_DRIVER)/Src/stm32$(ST_FAMILY)xx_hal_gpio.c \ + $(ST_HAL_DRIVER)/Src/stm32$(ST_FAMILY)xx_hal_dma.c + +INC += \ + $(TOP)/$(BOARD_PATH) \ + $(TOP)/lib/CMSIS_5/CMSIS/Core/Include \ + $(TOP)/$(ST_CMSIS)/Include \ + $(TOP)/$(ST_HAL_DRIVER)/Inc + +# Startup +SRC_S_GCC += $(ST_CMSIS)/Source/Templates/gcc/startup_$(MCU_VARIANT).s +SRC_S_IAR += $(ST_CMSIS)/Source/Templates/iar/startup_$(MCU_VARIANT).s + +# Linker +LD_FILE_IAR = $(ST_CMSIS)/Source/Templates/iar/linker/$(MCU_VARIANT)_flash.icf +LD_FILE_GCC = $(ST_CMSIS)/Source/Templates/gcc/linker/$(MCU_VARIANT_UPPER)_FLASH.ld + +# flash target using on-board stlink +flash: flash-stlink diff --git a/hw/bsp/stm32h5/stm32h5xx_hal_conf.h b/hw/bsp/stm32h5/stm32h5xx_hal_conf.h new file mode 100644 index 000000000..d017bb06b --- /dev/null +++ b/hw/bsp/stm32h5/stm32h5xx_hal_conf.h @@ -0,0 +1,355 @@ +/* USER CODE BEGIN Header */ +/** + ****************************************************************************** + * @file stm32h5xx_hal_conf.h + * @author MCD Application Team + * @brief HAL configuration file. + ****************************************************************************** + * @attention + * + * Copyright (c) 2018-2021 STMicroelectronics. + * All rights reserved. + * + * This software is licensed under terms that can be found in the LICENSE file + * in the root directory of this software component. + * If no LICENSE file comes with this software, it is provided AS-IS. + * + ****************************************************************************** + */ +/* USER CODE END Header */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef STM32h5xx_HAL_CONF_H +#define STM32h5xx_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_CRC_MODULE_ENABLED */ +/* #define HAL_CRYP_MODULE_ENABLED */ +/* #define HAL_DAC_MODULE_ENABLED */ +/* #define HAL_EXTI_MODULE_ENABLED */ +/* #define HAL_FDCAN_MODULE_ENABLED */ +/* #define HAL_HCD_MODULE_ENABLED */ +/* #define HAL_I2C_MODULE_ENABLED */ +/* #define HAL_I2S_MODULE_ENABLED */ +/* #define HAL_IWDG_MODULE_ENABLED */ +/* #define HAL_IRDA_MODULE_ENABLED */ +/* #define HAL_LPTIM_MODULE_ENABLED */ +/* #define HAL_PCD_MODULE_ENABLED */ +/* #define HAL_RNG_MODULE_ENABLED */ +/* #define HAL_RTC_MODULE_ENABLED */ +/* #define HAL_SMARTCARD_MODULE_ENABLED */ +/* #define HAL_SMBUS_MODULE_ENABLED */ +/* #define HAL_SPI_MODULE_ENABLED */ +/* #define HAL_TIM_MODULE_ENABLED */ +/* #define HAL_USART_MODULE_ENABLED */ +/* #define HAL_WWDG_MODULE_ENABLED */ +#define HAL_GPIO_MODULE_ENABLED +#define HAL_EXTI_MODULE_ENABLED +#define HAL_DMA_MODULE_ENABLED +#define HAL_RCC_MODULE_ENABLED +#define HAL_FLASH_MODULE_ENABLED +#define HAL_PWR_MODULE_ENABLED +#define HAL_CORTEX_MODULE_ENABLED +#define HAL_UART_MODULE_ENABLED + +/* ########################## Register Callbacks selection ############################## */ +/** + * @brief This is the list of modules where register callback can be used + */ +#define USE_HAL_ADC_REGISTER_CALLBACKS 0u +#define USE_HAL_CEC_REGISTER_CALLBACKS 0u +#define USE_HAL_COMP_REGISTER_CALLBACKS 0u +#define USE_HAL_CRYP_REGISTER_CALLBACKS 0u +#define USE_HAL_DAC_REGISTER_CALLBACKS 0u +#define USE_HAL_FDCAN_REGISTER_CALLBACKS 0u +#define USE_HAL_HCD_REGISTER_CALLBACKS 0u +#define USE_HAL_I2C_REGISTER_CALLBACKS 0u +#define USE_HAL_I2S_REGISTER_CALLBACKS 0u +#define USE_HAL_IRDA_REGISTER_CALLBACKS 0u +#define USE_HAL_LPTIM_REGISTER_CALLBACKS 0u +#define USE_HAL_PCD_REGISTER_CALLBACKS 0u +#define USE_HAL_RNG_REGISTER_CALLBACKS 0u +#define USE_HAL_RTC_REGISTER_CALLBACKS 0u +#define USE_HAL_SMBUS_REGISTER_CALLBACKS 0u +#define USE_HAL_SPI_REGISTER_CALLBACKS 0u +#define USE_HAL_TIM_REGISTER_CALLBACKS 0u +#define USE_HAL_UART_REGISTER_CALLBACKS 0u +#define USE_HAL_USART_REGISTER_CALLBACKS 0u +#define USE_HAL_WWDG_REGISTER_CALLBACKS 0u + + +/** + * @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 25000000U /*!< Value of the External oscillator in Hz */ +#endif /* HSE_VALUE */ + +#if !defined (HSE_STARTUP_TIMEOUT) +#define HSE_STARTUP_TIMEOUT 100U /*!< Time out for HSE start up, in ms */ +#endif /* HSE_STARTUP_TIMEOUT */ + +/** + * @brief Internal Core Speed oscillator (CSI) default value. + * This value is the default CSI range value after Reset. + */ +#if !defined (CSI_VALUE) +#define CSI_VALUE 4000000UL /*!< 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 64000000UL /*!< Value of the Internal oscillator in Hz*/ +#endif /* HSI_VALUE */ + +/** + * @brief Internal High Speed oscillator (HSI48) value for USB FS, SDMMC and RNG. + * This internal oscillator is mainly dedicated to provide a high precision clock to + * the USB peripheral by means of a special Clock Recovery System (CRS) circuitry. + * When the CRS is not used, the HSI48 RC oscillator runs on it default frequency + * which is subject to manufacturing process variations. + */ +#if !defined (HSI48_VALUE) +#define HSI48_VALUE 48000000UL /*!< Value of the Internal High Speed oscillator for USB FS/SDMMC/RNG in Hz. + The real value my vary depending on manufacturing process variations.*/ +#endif /* HSI48_VALUE */ + +/** + * @brief Internal Low Speed oscillator (LSI) value. + */ +#if !defined (LSI_VALUE) +#define LSI_VALUE 32000UL /*!< LSI Typical Value in Hz*/ +#endif /* LSI_VALUE */ /*!< Value of the Internal Low Speed oscillator in Hz +The real value may vary depending on the variations +in voltage and temperature.*/ + +#if !defined (LSI_STARTUP_TIME) +#define LSI_STARTUP_TIME 130UL /*!< Time out for LSI start up, in ms */ +#endif /* LSI_STARTUP_TIME */ + +/** + * @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 32768UL /*!< Value of the External oscillator in Hz*/ +#endif /* LSE_VALUE */ + +#if !defined (LSE_STARTUP_TIMEOUT) +#define LSE_STARTUP_TIMEOUT 5000UL /*!< Time out for LSE start up, in ms */ +#endif /* LSE_STARTUP_TIMEOUT */ + +/** + * @brief External clock source for SPI/SAI peripheral + * This value is used by the SPI/SAI HAL module to compute the SPI/SAI clock source + * frequency, this source is inserted directly through I2S_CKIN pad. + + */ +#if !defined (EXTERNAL_CLOCK_VALUE) +#define EXTERNAL_CLOCK_VALUE 12288000UL /*!< 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 3300UL /*!< Value of VDD in mv */ +#define TICK_INT_PRIORITY (15UL) /*!< tick interrupt priority (lowest by default) */ +#define USE_RTOS 0U +#define PREFETCH_ENABLE 0U /*!< Enable prefetch */ + + + +/* ################## SPI peripheral configuration ########################## */ + +/* CRC FEATURE: Use to activate CRC feature inside HAL SPI Driver +* Activated: CRC code is present inside driver +* Deactivated: CRC code cleaned from driver +*/ + +#define USE_SPI_CRC 0U + +/* ################## CRYP peripheral configuration ########################## */ + +#define USE_HAL_CRYP_SUSPEND_RESUME 1U + +/* ########################## Assert Selection ############################## */ +/** + * @brief Uncomment the line below to expanse the "assert_param" macro in the + * HAL drivers code + */ +/* #define USE_FULL_ASSERT 1U */ + +/* Includes ------------------------------------------------------------------*/ +/** + * @brief Include modules header file + */ + +#ifdef HAL_RCC_MODULE_ENABLED +#include "stm32h5xx_hal_rcc.h" +#endif /* HAL_RCC_MODULE_ENABLED */ + +#ifdef HAL_GPIO_MODULE_ENABLED +#include "stm32h5xx_hal_gpio.h" +#endif /* HAL_GPIO_MODULE_ENABLED */ + +#ifdef HAL_DMA_MODULE_ENABLED +#include "stm32h5xx_hal_dma.h" +#endif /* HAL_DMA_MODULE_ENABLED */ + +#ifdef HAL_CORTEX_MODULE_ENABLED +#include "stm32h5xx_hal_cortex.h" +#endif /* HAL_CORTEX_MODULE_ENABLED */ + +#ifdef HAL_ADC_MODULE_ENABLED +#include "stm32h5xx_hal_adc.h" +#include "stm32h5xx_hal_adc_ex.h" +#endif /* HAL_ADC_MODULE_ENABLED */ + +#ifdef HAL_CEC_MODULE_ENABLED +#include "stm32h5xx_hal_cec.h" +#endif /* HAL_CEC_MODULE_ENABLED */ + +#ifdef HAL_COMP_MODULE_ENABLED +#include "stm32h5xx_hal_comp.h" +#endif /* HAL_COMP_MODULE_ENABLED */ + +#ifdef HAL_CRC_MODULE_ENABLED +#include "stm32h5xx_hal_crc.h" +#endif /* HAL_CRC_MODULE_ENABLED */ + +#ifdef HAL_CRYP_MODULE_ENABLED +#include "stm32h5xx_hal_cryp.h" +#endif /* HAL_CRYP_MODULE_ENABLED */ + +#ifdef HAL_DAC_MODULE_ENABLED +#include "stm32h5xx_hal_dac.h" +#endif /* HAL_DAC_MODULE_ENABLED */ + +#ifdef HAL_EXTI_MODULE_ENABLED +#include "stm32h5xx_hal_exti.h" +#endif /* HAL_EXTI_MODULE_ENABLED */ + +#ifdef HAL_FLASH_MODULE_ENABLED +#include "stm32h5xx_hal_flash.h" +#endif /* HAL_FLASH_MODULE_ENABLED */ + +#ifdef HAL_FDCAN_MODULE_ENABLED +#include "stm32h5xx_hal_fdcan.h" +#endif /* HAL_FDCAN_MODULE_ENABLED */ + +#ifdef HAL_HCD_MODULE_ENABLED +#include "stm32h5xx_hal_hcd.h" +#endif /* HAL_HCD_MODULE_ENABLED */ + +#ifdef HAL_I2C_MODULE_ENABLED +#include "stm32h5xx_hal_i2c.h" +#endif /* HAL_I2C_MODULE_ENABLED */ + +#ifdef HAL_I2S_MODULE_ENABLED +#include "stm32h5xx_hal_i2s.h" +#endif /* HAL_I2S_MODULE_ENABLED */ + +#ifdef HAL_IRDA_MODULE_ENABLED +#include "stm32h5xx_hal_irda.h" +#endif /* HAL_IRDA_MODULE_ENABLED */ + +#ifdef HAL_IWDG_MODULE_ENABLED +#include "stm32h5xx_hal_iwdg.h" +#endif /* HAL_IWDG_MODULE_ENABLED */ + +#ifdef HAL_LPTIM_MODULE_ENABLED +#include "stm32h5xx_hal_lptim.h" +#endif /* HAL_LPTIM_MODULE_ENABLED */ + +#ifdef HAL_PCD_MODULE_ENABLED +#include "stm32h5xx_hal_pcd.h" +#endif /* HAL_PCD_MODULE_ENABLED */ + +#ifdef HAL_PWR_MODULE_ENABLED +#include "stm32h5xx_hal_pwr.h" +#endif /* HAL_PWR_MODULE_ENABLED */ + +#ifdef HAL_RNG_MODULE_ENABLED +#include "stm32h5xx_hal_rng.h" +#endif /* HAL_RNG_MODULE_ENABLED */ + +#ifdef HAL_RTC_MODULE_ENABLED +#include "stm32h5xx_hal_rtc.h" +#endif /* HAL_RTC_MODULE_ENABLED */ + +#ifdef HAL_SMARTCARD_MODULE_ENABLED +#include "stm32h5xx_hal_smartcard.h" +#endif /* HAL_SMARTCARD_MODULE_ENABLED */ + +#ifdef HAL_SMBUS_MODULE_ENABLED +#include "stm32h5xx_hal_smbus.h" +#endif /* HAL_SMBUS_MODULE_ENABLED */ + +#ifdef HAL_SPI_MODULE_ENABLED +#include "stm32h5xx_hal_spi.h" +#endif /* HAL_SPI_MODULE_ENABLED */ + +#ifdef HAL_TIM_MODULE_ENABLED +#include "stm32h5xx_hal_tim.h" +#endif /* HAL_TIM_MODULE_ENABLED */ + +#ifdef HAL_UART_MODULE_ENABLED +#include "stm32h5xx_hal_uart.h" +#endif /* HAL_UART_MODULE_ENABLED */ + +#ifdef HAL_USART_MODULE_ENABLED +#include "stm32h5xx_hal_usart.h" +#endif /* HAL_USART_MODULE_ENABLED */ + +#ifdef HAL_WWDG_MODULE_ENABLED +#include "stm32h5xx_hal_wwdg.h" +#endif /* HAL_WWDG_MODULE_ENABLED */ + +/* Exported macro ------------------------------------------------------------*/ +#ifdef USE_FULL_ASSERT +/** + * @brief The assert_param macro is used for functions 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)0U : assert_failed((uint8_t *)__FILE__, __LINE__)) +/* Exported functions ------------------------------------------------------- */ +void assert_failed(uint8_t *file, uint32_t line); +#else +#define assert_param(expr) ((void)0U) +#endif /* USE_FULL_ASSERT */ + +#ifdef __cplusplus +} +#endif + +#endif /* STM32h5xx_HAL_CONF_H */ diff --git a/src/common/tusb_mcu.h b/src/common/tusb_mcu.h index 6fab190ea..e589c4c86 100644 --- a/src/common/tusb_mcu.h +++ b/src/common/tusb_mcu.h @@ -210,6 +210,11 @@ #define TUP_DCD_ENDPOINT_MAX 9 +#elif TU_CHECK_MCU(OPT_MCU_STM32H5) + #define TUP_USBIP_FSDEV + #define TUP_USBIP_FSDEV_STM32 + #define TUP_DCD_ENDPOINT_MAX 8 + #elif TU_CHECK_MCU(OPT_MCU_STM32G4) // Device controller #define TUP_USBIP_FSDEV diff --git a/src/portable/st/stm32_fsdev/dcd_stm32_fsdev.c b/src/portable/st/stm32_fsdev/dcd_stm32_fsdev.c index 14cabaf8d..21cd3da26 100644 --- a/src/portable/st/stm32_fsdev/dcd_stm32_fsdev.c +++ b/src/portable/st/stm32_fsdev/dcd_stm32_fsdev.c @@ -242,7 +242,7 @@ void dcd_init (uint8_t rhport) } USB->CNTR = 0; // Enable USB -#ifndef STM32G0 // BTABLE register does not exist any more on STM32G0, it is fixed to USB SRAM base address +#if !defined(STM32G0) && !defined(STM32H5) // BTABLE register does not exist any more on STM32G0, it is fixed to USB SRAM base address USB->BTABLE = DCD_STM32_BTABLE_BASE; #endif USB->ISTR = 0; // Clear pending interrupts @@ -358,6 +358,9 @@ void dcd_int_enable (uint8_t rhport) NVIC_EnableIRQ(USB_UCPD1_2_IRQn); #endif +#elif CFG_TUSB_MCU == OPT_MCU_STM32H5 + NVIC_EnableIRQ(USB_DRD_FS_IRQn); + #elif CFG_TUSB_MCU == OPT_MCU_STM32WB NVIC_EnableIRQ(USB_HP_IRQn); NVIC_EnableIRQ(USB_LP_IRQn); @@ -415,6 +418,9 @@ void dcd_int_disable(uint8_t rhport) NVIC_DisableIRQ(USB_UCPD1_2_IRQn); #endif +#elif CFG_TUSB_MCU == OPT_MCU_STM32H5 + NVIC_DisableIRQ(USB_DRD_FS_IRQn); + #elif CFG_TUSB_MCU == OPT_MCU_STM32WB NVIC_DisableIRQ(USB_HP_IRQn); NVIC_DisableIRQ(USB_LP_IRQn); diff --git a/src/portable/st/stm32_fsdev/dcd_stm32_fsdev_pvt_st.h b/src/portable/st/stm32_fsdev/dcd_stm32_fsdev_pvt_st.h index e6649de5a..b71e4f498 100644 --- a/src/portable/st/stm32_fsdev/dcd_stm32_fsdev_pvt_st.h +++ b/src/portable/st/stm32_fsdev/dcd_stm32_fsdev_pvt_st.h @@ -110,6 +110,35 @@ #define USB_CNTR_LPMODE USB_CNTR_SUSPRDY #define USB_CNTR_FSUSP USB_CNTR_SUSPEN +#elif CFG_TUSB_MCU == OPT_MCU_STM32H5 + #include "stm32h5xx.h" + #define PMA_32BIT_ACCESS + #define PMA_LENGTH (2048u) + #undef USB_PMAADDR + #define USB_PMAADDR USB_DRD_PMAADDR + #define USB_TypeDef USB_DRD_TypeDef + #define EP0R CHEP0R + #define USB_EP_CTR_RX USB_EP_VTRX + #define USB_EP_CTR_TX USB_EP_VTTX + #define USB_EP_T_FIELD USB_CHEP_UTYPE + #define USB_EPREG_MASK USB_CHEP_REG_MASK + #define USB_EPTX_DTOGMASK USB_CHEP_TX_DTOGMASK + #define USB_EPRX_DTOGMASK USB_CHEP_RX_DTOGMASK + #define USB_EPTX_DTOG1 USB_CHEP_TX_DTOG1 + #define USB_EPTX_DTOG2 USB_CHEP_TX_DTOG2 + #define USB_EPRX_DTOG1 USB_CHEP_RX_DTOG1 + #define USB_EPRX_DTOG2 USB_CHEP_RX_DTOG2 + #define USB_EPRX_STAT USB_CH_RX_VALID + #define USB_EPKIND_MASK USB_EP_KIND_MASK + #define USB USB_DRD_FS + #define USB_CNTR_FRES USB_CNTR_USBRST + #define USB_CNTR_RESUME USB_CNTR_L2RES + #define USB_ISTR_EP_ID USB_ISTR_IDN + #define USB_EPADDR_FIELD USB_CHEP_ADDR + #define USB_CNTR_LPMODE USB_CNTR_SUSPRDY + #define USB_CNTR_FSUSP USB_CNTR_SUSPEN + + #elif CFG_TUSB_MCU == OPT_MCU_STM32WB #include "stm32wbxx.h" #define PMA_LENGTH (1024u) diff --git a/src/tusb_option.h b/src/tusb_option.h index 4d2aa137c..a76281c0c 100644 --- a/src/tusb_option.h +++ b/src/tusb_option.h @@ -86,6 +86,7 @@ #define OPT_MCU_STM32WB 312 ///< ST WB #define OPT_MCU_STM32U5 313 ///< ST U5 #define OPT_MCU_STM32L5 314 ///< ST L5 +#define OPT_MCU_STM32H5 315 ///< ST H5 // Sony #define OPT_MCU_CXD56 400 ///< SONY CXD56 diff --git a/tools/get_deps.py b/tools/get_deps.py index 79c272c07..86ffdc5c7 100644 --- a/tools/get_deps.py +++ b/tools/get_deps.py @@ -95,6 +95,9 @@ deps_optional = { 'hw/mcu/st/cmsis_device_h7': ['https://github.com/STMicroelectronics/cmsis_device_h7.git', '60dc2c913203dc8629dc233d4384dcc41c91e77f', 'stm32h7'], + 'hw/mcu/st/cmsis_device_h5': ['https://github.com/STMicroelectronics/cmsis_device_h5.git', + '62b2cb0fbfe10c5791ee469bbde7b397c2fea8f5', + 'stm32h5'], 'hw/mcu/st/cmsis_device_l0': ['https://github.com/STMicroelectronics/cmsis_device_l0.git', '06748ca1f93827befdb8b794402320d94d02004f', 'stm32l0'], @@ -140,6 +143,9 @@ deps_optional = { 'hw/mcu/st/stm32h7xx_hal_driver': ['https://github.com/STMicroelectronics/stm32h7xx_hal_driver.git', 'd8461b980b59b1625207d8c4f2ce0a9c2a7a3b04', 'stm32h7'], + 'hw/mcu/st/stm32h5xx_hal_driver': ['https://github.com/STMicroelectronics/stm32h5xx_hal_driver.git', + '2cf77de584196d619cec1b4586c3b9e2820a254e', + 'stm32h5'], 'hw/mcu/st/stm32l0xx_hal_driver': ['https://github.com/STMicroelectronics/stm32l0xx_hal_driver.git', 'fbdacaf6f8c82a4e1eb9bd74ba650b491e97e17b', 'stm32l0'], @@ -170,7 +176,7 @@ deps_optional = { 'lib/CMSIS_5': ['https://github.com/ARM-software/CMSIS_5.git', '20285262657d1b482d132d20d755c8c330d55c1f', 'imxrt kinetis_k32l2 kinetis_kl lpc51 lpc54 lpc55 mcx mm32 msp432e4 nrf ra saml2x' - 'stm32f0 stm32f1 stm32f2 stm32f3 stm32f4 stm32f7 stm32g0 stm32g4 ' + 'stm32f0 stm32f1 stm32f2 stm32f3 stm32f4 stm32f7 stm32g0 stm32g4 stm32h5' 'stm32h7 stm32l0 stm32l1 stm32l4 stm32l5 stm32u5 stm32wb'], 'lib/sct_neopixel': ['https://github.com/gsteiert/sct_neopixel.git', 'e73e04ca63495672d955f9268e003cffe168fcd8', @@ -204,16 +210,16 @@ def get_a_dep(d): # Init git deps if not existed if not p.exists(): p.mkdir(parents=True) - run_cmd(f"git -C {p} init") - run_cmd(f"git -C {p} remote add origin {url}") + run_cmd(f"{git_cmd} init") + run_cmd(f"{git_cmd} remote add origin {url}") # Check if commit is already fetched - result = run_cmd(f"git -C {p} rev-parse HEAD") + result = run_cmd(f"{git_cmd} rev-parse HEAD") head = result.stdout.decode("utf-8").splitlines()[0] - run_cmd(f"git -C {p} reset --hard") + run_cmd(f"{git_cmd} reset --hard") if commit != head: - run_cmd(f"git -C {p} fetch --depth 1 origin {commit}") - run_cmd(f"git -C {p} checkout FETCH_HEAD") + run_cmd(f"{git_cmd} fetch --depth 1 origin {commit}") + run_cmd(f"{git_cmd} checkout FETCH_HEAD") return 0