diff --git a/.github/workflows/cmake_arm.yml b/.github/workflows/cmake_arm.yml index ccca0c9be..2e74c304c 100644 --- a/.github/workflows/cmake_arm.yml +++ b/.github/workflows/cmake_arm.yml @@ -37,6 +37,7 @@ jobs: - 'mcx' - 'imxrt' - 'rp2040' + - 'stm32g0' steps: - name: Setup Python uses: actions/setup-python@v4 diff --git a/README.rst b/README.rst index ef441a596..425cfa0e3 100644 --- a/README.rst +++ b/README.rst @@ -55,7 +55,7 @@ The stack supports the following MCUs: - **Silabs:** EFM32GG - **Sony:** CXD56 -- **ST:** STM32 series: F0, F1, F2, F3, F4, F7, H7, G4, L0, L1, L4, L4+, WB +- **ST:** STM32 series: F0, F1, F2, F3, F4, F7, H7, G0, G4, L0, L1, L4, L4+, WB - **TI:** MSP430, MSP432E4, TM4C123 - **ValentyUSB:** eptri - **WCH:** CH32V307 diff --git a/hw/bsp/board_mcu.h b/hw/bsp/board_mcu.h index 35210dbae..edae4c645 100644 --- a/hw/bsp/board_mcu.h +++ b/hw/bsp/board_mcu.h @@ -101,6 +101,9 @@ #elif CFG_TUSB_MCU == OPT_MCU_STM32U5 #include "stm32u5xx.h" +#elif CFG_TUSB_MCU == OPT_MCU_STM32G0 + #include "stm32g0xx.h" + #elif CFG_TUSB_MCU == OPT_MCU_CXD56 // no header needed diff --git a/hw/bsp/family_support.cmake b/hw/bsp/family_support.cmake index 69290ceec..d9b8bbbe9 100644 --- a/hw/bsp/family_support.cmake +++ b/hw/bsp/family_support.cmake @@ -189,6 +189,19 @@ exit" endfunction() +# Add flash stlink target +function(family_flash_stlink TARGET) + if (NOT DEFINED STM32_PROGRAMMER_CLI) + set(STM32_PROGRAMMER_CLI STM32_Programmer_CLI) + endif () + + add_custom_target(${TARGET}-stlink + DEPENDS ${TARGET} + COMMAND ${STM32_PROGRAMMER_CLI} --connect port=swd --write $ --go + ) +endfunction() + + # Add flash pycod target function(family_flash_pyocd TARGET) if (NOT DEFINED PYOC) diff --git a/hw/bsp/lpc18/family.cmake b/hw/bsp/lpc18/family.cmake index 1bfc63d21..515348e10 100644 --- a/hw/bsp/lpc18/family.cmake +++ b/hw/bsp/lpc18/family.cmake @@ -46,14 +46,9 @@ if (NOT TARGET ${BOARD_TARGET}) ) update_board(${BOARD_TARGET}) - if (NOT DEFINED LD_FILE_${TOOLCHAIN}) - MESSAGE(FATAL_ERROR "LD_FILE_${TOOLCHAIN} not defined") - endif () - if (TOOLCHAIN STREQUAL "gcc") target_link_options(${BOARD_TARGET} PUBLIC "LINKER:--script=${LD_FILE_gcc}" - "LINKER:-Map=$>,$,$>${CMAKE_EXECUTABLE_SUFFIX}.map" # nanolib --specs=nosys.specs --specs=nano.specs diff --git a/hw/bsp/stm32g0/FreeRTOSConfig/FreeRTOSConfig.h b/hw/bsp/stm32g0/FreeRTOSConfig/FreeRTOSConfig.h new file mode 100644 index 000000000..1758efcf2 --- /dev/null +++ b/hw/bsp/stm32g0/FreeRTOSConfig/FreeRTOSConfig.h @@ -0,0 +1,166 @@ +/* + * 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. + *----------------------------------------------------------*/ + +// IAR assembler have limited preprocessor support and it only need following macros: +#ifndef __IASMARM__ +// FIXME cause redundant-decls warnings +extern uint32_t SystemCoreClock; +#endif + +/* Cortex M23/M33 port configuration. */ +#define configENABLE_MPU 0 +#define configENABLE_FPU 0 +#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 2 +#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 0 +#define configSUPPORT_DYNAMIC_ALLOCATION 1 + +/* 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 2 + +/* The lowest interrupt priority that can be used in a call to a "set priority" function. */ +#define configLIBRARY_LOWEST_INTERRUPT_PRIORITY ((1<
© COPYRIGHT(c) 2019 STMicroelectronics
+** +** Redistribution and use in source and binary forms, with or without modification, +** are permitted provided that the following conditions are met: +** 1. Redistributions of source code must retain the above copyright notice, +** this list of conditions and the following disclaimer. +** 2. Redistributions in binary form must reproduce the above copyright notice, +** this list of conditions and the following disclaimer in the documentation +** and/or other materials provided with the distribution. +** 3. Neither the name of STMicroelectronics nor the names of its contributors +** may be used to endorse or promote products derived from this software +** without specific prior written permission. +** +** THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +** AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +** IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE +** DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE +** FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL +** DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR +** SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +** CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, +** OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE +** OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +** +***************************************************************************** +*/ + +/* Entry Point */ +ENTRY(Reset_Handler) + +/* Highest address of the user mode stack */ +_estack = ORIGIN(RAM) + LENGTH(RAM); /* end of RAM */ +/* Generate a link error if heap and stack don't fit into RAM */ +_Min_Heap_Size = 0x200; /* required amount of heap */ +_Min_Stack_Size = 0x400; /* required amount of stack */ + +/* Specify the memory areas */ +MEMORY +{ +RAM (xrw) : ORIGIN = 0x20000000, LENGTH = 144K +FLASH (rx) : ORIGIN = 0x8000000, LENGTH = 512K +} + +/* Define output sections */ +SECTIONS +{ + /* The startup code goes first into FLASH */ + .isr_vector : + { + . = ALIGN(4); + KEEP(*(.isr_vector)) /* Startup code */ + . = ALIGN(4); + } >FLASH + + /* The program code and other data goes into FLASH */ + .text : + { + . = ALIGN(4); + *(.text) /* .text sections (code) */ + *(.text*) /* .text* sections (code) */ + *(.glue_7) /* glue arm to thumb code */ + *(.glue_7t) /* glue thumb to arm code */ + *(.eh_frame) + + KEEP (*(.init)) + KEEP (*(.fini)) + + . = ALIGN(4); + _etext = .; /* define a global symbols at end of code */ + } >FLASH + + /* Constant data goes into FLASH */ + .rodata : + { + . = ALIGN(4); + *(.rodata) /* .rodata sections (constants, strings, etc.) */ + *(.rodata*) /* .rodata* sections (constants, strings, etc.) */ + . = ALIGN(4); + } >FLASH + + .ARM.extab : { *(.ARM.extab* .gnu.linkonce.armextab.*) } >FLASH + .ARM : { + __exidx_start = .; + *(.ARM.exidx*) + __exidx_end = .; + } >FLASH + + .preinit_array : + { + PROVIDE_HIDDEN (__preinit_array_start = .); + KEEP (*(.preinit_array*)) + PROVIDE_HIDDEN (__preinit_array_end = .); + } >FLASH + .init_array : + { + PROVIDE_HIDDEN (__init_array_start = .); + KEEP (*(SORT(.init_array.*))) + KEEP (*(.init_array*)) + PROVIDE_HIDDEN (__init_array_end = .); + } >FLASH + .fini_array : + { + PROVIDE_HIDDEN (__fini_array_start = .); + KEEP (*(SORT(.fini_array.*))) + KEEP (*(.fini_array*)) + PROVIDE_HIDDEN (__fini_array_end = .); + } >FLASH + + /* used by the startup to initialize data */ + _sidata = LOADADDR(.data); + + /* Initialized data sections goes into RAM, load LMA copy after code */ + .data : + { + . = ALIGN(4); + _sdata = .; /* create a global symbol at data start */ + *(.data) /* .data sections */ + *(.data*) /* .data* sections */ + + . = ALIGN(4); + _edata = .; /* define a global symbol at data end */ + } >RAM AT> FLASH + + + /* Uninitialized data section */ + . = ALIGN(4); + .bss : + { + /* This is used by the startup in order to initialize the .bss section */ + _sbss = .; /* define a global symbol at bss start */ + __bss_start__ = _sbss; + *(.bss) + *(.bss*) + *(COMMON) + + . = ALIGN(4); + _ebss = .; /* define a global symbol at bss end */ + __bss_end__ = _ebss; + } >RAM + + /* User_heap_stack section, used to check that there is enough RAM left */ + ._user_heap_stack : + { + . = ALIGN(8); + PROVIDE ( end = . ); + PROVIDE ( _end = . ); + . = . + _Min_Heap_Size; + . = . + _Min_Stack_Size; + . = ALIGN(8); + } >RAM + + + + /* Remove information from the standard libraries */ + /DISCARD/ : + { + libc.a ( * ) + libm.a ( * ) + libgcc.a ( * ) + } + + .ARM.attributes 0 : { *(.ARM.attributes) } +} diff --git a/hw/bsp/stm32g0/boards/stm32g0b1nucleo/board.cmake b/hw/bsp/stm32g0/boards/stm32g0b1nucleo/board.cmake new file mode 100644 index 000000000..c9f2a9c8e --- /dev/null +++ b/hw/bsp/stm32g0/boards/stm32g0b1nucleo/board.cmake @@ -0,0 +1,15 @@ +#set(MCU_VARIANT MIMXRT1011) +set(JLINK_DEVICE STM32G0B1RE) + +set(LD_FILE_gcc ${CMAKE_CURRENT_LIST_DIR}/STM32G0B1RETx_FLASH.ld) +set(LD_FILE_iar ${ST_CMSIS}/Source/Templates/iar/linker/stm32g0b1xx_flash.icf) + +set(STARTUP_FILE_gcc ${ST_CMSIS}/Source/Templates/gcc/startup_stm32g0b1xx.s) +set(STARTUP_FILE_iar ${ST_CMSIS}/Source/Templates/iar/startup_stm32g0b1xx.s) + +function(update_board TARGET) + target_compile_definitions(${TARGET} PUBLIC + STM32G0B1xx + #HSE_VALUE=8000000U + ) +endfunction() diff --git a/hw/bsp/stm32g0/boards/stm32g0b1nucleo/board.h b/hw/bsp/stm32g0/boards/stm32g0b1nucleo/board.h new file mode 100644 index 000000000..ae0820529 --- /dev/null +++ b/hw/bsp/stm32g0/boards/stm32g0b1nucleo/board.h @@ -0,0 +1,163 @@ +/* + * The MIT License (MIT) + * + * Copyright (c) 2020, Ha Thach (tinyusb.org) + * Copyright (c) 2034, 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 + * 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 + +// G0B1RE Nucleo does not has usb connection. We need to manually connect +// - PA12 for D+, CN10.12 +// - PA11 for D-, CN10.14 + +// LED +#define LED_PORT GPIOA +#define LED_PIN GPIO_PIN_5 +#define LED_STATE_ON 0 + +// Button +#define BUTTON_PORT GPIOC +#define BUTTON_PIN GPIO_PIN_13 +#define BUTTON_STATE_ACTIVE 0 + +// UART Enable for STLink VCOM +#define UART_DEV USART2 +#define UART_CLK_EN __HAL_RCC_USART2_CLK_ENABLE +#define UART_GPIO_PORT GPIOA +#define UART_GPIO_AF GPIO_AF1_USART2 +#define UART_TX_PIN GPIO_PIN_2 +#define UART_RX_PIN GPIO_PIN_3 + + +//--------------------------------------------------------------------+ +// RCC Clock +//--------------------------------------------------------------------+ +#if 1 +// Clock configure for STM32G0B1RE Nucleo +static inline void board_clock_init(void) +{ + RCC_OscInitTypeDef RCC_OscInitStruct = {0}; + RCC_ClkInitTypeDef RCC_ClkInitStruct = {0}; + + /** Configure the main internal regulator output voltage */ + HAL_PWREx_ControlVoltageScaling(PWR_REGULATOR_VOLTAGE_SCALE1); + + /** Initializes the RCC Oscillators according to the specified parameters + * in the RCC_OscInitTypeDef structure. */ + RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_HSI; + RCC_OscInitStruct.HSIState = RCC_HSI_ON; + RCC_OscInitStruct.HSIDiv = RCC_HSI_DIV1; + RCC_OscInitStruct.HSICalibrationValue = RCC_HSICALIBRATION_DEFAULT; + RCC_OscInitStruct.PLL.PLLState = RCC_PLL_ON; + RCC_OscInitStruct.PLL.PLLSource = RCC_PLLSOURCE_HSI; + RCC_OscInitStruct.PLL.PLLM = RCC_PLLM_DIV1; + RCC_OscInitStruct.PLL.PLLN = 8; + RCC_OscInitStruct.PLL.PLLP = RCC_PLLP_DIV2; + RCC_OscInitStruct.PLL.PLLQ = RCC_PLLQ_DIV2; + RCC_OscInitStruct.PLL.PLLR = RCC_PLLR_DIV2; + HAL_RCC_OscConfig(&RCC_OscInitStruct); + + /** Initializes the CPU, AHB and APB buses clocks */ + RCC_ClkInitStruct.ClockType = RCC_CLOCKTYPE_HCLK | RCC_CLOCKTYPE_SYSCLK | RCC_CLOCKTYPE_PCLK1; + RCC_ClkInitStruct.SYSCLKSource = RCC_SYSCLKSOURCE_PLLCLK; + RCC_ClkInitStruct.AHBCLKDivider = RCC_SYSCLK_DIV1; + RCC_ClkInitStruct.APB1CLKDivider = RCC_HCLK_DIV1; + HAL_RCC_ClockConfig(&RCC_ClkInitStruct, FLASH_LATENCY_2); + + // Configure CRS clock source + __HAL_RCC_CRS_CLK_ENABLE(); + RCC_CRSInitTypeDef RCC_CRSInitStruct = {0}; + RCC_CRSInitStruct.Prescaler = RCC_CRS_SYNC_DIV1; + RCC_CRSInitStruct.Source = RCC_CRS_SYNC_SOURCE_USB; + RCC_CRSInitStruct.Polarity = RCC_CRS_SYNC_POLARITY_RISING; + RCC_CRSInitStruct.ReloadValue = __HAL_RCC_CRS_RELOADVALUE_CALCULATE(48000000,1000); + RCC_CRSInitStruct.ErrorLimitValue = 34; + RCC_CRSInitStruct.HSI48CalibrationValue = 32; + + HAL_RCCEx_CRSConfig(&RCC_CRSInitStruct); + + /* Select HSI48 as USB clock source */ + RCC_PeriphCLKInitTypeDef usb_clk = {0 }; + usb_clk.PeriphClockSelection = RCC_PERIPHCLK_USB; + usb_clk.UsbClockSelection = RCC_USBCLKSOURCE_HSI48; + HAL_RCCEx_PeriphCLKConfig(&usb_clk); + + // Enable HSI48 + RCC_OscInitTypeDef osc_hsi48 = {0}; + osc_hsi48.OscillatorType = RCC_OSCILLATORTYPE_HSI48; + osc_hsi48.HSI48State = RCC_HSI48_ON; + HAL_RCC_OscConfig(&osc_hsi48); +} +#else + +// Clock configure for STM32G0 nucleo with B0 mcu variant for someone that is skilled enough +// to rework and solder the B0 chip. Note: SB17 may need to be soldered as well (check user manual) +static inline void board_clock_init(void) +{ + RCC_OscInitTypeDef RCC_OscInitStruct = {0}; + RCC_ClkInitTypeDef RCC_ClkInitStruct = {0}; + RCC_PeriphCLKInitTypeDef PeriphClkInitStruct = { 0 }; + + /** Configure the main internal regulator output voltage */ + HAL_PWREx_ControlVoltageScaling(PWR_REGULATOR_VOLTAGE_SCALE1); + + /** Initializes the RCC Oscillators according to the specified parameters + * in the RCC_OscInitTypeDef structure. */ + 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 = RCC_PLLM_DIV1; + RCC_OscInitStruct.PLL.PLLN = 12; + RCC_OscInitStruct.PLL.PLLP = RCC_PLLP_DIV2; + RCC_OscInitStruct.PLL.PLLQ = RCC_PLLQ_DIV2; + RCC_OscInitStruct.PLL.PLLR = RCC_PLLR_DIV2; + HAL_RCC_OscConfig(&RCC_OscInitStruct); + + /* Select HSI48 as USB clock source */ + PeriphClkInitStruct.PeriphClockSelection = RCC_PERIPHCLK_USB; + PeriphClkInitStruct.UsbClockSelection = RCC_USBCLKSOURCE_PLL; + HAL_RCCEx_PeriphCLKConfig(&PeriphClkInitStruct); + + /** Initializes the CPU, AHB and APB buses clocks */ + RCC_ClkInitStruct.ClockType = RCC_CLOCKTYPE_HCLK|RCC_CLOCKTYPE_SYSCLK + |RCC_CLOCKTYPE_PCLK1; + RCC_ClkInitStruct.SYSCLKSource = RCC_SYSCLKSOURCE_PLLCLK; + RCC_ClkInitStruct.AHBCLKDivider = RCC_SYSCLK_DIV1; + RCC_ClkInitStruct.APB1CLKDivider = RCC_HCLK_DIV1; + + HAL_RCC_ClockConfig(&RCC_ClkInitStruct, FLASH_LATENCY_0); +} +#endif + +#ifdef __cplusplus + } +#endif + +#endif /* BOARD_H_ */ diff --git a/hw/bsp/stm32g0/boards/stm32g0b1nucleo/board.mk b/hw/bsp/stm32g0/boards/stm32g0b1nucleo/board.mk new file mode 100644 index 000000000..50f282b09 --- /dev/null +++ b/hw/bsp/stm32g0/boards/stm32g0b1nucleo/board.mk @@ -0,0 +1,13 @@ +CFLAGS += \ + -DSTM32G0B1xx + +# GCC +GCC_SRC_S += $(ST_CMSIS)/Source/Templates/gcc/startup_stm32g0b1xx.s +GCC_LD_FILE = $(BOARD_PATH)/STM32G0B1RETx_FLASH.ld + +# IAR +IAR_SRC_S += $(ST_CMSIS)/Source/Templates/iar/startup_stm32g0b1xx.s +IAR_LD_FILE = $(ST_CMSIS)/Source/Templates/iar/linker/stm32g0b1xx_flash.icf + +# For flash-jlink target +JLINK_DEVICE = stm32g0b1re diff --git a/hw/bsp/stm32g0/family.c b/hw/bsp/stm32g0/family.c new file mode 100644 index 000000000..1a975915f --- /dev/null +++ b/hw/bsp/stm32g0/family.c @@ -0,0 +1,185 @@ +/* + * The MIT License (MIT) + * + * Copyright (c) 2019 Ha Thach (tinyusb.org) + * 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 + * 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 "stm32g0xx_hal.h" +#include "bsp/board.h" +#include "board.h" + +//--------------------------------------------------------------------+ +// Forward USB interrupt events to TinyUSB IRQ Handler +//--------------------------------------------------------------------+ +void USB_UCPD1_2_IRQHandler(void) +{ + tud_int_handler(0); +} + +//--------------------------------------------------------------------+ +// MACRO TYPEDEF CONSTANT ENUM +//--------------------------------------------------------------------+ +UART_HandleTypeDef UartHandle; + +void board_init(void) +{ + HAL_Init(); // required for HAL_RCC_Osc TODO check with freeRTOS + board_clock_init(); + + // Enable All GPIOs clocks + __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_SYSCFG_CLK_ENABLE(); + __HAL_RCC_PWR_CLK_ENABLE(); + + UART_CLK_EN(); + +#if CFG_TUSB_OS == OPT_OS_NONE + // 1ms tick timer + SysTick_Config(SystemCoreClock / 1000); +#elif CFG_TUSB_OS == OPT_OS_FREERTOS + // Explicitly disable systick to prevent its ISR runs before scheduler start + SysTick->CTRL &= ~1U; + + // If freeRTOS is used, IRQ priority is limit by max syscall ( smaller is higher ) + NVIC_SetPriority(USB_UCPD1_2_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); +} + +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/stm32g0/family.cmake b/hw/bsp/stm32g0/family.cmake new file mode 100644 index 000000000..9674bc759 --- /dev/null +++ b/hw/bsp/stm32g0/family.cmake @@ -0,0 +1,138 @@ +include_guard() + +if (NOT BOARD) + message(FATAL_ERROR "BOARD not specified") +endif () + +set(ST_FAMILY g0) +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) + +# enable LTO +#set(CMAKE_INTERPROCEDURAL_OPTIMIZATION TRUE) + +# toolchain set up +set(CMAKE_SYSTEM_PROCESSOR cortex-m0plus CACHE INTERNAL "System Processor") +set(CMAKE_TOOLCHAIN_FILE ${TOP}/tools/cmake/toolchain/arm_${TOOLCHAIN}.cmake) + +set(FAMILY_MCUS STM32G0 CACHE INTERNAL "") + +# include board specific +include(${CMAKE_CURRENT_LIST_DIR}/boards/${BOARD}/board.cmake) + + +#------------------------------------ +# BOARD_TARGET +#------------------------------------ +# only need to be built ONCE for all examples +set(BOARD_TARGET board_${BOARD}) +if (NOT TARGET ${BOARD_TARGET}) + 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_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_gpio.c + ${ST_HAL_DRIVER}/Src/${ST_PREFIX}_hal_uart.c + ${ST_HAL_DRIVER}/Src/${ST_PREFIX}_hal_uart_ex.c + ) + target_include_directories(${BOARD_TARGET} PUBLIC + ${CMAKE_CURRENT_LIST_DIR} + ${CMSIS_5}/CMSIS/Core/Include + ${ST_CMSIS}/Include + ${ST_HAL_DRIVER}/Inc + ) + target_compile_options(${BOARD_TARGET} PUBLIC + ) + target_compile_definitions(${BOARD_TARGET} PUBLIC + ) + update_board(${BOARD_TARGET}) + + target_sources(${BOARD_TARGET} PUBLIC + ${STARTUP_FILE_${TOOLCHAIN}} + ) + + if (TOOLCHAIN STREQUAL "gcc") + target_link_options(${BOARD_TARGET} PUBLIC + "LINKER:--script=${LD_FILE_gcc}" + -nostartfiles + # nanolib + --specs=nosys.specs + --specs=nano.specs + ) + else () + # TODO support IAR + target_link_options(${BOARD_TARGET} PUBLIC + "LINKER:--config=${LD_FILE_iar}" + ) + endif () +endif () # BOARD_TARGET + + +#------------------------------------ +# Functions +#------------------------------------ +function(family_configure_example TARGET) + family_configure_common(${TARGET}) + + #---------- Port Specific ---------- + # These files are built for each example since it depends on example's tusb_config.h + target_sources(${TARGET} PUBLIC + # TinyUSB Port + ${TOP}/src/portable/st/stm32_fsdev/dcd_stm32_fsdev.c + # 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} + ) + + #---------- TinyUSB ---------- + # tinyusb target is built for each example since it depends on example's tusb_config.h + set(TINYUSB_TARGET_PREFIX ${TARGET}-) + add_library(${TARGET}-tinyusb_config INTERFACE) + + target_include_directories(${TARGET}-tinyusb_config INTERFACE + ${CMAKE_CURRENT_SOURCE_DIR}/src + ) + target_compile_definitions(${TARGET}-tinyusb_config INTERFACE + CFG_TUSB_MCU=OPT_MCU_STM32G0 + ) + + # tinyusb's CMakeList.txt + add_subdirectory(${TOP}/src ${CMAKE_CURRENT_BINARY_DIR}/tinyusb) + + # Link dependencies + target_link_libraries(${TARGET} PUBLIC ${BOARD_TARGET} ${TARGET}-tinyusb) + + # group target (not yet supported by clion) + set_target_properties(${TARGET}-tinyusb ${TARGET}-tinyusb_config + PROPERTIES FOLDER ${TARGET}_sub + ) + + #---------- Flash ---------- + family_flash_stlink(${TARGET}) + #family_flash_jlink(${TARGET}) +endfunction() + + +function(family_configure_device_example TARGET) + family_configure_example(${TARGET}) +endfunction() + +function(family_configure_host_example TARGET) + family_configure_example(${TARGET}) +endfunction() + +function(family_configure_dual_usb_example TARGET) + family_configure_example(${TARGET}) +endfunction() diff --git a/hw/bsp/stm32g0/family.mk b/hw/bsp/stm32g0/family.mk new file mode 100644 index 000000000..76f59fc34 --- /dev/null +++ b/hw/bsp/stm32g0/family.mk @@ -0,0 +1,57 @@ +ST_FAMILY = g0 +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 + +include $(TOP)/$(BOARD_PATH)/board.mk + +# -------------- +# Compiler Flags +# -------------- +CFLAGS += \ + -DCFG_TUSB_MCU=OPT_MCU_STM32G0 + +# GCC Flags +GCC_CFLAGS += \ + -flto \ + -mthumb \ + -mabi=aapcs \ + -mcpu=cortex-m0plus \ + -mfloat-abi=soft \ + -nostdlib -nostartfiles + +# suppress warning caused by vendor mcu driver +GCC_CFLAGS += -Wno-error=cast-align + +# IAR Flags +IAR_CFLAGS += --cpu cortex-m0 +IAR_ASFLAGS += --cpu cortex-m0 + +# ----------------- +# 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_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 + +INC += \ + $(TOP)/$(BOARD_PATH) \ + $(TOP)/lib/CMSIS_5/CMSIS/Core/Include \ + $(TOP)/$(ST_CMSIS)/Include \ + $(TOP)/$(ST_HAL_DRIVER)/Inc + +# For freeRTOS port source +FREERTOS_PORTABLE_SRC = $(FREERTOS_PORTABLE_PATH)/ARM_CM0 + +# flash target using on-board stlink +flash: flash-stlink diff --git a/hw/bsp/stm32g0/stm32g0xx_hal_conf.h b/hw/bsp/stm32g0/stm32g0xx_hal_conf.h new file mode 100644 index 000000000..b2e335676 --- /dev/null +++ b/hw/bsp/stm32g0/stm32g0xx_hal_conf.h @@ -0,0 +1,351 @@ +/* USER CODE BEGIN Header */ +/** + ****************************************************************************** + * @file stm32g0xx_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 STM32G0xx_HAL_CONF_H +#define STM32G0xx_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 + +/* ########################## 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 (8000000UL) /*!< Value of the External oscillator in Hz */ +#endif /* HSE_VALUE */ + +#if !defined (HSE_STARTUP_TIMEOUT) +#define HSE_STARTUP_TIMEOUT (100UL) /*!< Time out for HSE start up, in ms */ +#endif /* HSE_STARTUP_TIMEOUT */ + +/** + * @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 (16000000UL) /*!< Value of the Internal oscillator in Hz*/ +#endif /* HSI_VALUE */ + +#if defined(STM32G0C1xx) || defined(STM32G0B1xx) || defined(STM32G0B0xx) +/** + * @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 48000000U /*!< 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 */ +#endif + +/** + * @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.*/ +/** + * @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 I2S1 peripheral + * This value is used by the RCC HAL module to compute the I2S1 clock source + * frequency. + */ +#if !defined (EXTERNAL_I2S1_CLOCK_VALUE) +#define EXTERNAL_I2S1_CLOCK_VALUE (48000UL) /*!< Value of the I2S1 External clock source in Hz*/ +#endif /* EXTERNAL_I2S1_CLOCK_VALUE */ + +#if defined(STM32G0C1xx) || defined(STM32G0B1xx) || defined(STM32G0B0xx) +/** + * @brief External clock source for I2S2 peripheral + * This value is used by the RCC HAL module to compute the I2S2 clock source + * frequency. + */ +#if !defined (EXTERNAL_I2S2_CLOCK_VALUE) + #define EXTERNAL_I2S2_CLOCK_VALUE 48000U /*!< Value of the I2S2 External clock source in Hz*/ +#endif /* EXTERNAL_I2S2_CLOCK_VALUE */ +#endif + +/* 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 0U /*!< tick interrupt priority */ +#define USE_RTOS 0U +#define PREFETCH_ENABLE 1U +#define INSTRUCTION_CACHE_ENABLE 1U + +/* ################## SPI peripheral configuration ########################## */ + +/* CRC FEATURE: Use to activate CRC feature inside HAL SPI Driver +* Activated: CRC code is present inside driver +* Deactivated: CRC code cleaned from driver +*/ + +#define USE_SPI_CRC 0U + +/* ################## 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 "stm32g0xx_hal_rcc.h" +#endif /* HAL_RCC_MODULE_ENABLED */ + +#ifdef HAL_GPIO_MODULE_ENABLED +#include "stm32g0xx_hal_gpio.h" +#endif /* HAL_GPIO_MODULE_ENABLED */ + +#ifdef HAL_DMA_MODULE_ENABLED +#include "stm32g0xx_hal_dma.h" +#endif /* HAL_DMA_MODULE_ENABLED */ + +#ifdef HAL_CORTEX_MODULE_ENABLED +#include "stm32g0xx_hal_cortex.h" +#endif /* HAL_CORTEX_MODULE_ENABLED */ + +#ifdef HAL_ADC_MODULE_ENABLED +#include "stm32g0xx_hal_adc.h" +#include "stm32g0xx_hal_adc_ex.h" +#endif /* HAL_ADC_MODULE_ENABLED */ + +#ifdef HAL_CEC_MODULE_ENABLED +#include "stm32g0xx_hal_cec.h" +#endif /* HAL_CEC_MODULE_ENABLED */ + +#ifdef HAL_COMP_MODULE_ENABLED +#include "stm32g0xx_hal_comp.h" +#endif /* HAL_COMP_MODULE_ENABLED */ + +#ifdef HAL_CRC_MODULE_ENABLED +#include "stm32g0xx_hal_crc.h" +#endif /* HAL_CRC_MODULE_ENABLED */ + +#ifdef HAL_CRYP_MODULE_ENABLED +#include "stm32g0xx_hal_cryp.h" +#endif /* HAL_CRYP_MODULE_ENABLED */ + +#ifdef HAL_DAC_MODULE_ENABLED +#include "stm32g0xx_hal_dac.h" +#endif /* HAL_DAC_MODULE_ENABLED */ + +#ifdef HAL_EXTI_MODULE_ENABLED +#include "stm32g0xx_hal_exti.h" +#endif /* HAL_EXTI_MODULE_ENABLED */ + +#ifdef HAL_FLASH_MODULE_ENABLED +#include "stm32g0xx_hal_flash.h" +#endif /* HAL_FLASH_MODULE_ENABLED */ + +#ifdef HAL_FDCAN_MODULE_ENABLED +#include "stm32g0xx_hal_fdcan.h" +#endif /* HAL_FDCAN_MODULE_ENABLED */ + +#ifdef HAL_HCD_MODULE_ENABLED +#include "stm32g0xx_hal_hcd.h" +#endif /* HAL_HCD_MODULE_ENABLED */ + +#ifdef HAL_I2C_MODULE_ENABLED +#include "stm32g0xx_hal_i2c.h" +#endif /* HAL_I2C_MODULE_ENABLED */ + +#ifdef HAL_I2S_MODULE_ENABLED +#include "stm32g0xx_hal_i2s.h" +#endif /* HAL_I2S_MODULE_ENABLED */ + +#ifdef HAL_IRDA_MODULE_ENABLED +#include "stm32g0xx_hal_irda.h" +#endif /* HAL_IRDA_MODULE_ENABLED */ + +#ifdef HAL_IWDG_MODULE_ENABLED +#include "stm32g0xx_hal_iwdg.h" +#endif /* HAL_IWDG_MODULE_ENABLED */ + +#ifdef HAL_LPTIM_MODULE_ENABLED +#include "stm32g0xx_hal_lptim.h" +#endif /* HAL_LPTIM_MODULE_ENABLED */ + +#ifdef HAL_PCD_MODULE_ENABLED +#include "stm32g0xx_hal_pcd.h" +#endif /* HAL_PCD_MODULE_ENABLED */ + +#ifdef HAL_PWR_MODULE_ENABLED +#include "stm32g0xx_hal_pwr.h" +#endif /* HAL_PWR_MODULE_ENABLED */ + +#ifdef HAL_RNG_MODULE_ENABLED +#include "stm32g0xx_hal_rng.h" +#endif /* HAL_RNG_MODULE_ENABLED */ + +#ifdef HAL_RTC_MODULE_ENABLED +#include "stm32g0xx_hal_rtc.h" +#endif /* HAL_RTC_MODULE_ENABLED */ + +#ifdef HAL_SMARTCARD_MODULE_ENABLED +#include "stm32g0xx_hal_smartcard.h" +#endif /* HAL_SMARTCARD_MODULE_ENABLED */ + +#ifdef HAL_SMBUS_MODULE_ENABLED +#include "stm32g0xx_hal_smbus.h" +#endif /* HAL_SMBUS_MODULE_ENABLED */ + +#ifdef HAL_SPI_MODULE_ENABLED +#include "stm32g0xx_hal_spi.h" +#endif /* HAL_SPI_MODULE_ENABLED */ + +#ifdef HAL_TIM_MODULE_ENABLED +#include "stm32g0xx_hal_tim.h" +#endif /* HAL_TIM_MODULE_ENABLED */ + +#ifdef HAL_UART_MODULE_ENABLED +#include "stm32g0xx_hal_uart.h" +#endif /* HAL_UART_MODULE_ENABLED */ + +#ifdef HAL_USART_MODULE_ENABLED +#include "stm32g0xx_hal_usart.h" +#endif /* HAL_USART_MODULE_ENABLED */ + +#ifdef HAL_WWDG_MODULE_ENABLED +#include "stm32g0xx_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 /* STM32G0xx_HAL_CONF_H */ diff --git a/src/common/tusb_mcu.h b/src/common/tusb_mcu.h index 9c2933983..48f765674 100644 --- a/src/common/tusb_mcu.h +++ b/src/common/tusb_mcu.h @@ -201,6 +201,11 @@ #define TUP_USBIP_FSDEV_STM32 #define TUP_DCD_ENDPOINT_MAX 8 +#elif TU_CHECK_MCU(OPT_MCU_STM32G0) + #define TUP_USBIP_FSDEV + #define TUP_USBIP_FSDEV_STM32 + #define TUP_DCD_ENDPOINT_MAX 8 + #elif TU_CHECK_MCU(OPT_MCU_STM32L0, OPT_MCU_STM32L1) #define TUP_USBIP_FSDEV #define TUP_USBIP_FSDEV_STM32 diff --git a/src/portable/st/stm32_fsdev/dcd_stm32_fsdev.c b/src/portable/st/stm32_fsdev/dcd_stm32_fsdev.c index 98d3d0829..14cabaf8d 100644 --- a/src/portable/st/stm32_fsdev/dcd_stm32_fsdev.c +++ b/src/portable/st/stm32_fsdev/dcd_stm32_fsdev.c @@ -44,6 +44,7 @@ * L0x2, L0x3 1024 byte buffer * L1 512 byte buffer * L4x2, L4x3 1024 byte buffer + * G0 2048 byte buffer * * To use this driver, you must: * - If you are using a device with crystal-less USB, set up the clock recovery system (CRS) @@ -185,12 +186,12 @@ static void dcd_ep_ctr_handler(void); static uint8_t open_ep_count; static uint16_t ep_buf_ptr; ///< Points to first free memory location static void dcd_pma_alloc_reset(void); -static uint16_t dcd_pma_alloc(uint8_t ep_addr, size_t length); +static uint16_t dcd_pma_alloc(uint8_t ep_addr, uint16_t length); static void dcd_pma_free(uint8_t ep_addr); static void dcd_ep_free(uint8_t ep_addr); static uint8_t dcd_ep_alloc(uint8_t ep_addr, uint8_t ep_type); -static bool dcd_write_packet_memory(uint16_t dst, const void *__restrict src, size_t wNBytes); -static bool dcd_read_packet_memory(void *__restrict dst, uint16_t src, size_t wNBytes); +static bool dcd_write_packet_memory(uint16_t dst, const void *__restrict src, uint16_t wNBytes); +static bool dcd_read_packet_memory(void *__restrict dst, uint16_t src, uint16_t wNBytes); static bool dcd_write_packet_memory_ff(tu_fifo_t * ff, uint16_t dst, uint16_t wNBytes); static bool dcd_read_packet_memory_ff(tu_fifo_t * ff, uint16_t src, uint16_t wNBytes); @@ -209,17 +210,6 @@ TU_ATTR_ALWAYS_INLINE static inline xfer_ctl_t* xfer_ctl_ptr(uint32_t ep_addr) return &xfer_status[epnum][dir]; } -// Using a function due to better type checks -// This seems better than having to do type casts everywhere else -TU_ATTR_ALWAYS_INLINE static inline void reg16_clear_bits(__IO uint16_t *reg, uint16_t mask) { - *reg = (uint16_t)(*reg & ~mask); -} - -// Bits in ISTR are cleared upon writing 0 -TU_ATTR_ALWAYS_INLINE static inline void clear_istr_bits(uint16_t mask) { - USB->ISTR = ~mask; -} - //--------------------------------------------------------------------+ // Controller API //--------------------------------------------------------------------+ @@ -242,7 +232,9 @@ void dcd_init (uint8_t rhport) { asm("NOP"); } - reg16_clear_bits(&USB->CNTR, USB_CNTR_PDWN);// Remove powerdown + + USB->CNTR &= ~USB_CNTR_PDWN; + // Wait startup time, for F042 and F070, this is <= 1 us. for(uint32_t i = 0; i<200; i++) // should be a few us { @@ -250,8 +242,9 @@ 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 USB->BTABLE = DCD_STM32_BTABLE_BASE; - +#endif USB->ISTR = 0; // Clear pending interrupts // Reset endpoints to disabled @@ -312,7 +305,7 @@ void dcd_sof_enable(uint8_t rhport, bool en) } else { - USB->CNTR &= (uint16_t) ~USB_CNTR_SOFM; + USB->CNTR &= ~USB_CNTR_SOFM; } } @@ -358,6 +351,13 @@ void dcd_int_enable (uint8_t rhport) NVIC_EnableIRQ(USB_LP_IRQn); NVIC_EnableIRQ(USBWakeUp_IRQn); +#elif CFG_TUSB_MCU == OPT_MCU_STM32G0 + #ifdef STM32G0B0xx + NVIC_EnableIRQ(USB_IRQn); + #else + NVIC_EnableIRQ(USB_UCPD1_2_IRQn); + #endif + #elif CFG_TUSB_MCU == OPT_MCU_STM32WB NVIC_EnableIRQ(USB_HP_IRQn); NVIC_EnableIRQ(USB_LP_IRQn); @@ -408,6 +408,13 @@ void dcd_int_disable(uint8_t rhport) NVIC_DisableIRQ(USB_LP_IRQn); NVIC_DisableIRQ(USBWakeUp_IRQn); +#elif CFG_TUSB_MCU == OPT_MCU_STM32G0 + #ifdef STM32G0B0xx + NVIC_DisableIRQ(USB_IRQn); + #else + NVIC_DisableIRQ(USB_UCPD1_2_IRQn); + #endif + #elif CFG_TUSB_MCU == OPT_MCU_STM32WB NVIC_DisableIRQ(USB_HP_IRQn); NVIC_DisableIRQ(USB_LP_IRQn); @@ -439,7 +446,7 @@ void dcd_remote_wakeup(uint8_t rhport) { (void) rhport; - USB->CNTR |= (uint16_t) USB_CNTR_RESUME; + USB->CNTR |= USB_CNTR_RESUME; remoteWakeCountdown = 4u; // required to be 1 to 15 ms, ESOF should trigger every 1ms. } @@ -470,7 +477,6 @@ static void dcd_handle_bus_reset(void) //__IO uint16_t * const epreg = &(EPREG(0)); USB->DADDR = 0u; // disable USB peripheral by clearing the EF flag - for(uint32_t i=0; iff) { @@ -657,13 +667,13 @@ void dcd_int_handler(uint8_t rhport) { /* Put SOF flag at the beginning of ISR in case to get least amount of jitter if it is used for timing purposes */ if(int_status & USB_ISTR_SOF) { - clear_istr_bits(USB_ISTR_SOF); + USB->ISTR &=~USB_ISTR_SOF; dcd_event_sof(0, USB->FNR & USB_FNR_FN, true); } if(int_status & USB_ISTR_RESET) { // USBRST is start of reset. - clear_istr_bits(USB_ISTR_RESET); + USB->ISTR &=~USB_ISTR_RESET; dcd_handle_bus_reset(); dcd_event_bus_reset(0, TUSB_SPEED_FULL, true); return; // Don't do the rest of the things here; perhaps they've been cleared? @@ -678,9 +688,10 @@ void dcd_int_handler(uint8_t rhport) { if (int_status & USB_ISTR_WKUP) { - reg16_clear_bits(&USB->CNTR, USB_CNTR_LPMODE); - reg16_clear_bits(&USB->CNTR, USB_CNTR_FSUSP); - clear_istr_bits(USB_ISTR_WKUP); + USB->CNTR &= ~USB_CNTR_LPMODE; + USB->CNTR &= ~USB_CNTR_FSUSP; + + USB->ISTR &=~USB_ISTR_WKUP; dcd_event_bus_signal(0, DCD_EVENT_RESUME, true); } @@ -694,20 +705,20 @@ void dcd_int_handler(uint8_t rhport) { USB->CNTR |= USB_CNTR_LPMODE; /* clear of the ISTR bit must be done after setting of CNTR_FSUSP */ - clear_istr_bits(USB_ISTR_SUSP); + USB->ISTR &=~USB_ISTR_SUSP; dcd_event_bus_signal(0, DCD_EVENT_SUSPEND, true); } if(int_status & USB_ISTR_ESOF) { if(remoteWakeCountdown == 1u) { - USB->CNTR &= (uint16_t)(~USB_CNTR_RESUME); + USB->CNTR &= ~USB_CNTR_RESUME; } if(remoteWakeCountdown > 0u) { remoteWakeCountdown--; } - clear_istr_bits(USB_ISTR_ESOF); + USB->ISTR &=~USB_ISTR_ESOF; } } @@ -728,8 +739,8 @@ void dcd_edpt0_status_complete(uint8_t rhport, tusb_control_request_t const * re uint8_t const dev_addr = (uint8_t) request->wValue; // Setting new address after the whole request is complete - reg16_clear_bits(&USB->DADDR, USB_DADDR_ADD); - USB->DADDR = (uint16_t)(USB->DADDR | dev_addr); // leave the enable bit set + USB->DADDR &= ~USB_DADDR_ADD; + USB->DADDR |= dev_addr; // leave the enable bit set } } @@ -756,7 +767,7 @@ static void dcd_pma_alloc_reset(void) * * During failure, TU_ASSERT is used. If this happens, rework/reallocate memory manually. */ -static uint16_t dcd_pma_alloc(uint8_t ep_addr, size_t length) +static uint16_t dcd_pma_alloc(uint8_t ep_addr, uint16_t length) { xfer_ctl_t* epXferCtl = xfer_ctl_ptr(ep_addr); @@ -768,6 +779,13 @@ static uint16_t dcd_pma_alloc(uint8_t ep_addr, size_t length) return epXferCtl->pma_ptr; } + // Ensure allocated buffer is aligned +#ifdef PMA_32BIT_ACCESS + length = (length + 3) & ~0x03; +#else + length = (length + 1) & ~0x01; +#endif + open_ep_count++; uint16_t addr = ep_buf_ptr; @@ -778,7 +796,7 @@ static uint16_t dcd_pma_alloc(uint8_t ep_addr, size_t length) epXferCtl->pma_ptr = addr; epXferCtl->pma_alloc_size = length; - //TU_LOG2("dcd_pma_alloc(%x,%x)=%x\r\n",ep_addr,length,addr); + //TU_LOG1("dcd_pma_alloc(%x,%x)=%x\r\n",ep_addr,length,addr); return addr; } @@ -931,14 +949,14 @@ bool dcd_edpt_open (uint8_t rhport, tusb_desc_endpoint_t const * p_endpoint_desc if( (dir == TUSB_DIR_IN) || (wType == USB_EP_ISOCHRONOUS) ) { - *pcd_ep_tx_address_ptr(USB, ep_idx) = pma_addr; + pcd_set_ep_tx_address(USB, ep_idx, pma_addr); pcd_set_ep_tx_bufsize(USB, ep_idx, buffer_size); pcd_clear_tx_dtog(USB, ep_idx); } if( (dir == TUSB_DIR_OUT) || (wType == USB_EP_ISOCHRONOUS) ) { - *pcd_ep_rx_address_ptr(USB, ep_idx) = pma_addr; + pcd_set_ep_rx_address(USB, ep_idx, pma_addr); pcd_set_ep_rx_bufsize(USB, ep_idx, buffer_size); pcd_clear_rx_dtog(USB, ep_idx); } @@ -1018,8 +1036,8 @@ bool dcd_edpt_iso_alloc(uint8_t rhport, uint8_t ep_addr, uint16_t largest_packet pcd_set_eptype(USB, ep_idx, USB_EP_ISOCHRONOUS); - *pcd_ep_tx_address_ptr(USB, ep_idx) = pma_addr; - *pcd_ep_rx_address_ptr(USB, ep_idx) = pma_addr; + pcd_set_ep_tx_address(USB, ep_idx, pma_addr); + pcd_set_ep_rx_address(USB, ep_idx, pma_addr); return true; } @@ -1069,7 +1087,7 @@ static void dcd_transmit_packet(xfer_ctl_t * xfer, uint16_t ep_ix) } uint16_t ep_reg = pcd_get_endpoint(USB, ep_ix); - uint16_t addr_ptr = *pcd_ep_tx_address_ptr(USB,ep_ix); + uint16_t addr_ptr = pcd_get_ep_tx_address(USB, ep_ix); if (xfer->ff) { @@ -1203,6 +1221,40 @@ void dcd_edpt_clear_stall (uint8_t rhport, uint8_t ep_addr) } } +#ifdef PMA_32BIT_ACCESS +static bool dcd_write_packet_memory(uint16_t dst, const void *__restrict src, uint16_t wNBytes) +{ + const uint8_t* srcVal = src; + volatile uint32_t* dst32 = (volatile uint32_t*)(USB_PMAADDR + dst); + + for (uint32_t n = wNBytes / 4; n > 0; --n) { + *dst32++ = tu_unaligned_read32(srcVal); + srcVal += 4; + } + + wNBytes = wNBytes & 0x03; + if (wNBytes) + { + uint32_t wrVal = *srcVal; + wNBytes--; + + if (wNBytes) + { + wrVal |= *++srcVal << 8; + wNBytes--; + + if (wNBytes) + { + wrVal |= *++srcVal << 16; + } + } + + *dst32 = wrVal; + } + + return true; +} +#else // Packet buffer access can only be 8- or 16-bit. /** * @brief Copy a buffer from user memory area to packet memory area (PMA). @@ -1214,7 +1266,7 @@ void dcd_edpt_clear_stall (uint8_t rhport, uint8_t ep_addr) * @param wNBytes no. of bytes to be copied. * @retval None */ -static bool dcd_write_packet_memory(uint16_t dst, const void *__restrict src, size_t wNBytes) +static bool dcd_write_packet_memory(uint16_t dst, const void *__restrict src, uint16_t wNBytes) { uint32_t n = (uint32_t)wNBytes >> 1U; uint16_t temp1, temp2; @@ -1237,7 +1289,7 @@ static bool dcd_write_packet_memory(uint16_t dst, const void *__restrict src, si srcVal++; } - if (wNBytes & 0x01) + if (wNBytes) { temp1 = *srcVal; *pdwVal = temp1; @@ -1245,6 +1297,7 @@ static bool dcd_write_packet_memory(uint16_t dst, const void *__restrict src, si return true; } +#endif /** * @brief Copy from FIFO to packet memory area (PMA). @@ -1263,7 +1316,37 @@ static bool dcd_write_packet_memory_ff(tu_fifo_t * ff, uint16_t dst, uint16_t wN // We want to read from the FIFO and write it into the PMA, if LIN part is ODD and has WRAPPED part, // last lin byte will be combined with wrapped part - // To ensure PMA is always access 16bit aligned (dst aligned to 16 bit) + // To ensure PMA is always access aligned (dst aligned to 16 or 32 bit) +#ifdef PMA_32BIT_ACCESS + if((cnt_lin & 0x03) && cnt_wrap) + { + // Copy first linear part + dcd_write_packet_memory(dst, info.ptr_lin, cnt_lin &~0x03); + dst += cnt_lin &~0x03; + + // Copy last linear bytes & first wrapped bytes to buffer + uint32_t i; + uint8_t tmp[4]; + for (i = 0; i < (cnt_lin & 0x03); i++) + { + tmp[i] = ((uint8_t*)info.ptr_lin)[(cnt_lin &~0x03) + i]; + } + uint32_t wCnt = cnt_wrap; + for (; i < 4 && wCnt > 0; i++, wCnt--) + { + tmp[i] = *(uint8_t*)info.ptr_wrap; + info.ptr_wrap = (uint8_t*)info.ptr_wrap + 1; + } + + // Write unaligned buffer + dcd_write_packet_memory(dst, &tmp, 4); + dst += 4; + + // Copy rest of wrapped byte + if (wCnt) + dcd_write_packet_memory(dst, info.ptr_wrap, wCnt); + } +#else if((cnt_lin & 0x01) && cnt_wrap) { // Copy first linear part @@ -1278,6 +1361,7 @@ static bool dcd_write_packet_memory_ff(tu_fifo_t * ff, uint16_t dst, uint16_t wN // Copy rest of wrapped byte dcd_write_packet_memory(dst, ((uint8_t*)info.ptr_wrap) + 1, cnt_wrap - 1); } +#endif else { // Copy linear part @@ -1296,13 +1380,47 @@ static bool dcd_write_packet_memory_ff(tu_fifo_t * ff, uint16_t dst, uint16_t wN return true; } +#ifdef PMA_32BIT_ACCESS +static bool dcd_read_packet_memory(void *__restrict dst, uint16_t src, uint16_t wNBytes) +{ + uint8_t* dstVal = dst; + volatile uint32_t* src32 = (volatile uint32_t*)(USB_PMAADDR + src); + + for (uint32_t n = wNBytes / 4; n > 0; --n) { + tu_unaligned_write32(dstVal, *src32++); + dstVal += 4; + } + + wNBytes = wNBytes & 0x03; + if (wNBytes) + { + uint32_t rdVal = *src32; + + *dstVal = tu_u32_byte0(rdVal); + wNBytes--; + + if (wNBytes) + { + *++dstVal = tu_u32_byte1(rdVal); + wNBytes--; + + if (wNBytes) + { + *++dstVal = tu_u32_byte2(rdVal); + } + } + } + + return true; +} +#else /** * @brief Copy a buffer from packet memory area (PMA) to user memory area. * Uses byte-access of system memory and 16-bit access of packet memory * @param wNBytes no. of bytes to be copied. * @retval None */ -static bool dcd_read_packet_memory(void *__restrict dst, uint16_t src, size_t wNBytes) +static bool dcd_read_packet_memory(void *__restrict dst, uint16_t src, uint16_t wNBytes) { uint32_t n = (uint32_t)wNBytes >> 1U; // The GCC optimizer will combine access to 32-bit sizes if we let it. Force @@ -1329,6 +1447,7 @@ static bool dcd_read_packet_memory(void *__restrict dst, uint16_t src, size_t wN } return true; } +#endif /** * @brief Copy a buffer from user packet memory area (PMA) to FIFO. @@ -1346,9 +1465,39 @@ static bool dcd_read_packet_memory_ff(tu_fifo_t * ff, uint16_t src, uint16_t wNB uint16_t cnt_lin = TU_MIN(wNBytes, info.len_lin); uint16_t cnt_wrap = TU_MIN(wNBytes - cnt_lin, info.len_wrap); + // We want to read from PMA and write it into the FIFO, if LIN part is ODD and has WRAPPED part, // last lin byte will be combined with wrapped part - // To ensure PMA is always access 16bit aligned (src aligned to 16 bit) + // To ensure PMA is always access aligned (src aligned to 16 or 32 bit) +#ifdef PMA_32BIT_ACCESS + if((cnt_lin & 0x03) && cnt_wrap) + { + // Copy first linear part + dcd_read_packet_memory(info.ptr_lin, src, cnt_lin &~0x03); + src += cnt_lin &~0x03; + + // Copy last linear bytes & first wrapped bytes + uint8_t tmp[4]; + dcd_read_packet_memory(tmp, src, 4); + src += 4; + + uint32_t i; + for (i = 0; i < (cnt_lin & 0x03); i++) + { + ((uint8_t*)info.ptr_lin)[(cnt_lin &~0x03) + i] = tmp[i]; + } + uint32_t wCnt = cnt_wrap; + for (; i < 4 && wCnt > 0; i++, wCnt--) + { + *(uint8_t*)info.ptr_wrap = tmp[i]; + info.ptr_wrap = (uint8_t*)info.ptr_wrap + 1; + } + + // Copy rest of wrapped byte + if (wCnt) + dcd_read_packet_memory(info.ptr_wrap, src, wCnt); + } +#else if((cnt_lin & 0x01) && cnt_wrap) { // Copy first linear part @@ -1356,16 +1505,17 @@ static bool dcd_read_packet_memory_ff(tu_fifo_t * ff, uint16_t src, uint16_t wNB src += cnt_lin &~0x01; // Copy last linear byte & first wrapped byte - uint16_t tmp; - dcd_read_packet_memory(&tmp, src, 2); - - ((uint8_t*)info.ptr_lin)[cnt_lin - 1] = (uint8_t)tmp; - ((uint8_t*)info.ptr_wrap)[0] = (uint8_t)(tmp >> 8U); + uint8_t tmp[2]; + dcd_read_packet_memory(tmp, src, 2); src += 2; + ((uint8_t*)info.ptr_lin)[cnt_lin - 1] = tmp[0]; + ((uint8_t*)info.ptr_wrap)[0] = tmp[1]; + // Copy rest of wrapped byte dcd_read_packet_memory(((uint8_t*)info.ptr_wrap) + 1, src, cnt_wrap - 1); } +#endif else { // Copy linear part 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 e3fc8aeb5..e6649de5a 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 @@ -82,6 +82,34 @@ #include "stm32g4xx.h" #define PMA_LENGTH (1024u) +#elif CFG_TUSB_MCU == OPT_MCU_STM32G0 + #include "stm32g0xx.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) @@ -113,15 +141,31 @@ #define PMA_STRIDE (1u) #endif -// And for type-safety create a new macro for the volatile address of PMAADDR +// For type-safety create a new macro for the volatile address of PMAADDR // The compiler should warn us if we cast it to a non-volatile type? +#ifdef PMA_32BIT_ACCESS +static __IO uint32_t * const pma32 = (__IO uint32_t*)USB_PMAADDR; +#else // Volatile is also needed to prevent the optimizer from changing access to 32-bit (as 32-bit access is forbidden) static __IO uint16_t * const pma = (__IO uint16_t*)USB_PMAADDR; -// prototypes -TU_ATTR_ALWAYS_INLINE static inline __IO uint16_t* pcd_ep_rx_cnt_ptr(USB_TypeDef * USBx, uint32_t bEpIdx); -TU_ATTR_ALWAYS_INLINE static inline __IO uint16_t* pcd_ep_tx_cnt_ptr(USB_TypeDef * USBx, uint32_t bEpIdx); -TU_ATTR_ALWAYS_INLINE static inline void pcd_set_endpoint(USB_TypeDef * USBx, uint32_t bEpIdx, uint32_t wRegValue); +TU_ATTR_ALWAYS_INLINE static inline __IO uint16_t * pcd_btable_word_ptr(USB_TypeDef * USBx, size_t x) +{ + size_t total_word_offset = (((USBx)->BTABLE)>>1) + x; + total_word_offset *= PMA_STRIDE; + return &(pma[total_word_offset]); +} + +TU_ATTR_ALWAYS_INLINE static inline __IO uint16_t* pcd_ep_tx_cnt_ptr(USB_TypeDef * USBx, uint32_t bEpIdx) +{ + return pcd_btable_word_ptr(USBx,(bEpIdx)*4u + 1u); +} + +TU_ATTR_ALWAYS_INLINE static inline __IO uint16_t* pcd_ep_rx_cnt_ptr(USB_TypeDef * USBx, uint32_t bEpIdx) +{ + return pcd_btable_word_ptr(USBx,(bEpIdx)*4u + 3u); +} +#endif /* Aligned buffer size according to hardware */ TU_ATTR_ALWAYS_INLINE static inline uint16_t pcd_aligned_buffer_size(uint16_t size) @@ -139,13 +183,24 @@ TU_ATTR_ALWAYS_INLINE static inline uint16_t pcd_aligned_buffer_size(uint16_t si /* SetENDPOINT */ TU_ATTR_ALWAYS_INLINE static inline void pcd_set_endpoint(USB_TypeDef * USBx, uint32_t bEpIdx, uint32_t wRegValue) { +#ifdef PMA_32BIT_ACCESS + (void) USBx; + __O uint32_t *reg = (__O uint32_t *)(USB_DRD_BASE + bEpIdx*4); + *reg = wRegValue; +#else __O uint16_t *reg = (__O uint16_t *)((&USBx->EP0R) + bEpIdx*2u); *reg = (uint16_t)wRegValue; +#endif } /* GetENDPOINT */ -TU_ATTR_ALWAYS_INLINE static inline uint16_t pcd_get_endpoint(USB_TypeDef * USBx, uint32_t bEpIdx) { +TU_ATTR_ALWAYS_INLINE static inline uint32_t pcd_get_endpoint(USB_TypeDef * USBx, uint32_t bEpIdx) { +#ifdef PMA_32BIT_ACCESS + (void) USBx; + __I uint32_t *reg = (__I uint32_t *)(USB_DRD_BASE + bEpIdx*4); +#else __I uint16_t *reg = (__I uint16_t *)((&USBx->EP0R) + bEpIdx*2u); +#endif return *reg; } @@ -195,34 +250,24 @@ TU_ATTR_ALWAYS_INLINE static inline void pcd_clear_tx_ep_ctr(USB_TypeDef * USBx, */ TU_ATTR_ALWAYS_INLINE static inline uint32_t pcd_get_ep_tx_cnt(USB_TypeDef * USBx, uint32_t bEpIdx) { +#ifdef PMA_32BIT_ACCESS + (void) USBx; + return (pma32[2*bEpIdx] & 0x03FF0000) >> 16; +#else __I uint16_t *regPtr = pcd_ep_tx_cnt_ptr(USBx, bEpIdx); return *regPtr & 0x3ffU; +#endif } TU_ATTR_ALWAYS_INLINE static inline uint32_t pcd_get_ep_rx_cnt(USB_TypeDef * USBx, uint32_t bEpIdx) { +#ifdef PMA_32BIT_ACCESS + (void) USBx; + return (pma32[2*bEpIdx + 1] & 0x03FF0000) >> 16; +#else __I uint16_t *regPtr = pcd_ep_rx_cnt_ptr(USBx, bEpIdx); return *regPtr & 0x3ffU; -} - -/** - * @brief Sets counter of rx buffer with no. of blocks. - * @param dwReg Register - * @param wCount Counter. - * @param wNBlocks no. of Blocks. - * @retval None - */ -TU_ATTR_ALWAYS_INLINE static inline void pcd_set_ep_cnt_reg(__O uint16_t * pdwReg, size_t wCount) -{ - /* We assume that the buffer size is already aligned to hardware requirements. */ - uint16_t blocksize = (wCount > 62) ? 1 : 0; - uint16_t numblocks = wCount / (blocksize ? 32 : 2); - - /* There should be no remainder in the above calculation */ - TU_ASSERT((wCount - (numblocks * (blocksize ? 32 : 2))) == 0, /**/); - - /* Encode into register. When BLSIZE==1, we need to subtract 1 block count */ - *pdwReg = (blocksize << 15) | ((numblocks - blocksize) << 10); +#endif } /** @@ -241,57 +286,103 @@ TU_ATTR_ALWAYS_INLINE static inline void pcd_set_ep_address(USB_TypeDef * USBx, pcd_set_endpoint(USBx, bEpIdx,regVal); } -TU_ATTR_ALWAYS_INLINE static inline __IO uint16_t * pcd_btable_word_ptr(USB_TypeDef * USBx, size_t x) +TU_ATTR_ALWAYS_INLINE static inline uint32_t pcd_get_ep_tx_address(USB_TypeDef * USBx, uint32_t bEpIdx) { - size_t total_word_offset = (((USBx)->BTABLE)>>1) + x; - total_word_offset *= PMA_STRIDE; - return &(pma[total_word_offset]); +#ifdef PMA_32BIT_ACCESS + (void) USBx; + return pma32[2*bEpIdx] & 0x0000FFFFu ; +#else + return *pcd_btable_word_ptr(USBx,(bEpIdx)*4u + 0u); +#endif } -// Pointers to the PMA table entries (using the ARM address space) -TU_ATTR_ALWAYS_INLINE static inline __IO uint16_t* pcd_ep_tx_address_ptr(USB_TypeDef * USBx, uint32_t bEpIdx) +TU_ATTR_ALWAYS_INLINE static inline uint32_t pcd_get_ep_rx_address(USB_TypeDef * USBx, uint32_t bEpIdx) { - return pcd_btable_word_ptr(USBx,(bEpIdx)*4u + 0u); -} -TU_ATTR_ALWAYS_INLINE static inline __IO uint16_t* pcd_ep_tx_cnt_ptr(USB_TypeDef * USBx, uint32_t bEpIdx) -{ - return pcd_btable_word_ptr(USBx,(bEpIdx)*4u + 1u); +#ifdef PMA_32BIT_ACCESS + (void) USBx; + return pma32[2*bEpIdx + 1] & 0x0000FFFFu; +#else + return *pcd_btable_word_ptr(USBx,(bEpIdx)*4u + 2u); +#endif } -TU_ATTR_ALWAYS_INLINE static inline __IO uint16_t* pcd_ep_rx_address_ptr(USB_TypeDef * USBx, uint32_t bEpIdx) +TU_ATTR_ALWAYS_INLINE static inline void pcd_set_ep_tx_address(USB_TypeDef * USBx, uint32_t bEpIdx, uint32_t addr) { - return pcd_btable_word_ptr(USBx,(bEpIdx)*4u + 2u); +#ifdef PMA_32BIT_ACCESS + (void) USBx; + pma32[2*bEpIdx] = (pma32[2*bEpIdx] & 0xFFFF0000u) | (addr & 0x0000FFFCu); +#else + *pcd_btable_word_ptr(USBx,(bEpIdx)*4u + 0u) = addr; +#endif } -TU_ATTR_ALWAYS_INLINE static inline __IO uint16_t* pcd_ep_rx_cnt_ptr(USB_TypeDef * USBx, uint32_t bEpIdx) +TU_ATTR_ALWAYS_INLINE static inline void pcd_set_ep_rx_address(USB_TypeDef * USBx, uint32_t bEpIdx, uint32_t addr) { - return pcd_btable_word_ptr(USBx,(bEpIdx)*4u + 3u); +#ifdef PMA_32BIT_ACCESS + (void) USBx; + pma32[2*bEpIdx + 1] = (pma32[2*bEpIdx + 1] & 0xFFFF0000u) | (addr & 0x0000FFFCu); +#else + *pcd_btable_word_ptr(USBx,(bEpIdx)*4u + 2u) = addr; +#endif } -TU_ATTR_ALWAYS_INLINE static inline void pcd_set_ep_tx_cnt(USB_TypeDef * USBx, uint32_t bEpIdx, uint32_t wCount) +TU_ATTR_ALWAYS_INLINE static inline void pcd_set_ep_tx_cnt(USB_TypeDef * USBx, uint32_t bEpIdx, uint32_t wCount) { +#ifdef PMA_32BIT_ACCESS + (void) USBx; + pma32[2*bEpIdx] = (pma32[2*bEpIdx] & ~0x03FF0000u) | ((wCount & 0x3FFu) << 16); +#else __IO uint16_t * reg = pcd_ep_tx_cnt_ptr(USBx, bEpIdx); *reg = (uint16_t) (*reg & (uint16_t) ~0x3FFU) | (wCount & 0x3FFU); +#endif } -TU_ATTR_ALWAYS_INLINE static inline void pcd_set_ep_rx_cnt(USB_TypeDef * USBx, uint32_t bEpIdx, uint32_t wCount) +TU_ATTR_ALWAYS_INLINE static inline void pcd_set_ep_rx_cnt(USB_TypeDef * USBx, uint32_t bEpIdx, uint32_t wCount) { +#ifdef PMA_32BIT_ACCESS + (void) USBx; + pma32[2*bEpIdx + 1] = (pma32[2*bEpIdx + 1] & ~0x03FF0000u) | ((wCount & 0x3FFu) << 16); +#else __IO uint16_t * reg = pcd_ep_rx_cnt_ptr(USBx, bEpIdx); *reg = (uint16_t) (*reg & (uint16_t) ~0x3FFU) | (wCount & 0x3FFU); +#endif } -TU_ATTR_ALWAYS_INLINE static inline void pcd_set_ep_tx_bufsize(USB_TypeDef * USBx, uint32_t bEpIdx, uint32_t wCount) +TU_ATTR_ALWAYS_INLINE static inline void pcd_set_ep_blsize_num_blocks(USB_TypeDef * USBx, uint32_t rxtx_idx, uint32_t blocksize, uint32_t numblocks) { - __IO uint16_t *pdwReg = pcd_ep_tx_cnt_ptr((USBx),(bEpIdx)); - wCount = pcd_aligned_buffer_size(wCount); - pcd_set_ep_cnt_reg(pdwReg, wCount); + /* Encode into register. When BLSIZE==1, we need to subtract 1 block count */ +#ifdef PMA_32BIT_ACCESS + (void) USBx; + pma32[rxtx_idx] = (pma32[rxtx_idx] & 0x0000FFFFu) | (blocksize << 31) | ((numblocks - blocksize) << 26); +#else + __IO uint16_t *pdwReg = pcd_btable_word_ptr(USBx, rxtx_idx*2u + 1u); + *pdwReg = (blocksize << 15) | ((numblocks - blocksize) << 10); +#endif } -TU_ATTR_ALWAYS_INLINE static inline void pcd_set_ep_rx_bufsize(USB_TypeDef * USBx, uint32_t bEpIdx, uint32_t wCount) +TU_ATTR_ALWAYS_INLINE static inline void pcd_set_ep_bufsize(USB_TypeDef * USBx, uint32_t rxtx_idx, uint32_t wCount) { - __IO uint16_t *pdwReg = pcd_ep_rx_cnt_ptr((USBx),(bEpIdx)); wCount = pcd_aligned_buffer_size(wCount); - pcd_set_ep_cnt_reg(pdwReg, wCount); + + /* We assume that the buffer size is already aligned to hardware requirements. */ + uint16_t blocksize = (wCount > 62) ? 1 : 0; + uint16_t numblocks = wCount / (blocksize ? 32 : 2); + + /* There should be no remainder in the above calculation */ + TU_ASSERT((wCount - (numblocks * (blocksize ? 32 : 2))) == 0, /**/); + + /* Encode into register. When BLSIZE==1, we need to subtract 1 block count */ + pcd_set_ep_blsize_num_blocks(USBx, rxtx_idx, blocksize, numblocks); +} + +TU_ATTR_ALWAYS_INLINE static inline void pcd_set_ep_tx_bufsize(USB_TypeDef * USBx, uint32_t bEpIdx, uint32_t wCount) +{ + pcd_set_ep_bufsize(USBx, 2*bEpIdx, wCount); +} + +TU_ATTR_ALWAYS_INLINE static inline void pcd_set_ep_rx_bufsize(USB_TypeDef * USBx, uint32_t bEpIdx, uint32_t wCount) +{ + pcd_set_ep_bufsize(USBx, 2*bEpIdx + 1, wCount); } /** diff --git a/tools/cmake/cpu/cortex-m0plus.cmake b/tools/cmake/cpu/cortex-m0plus.cmake new file mode 100644 index 000000000..1e316ccfc --- /dev/null +++ b/tools/cmake/cpu/cortex-m0plus.cmake @@ -0,0 +1,11 @@ +if (TOOLCHAIN STREQUAL "gcc") + list(APPEND TOOLCHAIN_COMMON_FLAGS + -mthumb + -mcpu=cortex-m0plus + -mfloat-abi=soft + ) + + set(FREERTOS_PORT GCC_ARM_CM0 CACHE INTERNAL "") +else () + # TODO support IAR +endif () diff --git a/tools/get_deps.py b/tools/get_deps.py index b16bf7005..b4739e940 100644 --- a/tools/get_deps.py +++ b/tools/get_deps.py @@ -90,7 +90,7 @@ deps_optional = { 'fc676ef1ad177eb874eaa06444d3d75395fc51f4', 'stm32f7'], 'hw/mcu/st/cmsis_device_g0': ['https://github.com/STMicroelectronics/cmsis_device_g0.git', - '08258b28ee95f50cb9624d152a1cbf084be1f9a5', + '3a23e1224417f3f2d00300ecd620495e363f2094', 'stm32g0'], 'hw/mcu/st/cmsis_device_g4': ['https://github.com/STMicroelectronics/cmsis_device_g4.git', 'ce822adb1dc552b3aedd13621edbc7fdae124878', @@ -135,7 +135,7 @@ deps_optional = { 'f7ffdf6bf72110e58b42c632b0a051df5997e4ee', 'stm32f7'], 'hw/mcu/st/stm32g0xx_hal_driver': ['https://github.com/STMicroelectronics/stm32g0xx_hal_driver.git', - '5b53e6cee664a82b16c86491aa0060e2110c00cb', + 'e911b12c7f67084d7f6b76157a4c0d4e2ec3779c', 'stm32g0'], 'hw/mcu/st/stm32g4xx_hal_driver': ['https://github.com/STMicroelectronics/stm32g4xx_hal_driver.git', '8b4518417706d42eef5c14e56a650005abf478a8',