From ba9c774a2a5f784a85de1ca1212268b367046c03 Mon Sep 17 00:00:00 2001 From: hathach Date: Sat, 23 May 2020 13:29:30 +0700 Subject: [PATCH 01/48] board test work fine --- hw/bsp/stm32h743eval/STM32H743XIHx_FLASH.ld | 173 +++++++ hw/bsp/stm32h743eval/board.mk | 47 ++ hw/bsp/stm32h743eval/stm32h743eval.c | 274 +++++++++++ hw/bsp/stm32h743eval/stm32h7xx_hal_conf.h | 480 ++++++++++++++++++++ 4 files changed, 974 insertions(+) create mode 100644 hw/bsp/stm32h743eval/STM32H743XIHx_FLASH.ld create mode 100644 hw/bsp/stm32h743eval/board.mk create mode 100644 hw/bsp/stm32h743eval/stm32h743eval.c create mode 100644 hw/bsp/stm32h743eval/stm32h7xx_hal_conf.h diff --git a/hw/bsp/stm32h743eval/STM32H743XIHx_FLASH.ld b/hw/bsp/stm32h743eval/STM32H743XIHx_FLASH.ld new file mode 100644 index 000000000..59b9ff4df --- /dev/null +++ b/hw/bsp/stm32h743eval/STM32H743XIHx_FLASH.ld @@ -0,0 +1,173 @@ +/* +***************************************************************************** +** + +** File : LinkerScript.ld +** +** Abstract : Linker script for STM32H743XIHx Device with +** 2048KByte FLASH, 128KByte RAM +** +** Set heap size, stack size and stack location according +** to application requirements. +** +** Set memory bank area and size if external memory is used. +** +** Target : STMicroelectronics STM32 +** +** +** Distribution: The file is distributed as is, without any warranty +** of any kind. +** +** (c)Copyright Ac6. +** You may use this file as-is or modify it according to the needs of your +** project. Distribution of this file (unmodified or modified) is not +** permitted. Ac6 permit registered System Workbench for MCU users the +** rights to distribute the assembled, compiled & linked contents of this +** file as part of an application binary file, provided that it is built +** using the System Workbench for MCU toolchain. +** +***************************************************************************** +*/ + +/* Entry Point */ +ENTRY(Reset_Handler) + +/* Highest address of the user mode stack */ +_estack = 0x20020000; /* end of RAM */ +/* Generate a link error if heap and stack don't fit into RAM */ +_Min_Heap_Size = 0x200; /* required amount of heap */ +_Min_Stack_Size = 0x400; /* required amount of stack */ + +/* Specify the memory areas */ +MEMORY +{ +DTCMRAM (xrw) : ORIGIN = 0x20000000, LENGTH = 128K +RAM_D1 (xrw) : ORIGIN = 0x24000000, LENGTH = 512K +RAM_D2 (xrw) : ORIGIN = 0x30000000, LENGTH = 288K +RAM_D3 (xrw) : ORIGIN = 0x38000000, LENGTH = 64K +ITCMRAM (xrw) : ORIGIN = 0x00000000, LENGTH = 64K +FLASH (rx) : ORIGIN = 0x8000000, LENGTH = 2048K +} + +/* Define output sections */ +SECTIONS +{ + /* The startup code goes first into FLASH */ + .isr_vector : + { + . = ALIGN(4); + KEEP(*(.isr_vector)) /* Startup code */ + . = ALIGN(4); + } >FLASH + + /* The program code and other data goes into FLASH */ + .text : + { + . = ALIGN(4); + *(.text) /* .text sections (code) */ + *(.text*) /* .text* sections (code) */ + *(.glue_7) /* glue arm to thumb code */ + *(.glue_7t) /* glue thumb to arm code */ + *(.eh_frame) + + KEEP (*(.init)) + KEEP (*(.fini)) + + . = ALIGN(4); + _etext = .; /* define a global symbols at end of code */ + } >FLASH + + /* Constant data goes into FLASH */ + .rodata : + { + . = ALIGN(4); + *(.rodata) /* .rodata sections (constants, strings, etc.) */ + *(.rodata*) /* .rodata* sections (constants, strings, etc.) */ + . = ALIGN(4); + } >FLASH + + .ARM.extab : { *(.ARM.extab* .gnu.linkonce.armextab.*) } >FLASH + .ARM : { + __exidx_start = .; + *(.ARM.exidx*) + __exidx_end = .; + } >FLASH + + .preinit_array : + { + PROVIDE_HIDDEN (__preinit_array_start = .); + KEEP (*(.preinit_array*)) + PROVIDE_HIDDEN (__preinit_array_end = .); + } >FLASH + .init_array : + { + PROVIDE_HIDDEN (__init_array_start = .); + KEEP (*(SORT(.init_array.*))) + KEEP (*(.init_array*)) + PROVIDE_HIDDEN (__init_array_end = .); + } >FLASH + .fini_array : + { + PROVIDE_HIDDEN (__fini_array_start = .); + KEEP (*(SORT(.fini_array.*))) + KEEP (*(.fini_array*)) + PROVIDE_HIDDEN (__fini_array_end = .); + } >FLASH + + /* used by the startup to initialize data */ + _sidata = LOADADDR(.data); + + /* Initialized data sections goes into RAM, load LMA copy after code */ + .data : + { + . = ALIGN(4); + _sdata = .; /* create a global symbol at data start */ + *(.data) /* .data sections */ + *(.data*) /* .data* sections */ + + . = ALIGN(4); + _edata = .; /* define a global symbol at data end */ + } >DTCMRAM AT> FLASH + + + /* Uninitialized data section */ + . = ALIGN(4); + .bss : + { + /* This is used by the startup in order to initialize the .bss secion */ + _sbss = .; /* define a global symbol at bss start */ + __bss_start__ = _sbss; + *(.bss) + *(.bss*) + *(COMMON) + + . = ALIGN(4); + _ebss = .; /* define a global symbol at bss end */ + __bss_end__ = _ebss; + } >DTCMRAM + + /* User_heap_stack section, used to check that there is enough RAM left */ + ._user_heap_stack : + { + . = ALIGN(8); + PROVIDE ( end = . ); + PROVIDE ( _end = . ); + . = . + _Min_Heap_Size; + . = . + _Min_Stack_Size; + . = ALIGN(8); + } >DTCMRAM + + + + /* Remove information from the standard libraries */ + /DISCARD/ : + { + libc.a ( * ) + libm.a ( * ) + libgcc.a ( * ) + } + + .ARM.attributes 0 : { *(.ARM.attributes) } +} + + diff --git a/hw/bsp/stm32h743eval/board.mk b/hw/bsp/stm32h743eval/board.mk new file mode 100644 index 000000000..549249d24 --- /dev/null +++ b/hw/bsp/stm32h743eval/board.mk @@ -0,0 +1,47 @@ +CFLAGS += \ + -flto \ + -mthumb \ + -mabi=aapcs \ + -mcpu=cortex-m7 \ + -mfloat-abi=hard \ + -mfpu=fpv5-d16 \ + -nostdlib -nostartfiles \ + -DSTM32H743xx \ + -DCFG_TUSB_MCU=OPT_MCU_STM32H7 + +# suppress warning caused by vendor mcu driver +CFLAGS += -Wno-error=maybe-uninitialized + +ST_HAL_DRIVER = hw/mcu/st/st_driver/STM32H7xx_HAL_Driver +ST_CMSIS = hw/mcu/st/st_driver/CMSIS/Device/ST/STM32H7xx + +# All source paths should be relative to the top level. +LD_FILE = hw/bsp/$(BOARD)/STM32H743XIHx_FLASH.ld + +SRC_C += \ + $(ST_CMSIS)/Source/Templates/system_stm32h7xx.c \ + $(ST_HAL_DRIVER)/Src/stm32h7xx_hal.c \ + $(ST_HAL_DRIVER)/Src/stm32h7xx_hal_cortex.c \ + $(ST_HAL_DRIVER)/Src/stm32h7xx_hal_rcc.c \ + $(ST_HAL_DRIVER)/Src/stm32h7xx_hal_rcc_ex.c \ + $(ST_HAL_DRIVER)/Src/stm32h7xx_hal_gpio.c \ + $(ST_HAL_DRIVER)/Src/stm32h7xx_hal_pwr_ex.c + +SRC_S += \ + $(ST_CMSIS)/Source/Templates/gcc/startup_stm32h743xx.s + +INC += \ + $(TOP)/hw/mcu/st/st_driver/CMSIS/Include \ + $(TOP)/$(ST_CMSIS)/Include \ + $(TOP)/$(ST_HAL_DRIVER)/Inc \ + $(TOP)/hw/bsp/$(BOARD) + +# For TinyUSB port source +VENDOR = st +CHIP_FAMILY = synopsys + +# For freeRTOS port source +FREERTOS_PORT = ARM_CM7/r0p1 + +# flash target using on-board stlink +flash: flash-stlink diff --git a/hw/bsp/stm32h743eval/stm32h743eval.c b/hw/bsp/stm32h743eval/stm32h743eval.c new file mode 100644 index 000000000..ef9d575ac --- /dev/null +++ b/hw/bsp/stm32h743eval/stm32h743eval.c @@ -0,0 +1,274 @@ +/* + * The MIT License (MIT) + * + * Copyright (c) 2019 William D. Jones (thor0505@comcast.net), + * Ha Thach (tinyusb.org) + * + * Permission is hereby granted, free of charge, to any person obtaining a copy + * of this software and associated documentation files (the "Software"), to deal + * in the Software without restriction, including without limitation the rights + * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell + * copies of the Software, and to permit persons to whom the Software is + * furnished to do so, subject to the following conditions: + * + * The above copyright notice and this permission notice shall be included in + * all copies or substantial portions of the Software. + * + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR + * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE + * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER + * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, + * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN + * THE SOFTWARE. + * + * This file is part of the TinyUSB stack. + */ + +#include "../board.h" + +#include "stm32h7xx_hal.h" + +//--------------------------------------------------------------------+ +// Forward USB interrupt events to TinyUSB IRQ Handler +//--------------------------------------------------------------------+ +void OTG_FS_IRQHandler(void) +{ + tud_int_handler(0); +} + +//--------------------------------------------------------------------+ +// MACRO TYPEDEF CONSTANT ENUM +//--------------------------------------------------------------------+ + +#define LED_PORT GPIOA +#define LED_PIN GPIO_PIN_4 +#define LED_STATE_ON 1 + +// Tamper push-button +#define BUTTON_PORT GPIOC +#define BUTTON_PIN GPIO_PIN_13 +#define BUTTON_STATE_ACTIVE 0 + +// enable all LED, Button, Uart, USB clock +static void all_rcc_clk_enable(void) +{ + __HAL_RCC_GPIOA_CLK_ENABLE(); // LED, USB D+, D- + __HAL_RCC_GPIOC_CLK_ENABLE(); // Button +// __HAL_RCC_GPIOD_CLK_ENABLE(); // Uart tx, rx +// __HAL_RCC_USART3_CLK_ENABLE(); // Uart module +} + +/* PWR, RCC, GPIO (All): AHB4 (D3 domain) + USB{1,2} OTG_{H,F}S: AHB1 (D2 domain) +*/ + +/** + * @brief System Clock Configuration + * The system Clock is configured as follow : + * System Clock source = PLL (HSE) + * SYSCLK(Hz) = 400000000 (CPU Clock) + * HCLK(Hz) = 200000000 (AXI and AHBs Clock) + * AHB Prescaler = 2 + * D1 APB3 Prescaler = 2 (APB3 Clock 100MHz) + * D2 APB1 Prescaler = 2 (APB1 Clock 100MHz) + * D2 APB2 Prescaler = 2 (APB2 Clock 100MHz) + * D3 APB4 Prescaler = 2 (APB4 Clock 100MHz) + * HSE Frequency(Hz) = 25000000 + * PLL_M = 5 + * PLL_N = 160 + * PLL_P = 2 + * PLL_Q = 4 + * PLL_R = 2 + * PLL3_M = 25 + * PLL3_N = 336 + * PLL3_P = 2 + * PLL3_Q = 7 + * PLL3_R = 2 + * VDD(V) = 3.3 + * Flash Latency(WS) = 4 + * @param None + * @retval None + */ + +void SystemClock_Config(void) +{ + RCC_ClkInitTypeDef RCC_ClkInitStruct; + RCC_OscInitTypeDef RCC_OscInitStruct; + RCC_PeriphCLKInitTypeDef PeriphClkInitStruct; + + /*!< Supply configuration update enable */ + HAL_PWREx_ConfigSupply(PWR_LDO_SUPPLY); + + /* The voltage scaling allows optimizing the power consumption when the device is + clocked below the maximum system frequency, to update the voltage scaling value + regarding system frequency refer to product datasheet. */ + __HAL_PWR_VOLTAGESCALING_CONFIG(PWR_REGULATOR_VOLTAGE_SCALE1); + + while ((PWR->D3CR & (PWR_D3CR_VOSRDY)) != PWR_D3CR_VOSRDY) {} + + /* Enable HSE Oscillator and activate PLL with HSE as source */ + RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_HSE; + RCC_OscInitStruct.HSEState = RCC_HSE_ON; + RCC_OscInitStruct.HSIState = RCC_HSI_OFF; + RCC_OscInitStruct.CSIState = RCC_CSI_OFF; + RCC_OscInitStruct.PLL.PLLState = RCC_PLL_ON; + RCC_OscInitStruct.PLL.PLLSource = RCC_PLLSOURCE_HSE; + + /* PLL1 for System Clock */ + RCC_OscInitStruct.PLL.PLLM = 5; + RCC_OscInitStruct.PLL.PLLN = 160; + RCC_OscInitStruct.PLL.PLLFRACN = 0; + RCC_OscInitStruct.PLL.PLLP = 2; + RCC_OscInitStruct.PLL.PLLR = 2; + RCC_OscInitStruct.PLL.PLLQ = 4; + + RCC_OscInitStruct.PLL.PLLVCOSEL = RCC_PLL1VCOMEDIUM; + RCC_OscInitStruct.PLL.PLLRGE = RCC_PLL1VCIRANGE_2; + HAL_RCC_OscConfig(&RCC_OscInitStruct); + + /* PLL3 for USB Clock */ + PeriphClkInitStruct.PLL3.PLL3M = 25; + PeriphClkInitStruct.PLL3.PLL3N = 336; + PeriphClkInitStruct.PLL3.PLL3FRACN = 0; + PeriphClkInitStruct.PLL3.PLL3P = 2; + PeriphClkInitStruct.PLL3.PLL3R = 2; + PeriphClkInitStruct.PLL3.PLL3Q = 7; + + PeriphClkInitStruct.PeriphClockSelection = RCC_PERIPHCLK_USB; + PeriphClkInitStruct.UsbClockSelection = RCC_USBCLKSOURCE_PLL3; + HAL_RCCEx_PeriphCLKConfig(&PeriphClkInitStruct); + + /* Select PLL as system clock source and configure bus clocks dividers */ + RCC_ClkInitStruct.ClockType = (RCC_CLOCKTYPE_SYSCLK | RCC_CLOCKTYPE_HCLK | RCC_CLOCKTYPE_D1PCLK1 | RCC_CLOCKTYPE_PCLK1 | \ + RCC_CLOCKTYPE_PCLK2 | RCC_CLOCKTYPE_D3PCLK1); + + RCC_ClkInitStruct.SYSCLKSource = RCC_SYSCLKSOURCE_PLLCLK; + RCC_ClkInitStruct.SYSCLKDivider = RCC_SYSCLK_DIV1; + RCC_ClkInitStruct.AHBCLKDivider = RCC_HCLK_DIV2; + RCC_ClkInitStruct.APB1CLKDivider = RCC_APB1_DIV2; + RCC_ClkInitStruct.APB2CLKDivider = RCC_APB2_DIV2; + RCC_ClkInitStruct.APB3CLKDivider = RCC_APB3_DIV1; + HAL_RCC_ClockConfig(&RCC_ClkInitStruct, FLASH_LATENCY_4); + + /*activate CSI clock mondatory for I/O Compensation Cell*/ + __HAL_RCC_CSI_ENABLE() ; + + /* Enable SYSCFG clock mondatory for I/O Compensation Cell */ + __HAL_RCC_SYSCFG_CLK_ENABLE() ; + + /* Enables the I/O Compensation Cell */ + HAL_EnableCompensationCell(); +} + +void board_init(void) +{ + SystemClock_Config(); + all_rcc_clk_enable(); + + #if CFG_TUSB_OS == OPT_OS_NONE + // 1ms tick timer + SysTick_Config(SystemCoreClock / 1000); + #endif + + GPIO_InitTypeDef GPIO_InitStruct; + + // LED + GPIO_InitStruct.Pin = LED_PIN; + GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_PP; + GPIO_InitStruct.Pull = GPIO_PULLUP; + GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_HIGH; + HAL_GPIO_Init(LED_PORT, &GPIO_InitStruct); + + // Button + GPIO_InitStruct.Pin = BUTTON_PIN; + GPIO_InitStruct.Mode = GPIO_MODE_INPUT; + GPIO_InitStruct.Pull = GPIO_NOPULL; + GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_HIGH; + HAL_GPIO_Init(BUTTON_PORT, &GPIO_InitStruct); + + // USB Pin Init + // PA9- VUSB, PA10- ID, PA11- DM, PA12- DP + + /* Configure DM DP Pins */ + GPIO_InitStruct.Pin = GPIO_PIN_11 | GPIO_PIN_12; + GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_HIGH; + GPIO_InitStruct.Mode = GPIO_MODE_AF_PP; + GPIO_InitStruct.Pull = GPIO_NOPULL; + GPIO_InitStruct.Alternate = GPIO_AF10_OTG2_HS; + HAL_GPIO_Init(GPIOA, &GPIO_InitStruct); + + /* Configure VBUS Pin */ + GPIO_InitStruct.Pin = GPIO_PIN_9; + GPIO_InitStruct.Mode = GPIO_MODE_INPUT; + GPIO_InitStruct.Pull = GPIO_NOPULL; + HAL_GPIO_Init(GPIOA, &GPIO_InitStruct); + + /* This for ID line debug */ + GPIO_InitStruct.Pin = GPIO_PIN_10; + GPIO_InitStruct.Mode = GPIO_MODE_AF_OD; + GPIO_InitStruct.Pull = GPIO_PULLUP; + GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_HIGH; + GPIO_InitStruct.Alternate = GPIO_AF10_OTG2_HS; + HAL_GPIO_Init(GPIOA, &GPIO_InitStruct); + + // https://community.st.com/s/question/0D50X00009XkYZLSA3/stm32h7-nucleo-usb-fs-cdc + // TODO: Board init actually works fine without this line. + HAL_PWREx_EnableUSBVoltageDetector(); + __HAL_RCC_USB2_OTG_FS_CLK_ENABLE(); + + // Enable VBUS sense (B device) via pin PA9 + USB_OTG_FS->GCCFG |= USB_OTG_GCCFG_VBDEN; +} + +//--------------------------------------------------------------------+ +// Board porting API +//--------------------------------------------------------------------+ + +void board_led_write(bool state) +{ + HAL_GPIO_WritePin(LED_PORT, LED_PIN, state); +} + +uint32_t board_button_read(void) +{ + return (BUTTON_STATE_ACTIVE == HAL_GPIO_ReadPin(BUTTON_PORT, BUTTON_PIN)) ? 1 : 0; +} + +int board_uart_read(uint8_t* buf, int len) +{ + (void) buf; (void) len; + return 0; +} + +int board_uart_write(void const * buf, int len) +{ + (void) buf; (void) len; + return 0; +} + + +#if CFG_TUSB_OS == OPT_OS_NONE +volatile uint32_t system_ticks = 0; +void SysTick_Handler (void) +{ + system_ticks++; +} + +uint32_t board_millis(void) +{ + return system_ticks; +} +#endif + +void HardFault_Handler (void) +{ + asm("bkpt"); +} + +// Required by __libc_init_array in startup code if we are compiling using +// -nostdlib/-nostartfiles. +void _init(void) +{ + +} diff --git a/hw/bsp/stm32h743eval/stm32h7xx_hal_conf.h b/hw/bsp/stm32h743eval/stm32h7xx_hal_conf.h new file mode 100644 index 000000000..2a9eb37ae --- /dev/null +++ b/hw/bsp/stm32h743eval/stm32h7xx_hal_conf.h @@ -0,0 +1,480 @@ +/** + ****************************************************************************** + * @file stm32h7xx_hal_conf_template.h + * @brief HAL configuration template file. + * This file should be copied to the application folder and renamed + * to stm32h7xx_hal_conf.h. + ****************************************************************************** + * @attention + * + *

© COPYRIGHT(c) 2019 STMicroelectronics

+ * + * Redistribution and use in source and binary forms, with or without modification, + * are permitted provided that the following conditions are met: + * 1. Redistributions of source code must retain the above copyright notice, + * this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * 3. Neither the name of STMicroelectronics nor the names of its contributors + * may be used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE + * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE + * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR + * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, + * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE + * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __STM32H7xx_HAL_CONF_H +#define __STM32H7xx_HAL_CONF_H + +#ifdef __cplusplus + extern "C" { +#endif + +/* Exported types ------------------------------------------------------------*/ +/* Exported constants --------------------------------------------------------*/ + +/* ########################## Module Selection ############################## */ +/** + * @brief This is the list of modules to be used in the HAL driver + */ +#define HAL_MODULE_ENABLED +#define HAL_ADC_MODULE_ENABLED +/* #define HAL_CEC_MODULE_ENABLED */ +/* #define HAL_COMP_MODULE_ENABLED */ +#define HAL_CORTEX_MODULE_ENABLED +/* #define HAL_CRC_MODULE_ENABLED */ +/* #define HAL_CRYP_MODULE_ENABLED */ +/* #define HAL_DAC_MODULE_ENABLED */ +/* #define HAL_DCMI_MODULE_ENABLED */ +/* #define HAL_DFSDM_MODULE_ENABLED */ +#define HAL_DMA_MODULE_ENABLED +/* #define HAL_DMA2D_MODULE_ENABLED */ +/* #define HAL_ETH_MODULE_ENABLED */ +/* #define HAL_EXTI_MODULE_ENABLED */ +/* #define HAL_FDCAN_MODULE_ENABLED */ +#define HAL_FLASH_MODULE_ENABLED +#define HAL_GPIO_MODULE_ENABLED +/* #define HAL_HASH_MODULE_ENABLED */ +/* #define HAL_HCD_MODULE_ENABLED */ +/* #define HAL_HRTIM_MODULE_ENABLED */ +/* #define HAL_HSEM_MODULE_ENABLED */ +/* #define HAL_I2C_MODULE_ENABLED */ +/* #define HAL_I2S_MODULE_ENABLED */ +/* #define HAL_IRDA_MODULE_ENABLED */ +/* #define HAL_IWDG_MODULE_ENABLED */ +/* #define HAL_JPEG_MODULE_ENABLED */ +/* #define HAL_LPTIM_MODULE_ENABLED */ +/* #define HAL_LTDC_MODULE_ENABLED */ +/* #define HAL_MDIOS_MODULE_ENABLED */ +/* #define HAL_MDMA_MODULE_ENABLED */ +/* #define HAL_MMC_MODULE_ENABLED */ +/* #define HAL_NAND_MODULE_ENABLED */ +/* #define HAL_NOR_MODULE_ENABLED */ +/* #define HAL_OPAMP_MODULE_ENABLED */ +/* #define HAL_PCD_MODULE_ENABLED */ +#define HAL_PWR_MODULE_ENABLED +/* #define HAL_QSPI_MODULE_ENABLED */ +/* #define HAL_RAMECC_MODULE_ENABLED */ +#define HAL_RCC_MODULE_ENABLED +/* #define HAL_RNG_MODULE_ENABLED */ +/* #define HAL_RTC_MODULE_ENABLED */ +/* #define HAL_SAI_MODULE_ENABLED */ +/* #define HAL_SD_MODULE_ENABLED */ +/* #define HAL_SDRAM_MODULE_ENABLED */ +/* #define HAL_SMARTCARD_MODULE_ENABLED */ +/* #define HAL_SMBUS_MODULE_ENABLED */ +/* #define HAL_SPDIFRX_MODULE_ENABLED */ +#define HAL_SPI_MODULE_ENABLED +/* #define HAL_SRAM_MODULE_ENABLED */ +/* #define HAL_SWPMI_MODULE_ENABLED */ +/* #define HAL_TIM_MODULE_ENABLED */ +/* #define HAL_UART_MODULE_ENABLED */ +/* #define HAL_USART_MODULE_ENABLED */ +/* #define HAL_WWDG_MODULE_ENABLED */ + +/* ########################## Oscillator Values adaptation ####################*/ +/** + * @brief Adjust the value of External High Speed oscillator (HSE) used in your application. + * This value is used by the RCC HAL module to compute the system frequency + * (when HSE is used as system clock source, directly or through the PLL). + */ +#if !defined (HSE_VALUE) +#define HSE_VALUE ((uint32_t)25000000) /*!< Value of the External oscillator in Hz */ +#endif /* HSE_VALUE */ + +#if !defined (HSE_STARTUP_TIMEOUT) + #define HSE_STARTUP_TIMEOUT ((uint32_t)5000) /*!< Time out for HSE start up, in ms */ +#endif /* HSE_STARTUP_TIMEOUT */ + +/** + * @brief Internal oscillator (CSI) default value. + * This value is the default CSI value after Reset. + */ +#if !defined (CSI_VALUE) + #define CSI_VALUE ((uint32_t)4000000) /*!< Value of the Internal oscillator in Hz*/ +#endif /* CSI_VALUE */ + +/** + * @brief Internal High Speed oscillator (HSI) value. + * This value is used by the RCC HAL module to compute the system frequency + * (when HSI is used as system clock source, directly or through the PLL). + */ +#if !defined (HSI_VALUE) + #define HSI_VALUE ((uint32_t)64000000) /*!< Value of the Internal oscillator in Hz*/ +#endif /* HSI_VALUE */ + +/** + * @brief External Low Speed oscillator (LSE) value. + * This value is used by the UART, RTC HAL module to compute the system frequency + */ +#if !defined (LSE_VALUE) + #define LSE_VALUE ((uint32_t)32768) /*!< Value of the External oscillator in Hz*/ +#endif /* LSE_VALUE */ + + +#if !defined (LSE_STARTUP_TIMEOUT) + #define LSE_STARTUP_TIMEOUT ((uint32_t)5000) /*!< Time out for LSE start up, in ms */ +#endif /* LSE_STARTUP_TIMEOUT */ + +#if !defined (LSI_VALUE) + #define LSI_VALUE ((uint32_t)32000) /*!< 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 clock source for I2S peripheral + * This value is used by the I2S HAL module to compute the I2S clock source + * frequency, this source is inserted directly through I2S_CKIN pad. + */ +#if !defined (EXTERNAL_CLOCK_VALUE) + #define EXTERNAL_CLOCK_VALUE 12288000U /*!< Value of the External clock in Hz*/ +#endif /* EXTERNAL_CLOCK_VALUE */ + +/* Tip: To avoid modifying this file each time you need to use different HSE, + === you can define the HSE value in your toolchain compiler preprocessor. */ + +/* ########################### System Configuration ######################### */ +/** + * @brief This is the HAL system configuration section + */ +#define VDD_VALUE ((uint32_t)3300) /*!< Value of VDD in mv */ +#define TICK_INT_PRIORITY ((uint32_t)0x0F) /*!< tick interrupt priority */ +#define USE_RTOS 0 +#define USE_SD_TRANSCEIVER 1U /*!< use uSD Transceiver */ +#define USE_SPI_CRC 1U /*!< use CRC in SPI */ + +#define USE_HAL_ADC_REGISTER_CALLBACKS 0U /* ADC register callback disabled */ +#define USE_HAL_CEC_REGISTER_CALLBACKS 0U /* CEC register callback disabled */ +#define USE_HAL_COMP_REGISTER_CALLBACKS 0U /* COMP register callback disabled */ +#define USE_HAL_CRYP_REGISTER_CALLBACKS 0U /* CRYP register callback disabled */ +#define USE_HAL_DAC_REGISTER_CALLBACKS 0U /* DAC register callback disabled */ +#define USE_HAL_DCMI_REGISTER_CALLBACKS 0U /* DCMI register callback disabled */ +#define USE_HAL_DFSDM_REGISTER_CALLBACKS 0U /* DFSDM register callback disabled */ +#define USE_HAL_DMA2D_REGISTER_CALLBACKS 0U /* DMA2D register callback disabled */ +#define USE_HAL_DSI_REGISTER_CALLBACKS 0U /* DSI register callback disabled */ +#define USE_HAL_ETH_REGISTER_CALLBACKS 0U /* ETH register callback disabled */ +#define USE_HAL_FDCAN_REGISTER_CALLBACKS 0U /* FDCAN register callback disabled */ +#define USE_HAL_NAND_REGISTER_CALLBACKS 0U /* NAND register callback disabled */ +#define USE_HAL_NOR_REGISTER_CALLBACKS 0U /* NOR register callback disabled */ +#define USE_HAL_SDRAM_REGISTER_CALLBACKS 0U /* SDRAM register callback disabled */ +#define USE_HAL_SRAM_REGISTER_CALLBACKS 0U /* SRAM register callback disabled */ +#define USE_HAL_HASH_REGISTER_CALLBACKS 0U /* HASH register callback disabled */ +#define USE_HAL_HCD_REGISTER_CALLBACKS 0U /* HCD register callback disabled */ +#define USE_HAL_HRTIM_REGISTER_CALLBACKS 0U /* HRTIM register callback disabled */ +#define USE_HAL_I2C_REGISTER_CALLBACKS 0U /* I2C register callback disabled */ +#define USE_HAL_I2S_REGISTER_CALLBACKS 0U /* I2S register callback disabled */ +#define USE_HAL_JPEG_REGISTER_CALLBACKS 0U /* JPEG register callback disabled */ +#define USE_HAL_LPTIM_REGISTER_CALLBACKS 0U /* LPTIM register callback disabled */ +#define USE_HAL_LTDC_REGISTER_CALLBACKS 0U /* LTDC register callback disabled */ +#define USE_HAL_MDIOS_REGISTER_CALLBACKS 0U /* MDIO register callback disabled */ +#define USE_HAL_OPAMP_REGISTER_CALLBACKS 0U /* MDIO register callback disabled */ +#define USE_HAL_PCD_REGISTER_CALLBACKS 0U /* PCD register callback disabled */ +#define USE_HAL_QSPI_REGISTER_CALLBACKS 0U /* QSPI register callback disabled */ +#define USE_HAL_RNG_REGISTER_CALLBACKS 0U /* RNG register callback disabled */ +#define USE_HAL_RTC_REGISTER_CALLBACKS 0U /* RTC register callback disabled */ +#define USE_HAL_SAI_REGISTER_CALLBACKS 0U /* SAI register callback disabled */ +#define USE_HAL_SPDIFRX_REGISTER_CALLBACKS 0U /* SPDIFRX register callback disabled */ +#define USE_HAL_SMBUS_REGISTER_CALLBACKS 0U /* SMBUS register callback disabled */ +#define USE_HAL_SPI_REGISTER_CALLBACKS 0U /* SPI register callback disabled */ +#define USE_HAL_SWPMI_REGISTER_CALLBACKS 0U /* SWPMI register callback disabled */ +#define USE_HAL_TIM_REGISTER_CALLBACKS 0U /* TIM register callback disabled */ +#define USE_HAL_WWDG_REGISTER_CALLBACKS 0U /* WWDG register callback disabled */ + +/* ########################### Ethernet Configuration ######################### */ +#define ETH_TX_DESC_CNT 4 /* number of Ethernet Tx DMA descriptors */ +#define ETH_RX_DESC_CNT 4 /* number of Ethernet Rx DMA descriptors */ + +#define ETH_MAC_ADDR0 ((uint8_t)0x02) +#define ETH_MAC_ADDR1 ((uint8_t)0x00) +#define ETH_MAC_ADDR2 ((uint8_t)0x00) +#define ETH_MAC_ADDR3 ((uint8_t)0x00) +#define ETH_MAC_ADDR4 ((uint8_t)0x00) +#define ETH_MAC_ADDR5 ((uint8_t)0x00) + +/* ########################## Assert Selection ############################## */ +/** + * @brief Uncomment the line below to expanse the "assert_param" macro in the + * HAL drivers code + */ +/* #define USE_FULL_ASSERT 1 */ + + +/* Includes ------------------------------------------------------------------*/ +/** + * @brief Include module's header file + */ + +#ifdef HAL_RCC_MODULE_ENABLED + #include "stm32h7xx_hal_rcc.h" +#endif /* HAL_RCC_MODULE_ENABLED */ + +#ifdef HAL_GPIO_MODULE_ENABLED + #include "stm32h7xx_hal_gpio.h" +#endif /* HAL_GPIO_MODULE_ENABLED */ + +#ifdef HAL_DMA_MODULE_ENABLED + #include "stm32h7xx_hal_dma.h" +#endif /* HAL_DMA_MODULE_ENABLED */ + +#ifdef HAL_MDMA_MODULE_ENABLED + #include "stm32h7xx_hal_mdma.h" +#endif /* HAL_MDMA_MODULE_ENABLED */ + +#ifdef HAL_HASH_MODULE_ENABLED + #include "stm32h7xx_hal_hash.h" +#endif /* HAL_HASH_MODULE_ENABLED */ + +#ifdef HAL_DCMI_MODULE_ENABLED + #include "stm32h7xx_hal_dcmi.h" +#endif /* HAL_DCMI_MODULE_ENABLED */ + +#ifdef HAL_DMA2D_MODULE_ENABLED + #include "stm32h7xx_hal_dma2d.h" +#endif /* HAL_DMA2D_MODULE_ENABLED */ + +#ifdef HAL_DSI_MODULE_ENABLED + #include "stm32h7xx_hal_dsi.h" +#endif /* HAL_DSI_MODULE_ENABLED */ + +#ifdef HAL_DFSDM_MODULE_ENABLED + #include "stm32h7xx_hal_dfsdm.h" +#endif /* HAL_DFSDM_MODULE_ENABLED */ + +#ifdef HAL_ETH_MODULE_ENABLED + #include "stm32h7xx_hal_eth.h" +#endif /* HAL_ETH_MODULE_ENABLED */ + +#ifdef HAL_EXTI_MODULE_ENABLED + #include "stm32h7xx_hal_exti.h" +#endif /* HAL_EXTI_MODULE_ENABLED */ + +#ifdef HAL_CORTEX_MODULE_ENABLED + #include "stm32h7xx_hal_cortex.h" +#endif /* HAL_CORTEX_MODULE_ENABLED */ + +#ifdef HAL_ADC_MODULE_ENABLED + #include "stm32h7xx_hal_adc.h" +#endif /* HAL_ADC_MODULE_ENABLED */ + +#ifdef HAL_FDCAN_MODULE_ENABLED + #include "stm32h7xx_hal_fdcan.h" +#endif /* HAL_FDCAN_MODULE_ENABLED */ + +#ifdef HAL_CEC_MODULE_ENABLED + #include "stm32h7xx_hal_cec.h" +#endif /* HAL_CEC_MODULE_ENABLED */ + +#ifdef HAL_COMP_MODULE_ENABLED + #include "stm32h7xx_hal_comp.h" +#endif /* HAL_COMP_MODULE_ENABLED */ + +#ifdef HAL_CRC_MODULE_ENABLED + #include "stm32h7xx_hal_crc.h" +#endif /* HAL_CRC_MODULE_ENABLED */ + +#ifdef HAL_CRYP_MODULE_ENABLED + #include "stm32h7xx_hal_cryp.h" +#endif /* HAL_CRYP_MODULE_ENABLED */ + +#ifdef HAL_DAC_MODULE_ENABLED + #include "stm32h7xx_hal_dac.h" +#endif /* HAL_DAC_MODULE_ENABLED */ + +#ifdef HAL_FLASH_MODULE_ENABLED + #include "stm32h7xx_hal_flash.h" +#endif /* HAL_FLASH_MODULE_ENABLED */ + +#ifdef HAL_HRTIM_MODULE_ENABLED + #include "stm32h7xx_hal_hrtim.h" +#endif /* HAL_HRTIM_MODULE_ENABLED */ + +#ifdef HAL_HSEM_MODULE_ENABLED + #include "stm32h7xx_hal_hsem.h" +#endif /* HAL_HSEM_MODULE_ENABLED */ + +#ifdef HAL_SRAM_MODULE_ENABLED + #include "stm32h7xx_hal_sram.h" +#endif /* HAL_SRAM_MODULE_ENABLED */ + +#ifdef HAL_NOR_MODULE_ENABLED + #include "stm32h7xx_hal_nor.h" +#endif /* HAL_NOR_MODULE_ENABLED */ + +#ifdef HAL_NAND_MODULE_ENABLED + #include "stm32h7xx_hal_nand.h" +#endif /* HAL_NAND_MODULE_ENABLED */ + +#ifdef HAL_I2C_MODULE_ENABLED + #include "stm32h7xx_hal_i2c.h" +#endif /* HAL_I2C_MODULE_ENABLED */ + +#ifdef HAL_I2S_MODULE_ENABLED + #include "stm32h7xx_hal_i2s.h" +#endif /* HAL_I2S_MODULE_ENABLED */ + +#ifdef HAL_IWDG_MODULE_ENABLED + #include "stm32h7xx_hal_iwdg.h" +#endif /* HAL_IWDG_MODULE_ENABLED */ + +#ifdef HAL_JPEG_MODULE_ENABLED + #include "stm32h7xx_hal_jpeg.h" +#endif /* HAL_JPEG_MODULE_ENABLED */ + +#ifdef HAL_MDIOS_MODULE_ENABLED + #include "stm32h7xx_hal_mdios.h" +#endif /* HAL_MDIOS_MODULE_ENABLED */ + +#ifdef HAL_MMC_MODULE_ENABLED + #include "stm32h7xx_hal_mmc.h" +#endif /* HAL_MMC_MODULE_ENABLED */ + +#ifdef HAL_LPTIM_MODULE_ENABLED +#include "stm32h7xx_hal_lptim.h" +#endif /* HAL_LPTIM_MODULE_ENABLED */ + +#ifdef HAL_LTDC_MODULE_ENABLED +#include "stm32h7xx_hal_ltdc.h" +#endif /* HAL_LTDC_MODULE_ENABLED */ + +#ifdef HAL_OPAMP_MODULE_ENABLED +#include "stm32h7xx_hal_opamp.h" +#endif /* HAL_OPAMP_MODULE_ENABLED */ + +#ifdef HAL_PWR_MODULE_ENABLED + #include "stm32h7xx_hal_pwr.h" +#endif /* HAL_PWR_MODULE_ENABLED */ + +#ifdef HAL_QSPI_MODULE_ENABLED + #include "stm32h7xx_hal_qspi.h" +#endif /* HAL_QSPI_MODULE_ENABLED */ + +#ifdef HAL_RAMECC_MODULE_ENABLED + #include "stm32h7xx_hal_ramecc.h" +#endif /* HAL_HCD_MODULE_ENABLED */ + +#ifdef HAL_RNG_MODULE_ENABLED + #include "stm32h7xx_hal_rng.h" +#endif /* HAL_RNG_MODULE_ENABLED */ + +#ifdef HAL_RTC_MODULE_ENABLED + #include "stm32h7xx_hal_rtc.h" +#endif /* HAL_RTC_MODULE_ENABLED */ + +#ifdef HAL_SAI_MODULE_ENABLED + #include "stm32h7xx_hal_sai.h" +#endif /* HAL_SAI_MODULE_ENABLED */ + +#ifdef HAL_SD_MODULE_ENABLED + #include "stm32h7xx_hal_sd.h" +#endif /* HAL_SD_MODULE_ENABLED */ + +#ifdef HAL_SDRAM_MODULE_ENABLED + #include "stm32h7xx_hal_sdram.h" +#endif /* HAL_SDRAM_MODULE_ENABLED */ + +#ifdef HAL_SPI_MODULE_ENABLED + #include "stm32h7xx_hal_spi.h" +#endif /* HAL_SPI_MODULE_ENABLED */ + +#ifdef HAL_SPDIFRX_MODULE_ENABLED + #include "stm32h7xx_hal_spdifrx.h" +#endif /* HAL_SPDIFRX_MODULE_ENABLED */ + +#ifdef HAL_SWPMI_MODULE_ENABLED + #include "stm32h7xx_hal_swpmi.h" +#endif /* HAL_SWPMI_MODULE_ENABLED */ + +#ifdef HAL_TIM_MODULE_ENABLED + #include "stm32h7xx_hal_tim.h" +#endif /* HAL_TIM_MODULE_ENABLED */ + +#ifdef HAL_UART_MODULE_ENABLED + #include "stm32h7xx_hal_uart.h" +#endif /* HAL_UART_MODULE_ENABLED */ + +#ifdef HAL_USART_MODULE_ENABLED + #include "stm32h7xx_hal_usart.h" +#endif /* HAL_USART_MODULE_ENABLED */ + +#ifdef HAL_IRDA_MODULE_ENABLED + #include "stm32h7xx_hal_irda.h" +#endif /* HAL_IRDA_MODULE_ENABLED */ + +#ifdef HAL_SMARTCARD_MODULE_ENABLED + #include "stm32h7xx_hal_smartcard.h" +#endif /* HAL_SMARTCARD_MODULE_ENABLED */ + +#ifdef HAL_SMBUS_MODULE_ENABLED + #include "stm32h7xx_hal_smbus.h" +#endif /* HAL_SMBUS_MODULE_ENABLED */ + +#ifdef HAL_WWDG_MODULE_ENABLED + #include "stm32h7xx_hal_wwdg.h" +#endif /* HAL_WWDG_MODULE_ENABLED */ + +#ifdef HAL_PCD_MODULE_ENABLED + #include "stm32h7xx_hal_pcd.h" +#endif /* HAL_PCD_MODULE_ENABLED */ + +#ifdef HAL_HCD_MODULE_ENABLED + #include "stm32h7xx_hal_hcd.h" +#endif /* HAL_HCD_MODULE_ENABLED */ + +/* Exported macro ------------------------------------------------------------*/ +#ifdef USE_FULL_ASSERT +/** + * @brief The assert_param macro is used for function's parameters check. + * @param expr: If expr is false, it calls assert_failed function + * which reports the name of the source file and the source + * line number of the call that failed. + * If expr is true, it returns no value. + * @retval None + */ + #define assert_param(expr) ((expr) ? (void)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 /* __STM32H7xx_HAL_CONF_H */ + + +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ From 62a746bdc7dc677cabeba9ef6f1dd974de1c0791 Mon Sep 17 00:00:00 2001 From: hathach Date: Tue, 26 May 2020 12:18:18 +0700 Subject: [PATCH 02/48] wip --- hw/bsp/stm32h743eval/board.mk | 7 ++++++- hw/bsp/stm32h743eval/stm32h743eval.c | 13 +++++++++++-- 2 files changed, 17 insertions(+), 3 deletions(-) diff --git a/hw/bsp/stm32h743eval/board.mk b/hw/bsp/stm32h743eval/board.mk index 549249d24..5044cdc08 100644 --- a/hw/bsp/stm32h743eval/board.mk +++ b/hw/bsp/stm32h743eval/board.mk @@ -7,7 +7,12 @@ CFLAGS += \ -mfpu=fpv5-d16 \ -nostdlib -nostartfiles \ -DSTM32H743xx \ - -DCFG_TUSB_MCU=OPT_MCU_STM32H7 + -DCFG_TUSB_MCU=OPT_MCU_STM32H7 \ + +# Board specific for using usb ports +CFLAGS += \ + -DCFG_BOARD_DEVICE_RHPORT_NUM=1 \ + -DCFG_BOARD_DEVICE_RHPORT_HIGHSPEED # suppress warning caused by vendor mcu driver CFLAGS += -Wno-error=maybe-uninitialized diff --git a/hw/bsp/stm32h743eval/stm32h743eval.c b/hw/bsp/stm32h743eval/stm32h743eval.c index ef9d575ac..5a7934ea2 100644 --- a/hw/bsp/stm32h743eval/stm32h743eval.c +++ b/hw/bsp/stm32h743eval/stm32h743eval.c @@ -187,8 +187,16 @@ void board_init(void) GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_HIGH; HAL_GPIO_Init(BUTTON_PORT, &GPIO_InitStruct); - // USB Pin Init - // PA9- VUSB, PA10- ID, PA11- DM, PA12- DP +#if CFG_TUSB_RHPORT0_MODE & OPT_MODE_DEVICE + + // USB1 HS (ULPI Phy), internal FS PHY + // PB12 ID, PB13 VBUS, PB14 DM, PB15 DP + +#endif + +#if CFG_TUSB_RHPORT1_MODE & OPT_MODE_DEVICE + // USB2 FS Pin Init + // PA9 VUSB, PA10 ID, PA11 DM, PA12 DP /* Configure DM DP Pins */ GPIO_InitStruct.Pin = GPIO_PIN_11 | GPIO_PIN_12; @@ -219,6 +227,7 @@ void board_init(void) // Enable VBUS sense (B device) via pin PA9 USB_OTG_FS->GCCFG |= USB_OTG_GCCFG_VBDEN; +#endif } //--------------------------------------------------------------------+ From fad088719e7cc4d1cab9216eb81567dd67af65f7 Mon Sep 17 00:00:00 2001 From: hathach Date: Tue, 26 May 2020 15:21:23 +0700 Subject: [PATCH 03/48] merge CFG_TUSB_RHPORT1_MODE into CFG_TUSB_RHPORT0_MODE each port is 1 byte for easy maintenance --- examples/device/cdc_msc/src/tusb_config.h | 25 ++++++++---- hw/bsp/ea4357/ea4357.c | 8 ++-- hw/bsp/mcb1800/mcb1800.c | 8 ++-- hw/bsp/mimxrt1050_evkb/mimxrt1050_evkb.c | 4 +- hw/bsp/mimxrt1060_evk/mimxrt1060_evk.c | 4 +- hw/bsp/mimxrt1064_evk/mimxrt1064_evk.c | 4 +- hw/bsp/ngx4330/ngx4330.c | 8 ++-- hw/bsp/teensy_40/teensy40.c | 4 +- src/tusb_option.h | 50 +++++++++++++---------- 9 files changed, 66 insertions(+), 49 deletions(-) diff --git a/examples/device/cdc_msc/src/tusb_config.h b/examples/device/cdc_msc/src/tusb_config.h index 09e98b247..9beb9f6a2 100644 --- a/examples/device/cdc_msc/src/tusb_config.h +++ b/examples/device/cdc_msc/src/tusb_config.h @@ -34,19 +34,30 @@ // COMMON CONFIGURATION //-------------------------------------------------------------------- -// defined by compiler flags for flexibility +// defined by board.mk #ifndef CFG_TUSB_MCU #error CFG_TUSB_MCU must be defined #endif -#if CFG_TUSB_MCU == OPT_MCU_LPC18XX || CFG_TUSB_MCU == OPT_MCU_LPC43XX || CFG_TUSB_MCU == OPT_MCU_MIMXRT10XX || \ - CFG_TUSB_MCU == OPT_MCU_NUC505 || CFG_TUSB_MCU == OPT_MCU_CXD56 - #define CFG_TUSB_RHPORT0_MODE (OPT_MODE_DEVICE | OPT_MODE_HIGH_SPEED) -#else - #define CFG_TUSB_RHPORT0_MODE OPT_MODE_DEVICE +// RHPort number used for device can be defined by board.mk, default to port 0 +#ifndef BOARD_DEVICE_RHPORT_NUM + #define BOARD_DEVICE_RHPORT_NUM 0 #endif -#define CFG_TUSB_OS OPT_OS_NONE +// RHPort max operational speed can defined by board.mk +// Default to Highspeed for MCU with internal HighSpeed PHY (can be port specific), otherwise FullSpeed +#ifndef BOARD_DEVICE_RHPORT_SPEED + #if (CFG_TUSB_MCU == OPT_MCU_LPC18XX || CFG_TUSB_MCU == OPT_MCU_LPC43XX || CFG_TUSB_MCU == OPT_MCU_MIMXRT10XX || \ + CFG_TUSB_MCU == OPT_MCU_NUC505 || CFG_TUSB_MCU == OPT_MCU_CXD56) + #define BOARD_DEVICE_RHPORT_SPEED OPT_MODE_HIGH_SPEED + #else + #define BOARD_DEVICE_RHPORT_SPEED OPT_MODE_FULL_SPEED + #endif +#endif + +// Device mode with rhport and speed defined by board.mk +#define CFG_TUSB_RHPORT0_MODE ((OPT_MODE_DEVICE | BOARD_DEVICE_RHPORT_SPEED) << (8*BOARD_DEVICE_RHPORT_NUM)) +#define CFG_TUSB_OS OPT_OS_NONE // CFG_TUSB_DEBUG is defined by compiler in DEBUG build // #define CFG_TUSB_DEBUG 0 diff --git a/hw/bsp/ea4357/ea4357.c b/hw/bsp/ea4357/ea4357.c index b7e7f7a5c..04c4e60a6 100644 --- a/hw/bsp/ea4357/ea4357.c +++ b/hw/bsp/ea4357/ea4357.c @@ -149,7 +149,7 @@ void board_init(void) * status feedback from the distribution switch. GPIO54 is used for VBUS sensing. 15Kohm pull-down * resistors are always active */ -#if CFG_TUSB_RHPORT0_MODE +#if CFG_TUSB_RHPORT0_MODE & (OPT_MODE_DEVICE | OPT_MODE_HOST) Chip_USB0_Init(); // // Reset controller @@ -185,7 +185,7 @@ void board_init(void) * of VBUS can be read via U31. * JP16 shall not be inserted. */ -#if CFG_TUSB_RHPORT1_MODE +#if CFG_TUSB_RHPORT0_MODE & ((OPT_MODE_DEVICE | OPT_MODE_HOST) << 8) Chip_USB1_Init(); // // Reset controller @@ -232,11 +232,11 @@ void USB0_IRQHandler(void) void USB1_IRQHandler(void) { - #if CFG_TUSB_RHPORT1_MODE & OPT_MODE_HOST + #if CFG_TUSB_RHPORT0_MODE & (OPT_MODE_HOST << 8) tuh_isr(1); #endif - #if CFG_TUSB_RHPORT1_MODE & OPT_MODE_DEVICE + #if CFG_TUSB_RHPORT0_MODE & (OPT_MODE_DEVICE << 8) tud_int_handler(1); #endif } diff --git a/hw/bsp/mcb1800/mcb1800.c b/hw/bsp/mcb1800/mcb1800.c index ae9f1b62f..6387f983e 100644 --- a/hw/bsp/mcb1800/mcb1800.c +++ b/hw/bsp/mcb1800/mcb1800.c @@ -43,11 +43,11 @@ void USB0_IRQHandler(void) void USB1_IRQHandler(void) { - #if CFG_TUSB_RHPORT1_MODE & OPT_MODE_HOST + #if CFG_TUSB_RHPORT0_MODE & (OPT_MODE_HOST << 8) tuh_isr(1); #endif - #if CFG_TUSB_RHPORT1_MODE & OPT_MODE_DEVICE + #if CFG_TUSB_RHPORT0_MODE & (OPT_MODE_DEVICE << 8) tud_int_handler(1); #endif } @@ -163,7 +163,7 @@ void board_init(void) }; // USB0 -#if CFG_TUSB_RHPORT0_MODE +#if CFG_TUSB_RHPORT0_MODE & (OPT_MODE_DEVICE | OPT_MODE_HOST) Chip_USB0_Init(); // // Reset controller @@ -180,7 +180,7 @@ void board_init(void) #endif // USB1 -#if CFG_TUSB_RHPORT1_MODE +#if CFG_TUSB_RHPORT0_MODE & ((OPT_MODE_DEVICE | OPT_MODE_HOST) << 8) Chip_USB1_Init(); // // Reset controller diff --git a/hw/bsp/mimxrt1050_evkb/mimxrt1050_evkb.c b/hw/bsp/mimxrt1050_evkb/mimxrt1050_evkb.c index be0ae3ea8..8dae7a0c2 100644 --- a/hw/bsp/mimxrt1050_evkb/mimxrt1050_evkb.c +++ b/hw/bsp/mimxrt1050_evkb/mimxrt1050_evkb.c @@ -134,11 +134,11 @@ void USB_OTG1_IRQHandler(void) void USB_OTG2_IRQHandler(void) { - #if CFG_TUSB_RHPORT1_MODE & OPT_MODE_HOST + #if CFG_TUSB_RHPORT0_MODE & (OPT_MODE_HOST << 8) tuh_isr(1); #endif - #if CFG_TUSB_RHPORT1_MODE & OPT_MODE_DEVICE + #if CFG_TUSB_RHPORT0_MODE & (OPT_MODE_DEVICE << 8) tud_int_handler(1); #endif } diff --git a/hw/bsp/mimxrt1060_evk/mimxrt1060_evk.c b/hw/bsp/mimxrt1060_evk/mimxrt1060_evk.c index be0ae3ea8..8dae7a0c2 100644 --- a/hw/bsp/mimxrt1060_evk/mimxrt1060_evk.c +++ b/hw/bsp/mimxrt1060_evk/mimxrt1060_evk.c @@ -134,11 +134,11 @@ void USB_OTG1_IRQHandler(void) void USB_OTG2_IRQHandler(void) { - #if CFG_TUSB_RHPORT1_MODE & OPT_MODE_HOST + #if CFG_TUSB_RHPORT0_MODE & (OPT_MODE_HOST << 8) tuh_isr(1); #endif - #if CFG_TUSB_RHPORT1_MODE & OPT_MODE_DEVICE + #if CFG_TUSB_RHPORT0_MODE & (OPT_MODE_DEVICE << 8) tud_int_handler(1); #endif } diff --git a/hw/bsp/mimxrt1064_evk/mimxrt1064_evk.c b/hw/bsp/mimxrt1064_evk/mimxrt1064_evk.c index be0ae3ea8..8dae7a0c2 100644 --- a/hw/bsp/mimxrt1064_evk/mimxrt1064_evk.c +++ b/hw/bsp/mimxrt1064_evk/mimxrt1064_evk.c @@ -134,11 +134,11 @@ void USB_OTG1_IRQHandler(void) void USB_OTG2_IRQHandler(void) { - #if CFG_TUSB_RHPORT1_MODE & OPT_MODE_HOST + #if CFG_TUSB_RHPORT0_MODE & (OPT_MODE_HOST << 8) tuh_isr(1); #endif - #if CFG_TUSB_RHPORT1_MODE & OPT_MODE_DEVICE + #if CFG_TUSB_RHPORT0_MODE & (OPT_MODE_DEVICE << 8) tud_int_handler(1); #endif } diff --git a/hw/bsp/ngx4330/ngx4330.c b/hw/bsp/ngx4330/ngx4330.c index 5296ddcb3..85d11d6ad 100644 --- a/hw/bsp/ngx4330/ngx4330.c +++ b/hw/bsp/ngx4330/ngx4330.c @@ -161,7 +161,7 @@ void board_init(void) * status feedback from the distribution switch. GPIO54 is used for VBUS sensing. 15Kohm pull-down * resistors are always active */ -#if CFG_TUSB_RHPORT0_MODE +#if CFG_TUSB_RHPORT0_MODE & (OPT_MODE_DEVICE | OPT_MODE_HOST) Chip_USB0_Init(); // // Reset controller @@ -197,7 +197,7 @@ void board_init(void) * of VBUS can be read via U31. * JP16 shall not be inserted. */ -#if CFG_TUSB_RHPORT1_MODE +#if CFG_TUSB_RHPORT0_MODE & ((OPT_MODE_DEVICE | OPT_MODE_HOST) << 8) Chip_USB1_Init(); // // Reset controller @@ -235,11 +235,11 @@ void USB0_IRQHandler(void) void USB1_IRQHandler(void) { - #if CFG_TUSB_RHPORT1_MODE & OPT_MODE_HOST + #if CFG_TUSB_RHPORT0_MODE & (OPT_MODE_HOST << 8) tuh_isr(1); #endif - #if CFG_TUSB_RHPORT1_MODE & OPT_MODE_DEVICE + #if CFG_TUSB_RHPORT0_MODE & (OPT_MODE_DEVICE << 8) tud_int_handler(1); #endif } diff --git a/hw/bsp/teensy_40/teensy40.c b/hw/bsp/teensy_40/teensy40.c index f45a98ef3..0ca86f602 100644 --- a/hw/bsp/teensy_40/teensy40.c +++ b/hw/bsp/teensy_40/teensy40.c @@ -135,11 +135,11 @@ void USB_OTG1_IRQHandler(void) void USB_OTG2_IRQHandler(void) { - #if CFG_TUSB_RHPORT1_MODE & OPT_MODE_HOST + #if CFG_TUSB_RHPORT0_MODE & (OPT_MODE_HOST << 8) tuh_isr(1); #endif - #if CFG_TUSB_RHPORT1_MODE & OPT_MODE_DEVICE + #if CFG_TUSB_RHPORT0_MODE & (OPT_MODE_DEVICE << 8) tud_int_handler(1); #endif } diff --git a/src/tusb_option.h b/src/tusb_option.h index 9e6a2b532..472656424 100644 --- a/src/tusb_option.h +++ b/src/tusb_option.h @@ -114,44 +114,50 @@ /** \addtogroup group_configuration * @{ */ + //-------------------------------------------------------------------- -// CONTROLLER -// Only 1 roothub port can be configured to be device and/or host. -// tinyusb does not support dual devices or dual host configuration +// RootHub Mode Configuration +// +// Each byte of the CFG_TUSB_RHPORTx_MODE contains operation mode for +// a roothub port (device or host). Therefore each macro can have up to +// 4 ports. //-------------------------------------------------------------------- -/** \defgroup group_mode Controller Mode Selection - * \brief CFG_TUSB_CONTROLLER_N_MODE must be defined with these - * @{ */ + +// Lower 4-bit is operational mode #define OPT_MODE_NONE 0x00 ///< Disabled #define OPT_MODE_DEVICE 0x01 ///< Device Mode #define OPT_MODE_HOST 0x02 ///< Host Mode -#define OPT_MODE_HIGH_SPEED 0x10 ///< High speed -/** @} */ + +// Higher 4-bit is max operational speed (corresponding to tusb_speed_t) +#define OPT_MODE_FULL_SPEED 0x00 ///< Max Full Speed +#define OPT_MODE_LOW_SPEED 0x10 ///< Max Low Speed +#define OPT_MODE_HIGH_SPEED 0x20 ///< Max High Speed + #ifndef CFG_TUSB_RHPORT0_MODE #define CFG_TUSB_RHPORT0_MODE OPT_MODE_NONE #endif -#ifndef CFG_TUSB_RHPORT1_MODE - #define CFG_TUSB_RHPORT1_MODE OPT_MODE_NONE -#endif +//#ifndef CFG_TUSB_RHPORT1_MODE +// #define CFG_TUSB_RHPORT1_MODE OPT_MODE_NONE +//#endif -#if ((CFG_TUSB_RHPORT0_MODE & OPT_MODE_HOST) && (CFG_TUSB_RHPORT1_MODE & OPT_MODE_HOST)) || \ - ((CFG_TUSB_RHPORT0_MODE & OPT_MODE_DEVICE) && (CFG_TUSB_RHPORT1_MODE & OPT_MODE_DEVICE)) - #error "tinyusb does not support same modes on more than 1 roothub port" +#if ((CFG_TUSB_RHPORT0_MODE & OPT_MODE_HOST ) && (CFG_TUSB_RHPORT0_MODE & (OPT_MODE_HOST << 8)) ) || \ + ((CFG_TUSB_RHPORT0_MODE & OPT_MODE_DEVICE) && (CFG_TUSB_RHPORT0_MODE & (OPT_MODE_DEVICE << 8)) ) + #error "TinyUSB currently does not support same modes on more than 1 roothub port" #endif // Which roothub port is configured as host -#define TUH_OPT_RHPORT ( (CFG_TUSB_RHPORT0_MODE & OPT_MODE_HOST) ? 0 : ((CFG_TUSB_RHPORT1_MODE & OPT_MODE_HOST) ? 1 : -1) ) +#define TUH_OPT_RHPORT ( (CFG_TUSB_RHPORT0_MODE & OPT_MODE_HOST) ? 0 : ((CFG_TUSB_RHPORT0_MODE & (OPT_MODE_HOST << 8)) ? 1 : -1) ) #define TUSB_OPT_HOST_ENABLED ( TUH_OPT_RHPORT >= 0 ) // Which roothub port is configured as device -#define TUD_OPT_RHPORT ( (CFG_TUSB_RHPORT0_MODE & OPT_MODE_DEVICE) ? 0 : ((CFG_TUSB_RHPORT1_MODE & OPT_MODE_DEVICE) ? 1 : -1) ) +#define TUD_OPT_RHPORT ( (CFG_TUSB_RHPORT0_MODE & OPT_MODE_DEVICE) ? 0 : ((CFG_TUSB_RHPORT0_MODE & (OPT_MODE_DEVICE << 8)) ? 1 : -1) ) #if TUD_OPT_RHPORT == 0 -#define TUD_OPT_HIGH_SPEED ( CFG_TUSB_RHPORT0_MODE & OPT_MODE_HIGH_SPEED ) + #define TUD_OPT_HIGH_SPEED ( CFG_TUSB_RHPORT0_MODE & OPT_MODE_HIGH_SPEED ) #else -#define TUD_OPT_HIGH_SPEED ( CFG_TUSB_RHPORT1_MODE & OPT_MODE_HIGH_SPEED ) + #define TUD_OPT_HIGH_SPEED ( CFG_TUSB_RHPORT0_MODE & (OPT_MODE_HIGH_SPEED << 8) ) #endif #define TUSB_OPT_DEVICE_ENABLED ( TUD_OPT_RHPORT >= 0 ) @@ -168,15 +174,15 @@ // place data in accessible RAM for usb controller #ifndef CFG_TUSB_MEM_SECTION -#define CFG_TUSB_MEM_SECTION + #define CFG_TUSB_MEM_SECTION #endif #ifndef CFG_TUSB_MEM_ALIGN -#define CFG_TUSB_MEM_ALIGN TU_ATTR_ALIGNED(4) + #define CFG_TUSB_MEM_ALIGN TU_ATTR_ALIGNED(4) #endif #ifndef CFG_TUSB_OS -#define CFG_TUSB_OS OPT_OS_NONE + #define CFG_TUSB_OS OPT_OS_NONE #endif //-------------------------------------------------------------------- @@ -184,7 +190,7 @@ //-------------------------------------------------------------------- #ifndef CFG_TUD_ENDPOINT0_SIZE - #define CFG_TUD_ENDPOINT0_SIZE 64 + #define CFG_TUD_ENDPOINT0_SIZE 64 #endif #ifndef CFG_TUD_CDC From b7ab60aa44ff7803161196b579eafd6c26321df7 Mon Sep 17 00:00:00 2001 From: hathach Date: Tue, 26 May 2020 15:52:02 +0700 Subject: [PATCH 04/48] suporting multiple port (OTG FS + HS) for stm32 --- src/portable/st/synopsys/dcd_synopsys.c | 149 +++++++++++++----------- 1 file changed, 80 insertions(+), 69 deletions(-) diff --git a/src/portable/st/synopsys/dcd_synopsys.c b/src/portable/st/synopsys/dcd_synopsys.c index 717a59db6..ee987b0de 100644 --- a/src/portable/st/synopsys/dcd_synopsys.c +++ b/src/portable/st/synopsys/dcd_synopsys.c @@ -82,6 +82,33 @@ #include "device/dcd.h" +//--------------------------------------------------------------------+ +// +//--------------------------------------------------------------------+ + +typedef struct +{ + uint32_t regs; // registers + const IRQn_Type irqnum; // IRQ number +// const uint8_t ep_count; // Max bi-directional Endpoints +}dcd_rhport_t; + +// To be consistent across stm32 port. We will number OTG_FS as Rhport0, and OTG_HS as Rhport1 +static const dcd_rhport_t _dcd_rhport[] = +{ + { .regs = USB_OTG_FS_PERIPH_BASE, .irqnum = OTG_FS_IRQn } + +#ifdef USB_OTG_HS + ,{ .regs = USB_OTG_HS_PERIPH_BASE, .irqnum = OTG_HS_IRQn } +#endif +}; + +#define DEVICE_BASE(_port) (USB_OTG_DeviceTypeDef *) (_dcd_rhport[_port].regs + USB_OTG_DEVICE_BASE) +#define OUT_EP_BASE(_port) (USB_OTG_OUTEndpointTypeDef *) (_dcd_rhport[_port].regs + USB_OTG_OUT_ENDPOINT_BASE) +#define IN_EP_BASE(_port) (USB_OTG_INEndpointTypeDef *) (_dcd_rhport[_port].regs + USB_OTG_IN_ENDPOINT_BASE) +#define FIFO_BASE(_port, _x) ((volatile uint32_t *) (_dcd_rhport[_port].regs + USB_OTG_FIFO_BASE + (_x) * USB_OTG_FIFO_SIZE)) + + /*------------------------------------------------------------------*/ /* MACRO TYPEDEF CONSTANT ENUM *------------------------------------------------------------------*/ @@ -90,11 +117,6 @@ // We disable SOF for now until needed later on #define USE_SOF 0 -#define DEVICE_BASE (USB_OTG_DeviceTypeDef *) (USB_OTG_FS_PERIPH_BASE + USB_OTG_DEVICE_BASE) -#define OUT_EP_BASE (USB_OTG_OUTEndpointTypeDef *) (USB_OTG_FS_PERIPH_BASE + USB_OTG_OUT_ENDPOINT_BASE) -#define IN_EP_BASE (USB_OTG_INEndpointTypeDef *) (USB_OTG_FS_PERIPH_BASE + USB_OTG_IN_ENDPOINT_BASE) -#define FIFO_BASE(_x) ((volatile uint32_t *) (USB_OTG_FS_PERIPH_BASE + USB_OTG_FIFO_BASE + (_x) * USB_OTG_FIFO_SIZE)) - static TU_ATTR_ALIGNED(4) uint32_t _setup_packet[6]; static uint8_t _setup_offs; // We store up to 3 setup packets. @@ -113,9 +135,10 @@ xfer_ctl_t xfer_status[EP_MAX][2]; // Setup the control endpoint 0. -static void bus_reset(void) { - USB_OTG_DeviceTypeDef * dev = DEVICE_BASE; - USB_OTG_OUTEndpointTypeDef * out_ep = OUT_EP_BASE; +static void bus_reset(uint8_t rhport) +{ + USB_OTG_DeviceTypeDef * dev = DEVICE_BASE(rhport); + USB_OTG_OUTEndpointTypeDef * out_ep = OUT_EP_BASE(rhport); for(uint8_t n = 0; n < EP_MAX; n++) { out_ep[n].DOEPCTL |= USB_OTG_DOEPCTL_SNAK; @@ -163,9 +186,11 @@ static void bus_reset(void) { USB_OTG_FS->GINTMSK |= USB_OTG_GINTMSK_OEPINT | USB_OTG_GINTMSK_IEPINT; } -static void end_of_reset(void) { - USB_OTG_DeviceTypeDef * dev = DEVICE_BASE; - USB_OTG_INEndpointTypeDef * in_ep = IN_EP_BASE; +static void end_of_reset(uint8_t rhport) +{ + USB_OTG_DeviceTypeDef * dev = DEVICE_BASE(rhport); + USB_OTG_INEndpointTypeDef * in_ep = IN_EP_BASE(rhport); + // On current silicon on the Full Speed core, speed is fixed to Full Speed. // However, keep for debugging and in case Low Speed is ever supported. uint32_t enum_spd = (dev->DSTS & USB_OTG_DSTS_ENUMSPD_Msk) >> USB_OTG_DSTS_ENUMSPD_Pos; @@ -191,8 +216,6 @@ static void end_of_reset(void) { *------------------------------------------------------------------*/ void dcd_init (uint8_t rhport) { - (void) rhport; - // Programming model begins in the last section of the chapter on the USB // peripheral in each Reference Manual. USB_OTG_FS->GAHBCFG |= USB_OTG_GAHBCFG_GINT; @@ -210,7 +233,7 @@ void dcd_init (uint8_t rhport) // the core to stop working/require reset. USB_OTG_FS->GINTMSK |= USB_OTG_GINTMSK_OTGINT | USB_OTG_GINTMSK_MMISM; - USB_OTG_DeviceTypeDef * dev = DEVICE_BASE; + USB_OTG_DeviceTypeDef * dev = DEVICE_BASE(rhport); // If USB host misbehaves during status portion of control xfer // (non zero-length packet), send STALL back and discard. Full speed. @@ -226,21 +249,17 @@ void dcd_init (uint8_t rhport) void dcd_int_enable (uint8_t rhport) { - (void) rhport; - NVIC_EnableIRQ(OTG_FS_IRQn); + NVIC_EnableIRQ(_dcd_rhport[rhport].irqnum); } void dcd_int_disable (uint8_t rhport) { - (void) rhport; - NVIC_DisableIRQ(OTG_FS_IRQn); + NVIC_EnableIRQ(_dcd_rhport[rhport].irqnum); } void dcd_set_address (uint8_t rhport, uint8_t dev_addr) { - (void) rhport; - - USB_OTG_DeviceTypeDef * dev = DEVICE_BASE; + USB_OTG_DeviceTypeDef * dev = DEVICE_BASE(rhport); dev->DCFG |= (dev_addr << USB_OTG_DCFG_DAD_Pos) & USB_OTG_DCFG_DAD_Msk; // Response with status after changing device address @@ -254,16 +273,14 @@ void dcd_remote_wakeup(uint8_t rhport) void dcd_connect(uint8_t rhport) { - (void) rhport; - USB_OTG_DeviceTypeDef * dev = DEVICE_BASE; + USB_OTG_DeviceTypeDef * dev = DEVICE_BASE(rhport); dev->DCTL &= ~USB_OTG_DCTL_SDIS; } void dcd_disconnect(uint8_t rhport) { - (void) rhport; - USB_OTG_DeviceTypeDef * dev = DEVICE_BASE; + USB_OTG_DeviceTypeDef * dev = DEVICE_BASE(rhport); dev->DCTL |= USB_OTG_DCTL_SDIS; } @@ -275,10 +292,9 @@ void dcd_disconnect(uint8_t rhport) bool dcd_edpt_open (uint8_t rhport, tusb_desc_endpoint_t const * desc_edpt) { - (void) rhport; - USB_OTG_DeviceTypeDef * dev = DEVICE_BASE; - USB_OTG_OUTEndpointTypeDef * out_ep = OUT_EP_BASE; - USB_OTG_INEndpointTypeDef * in_ep = IN_EP_BASE; + USB_OTG_DeviceTypeDef * dev = DEVICE_BASE(rhport); + USB_OTG_OUTEndpointTypeDef * out_ep = OUT_EP_BASE(rhport); + USB_OTG_INEndpointTypeDef * in_ep = IN_EP_BASE(rhport); uint8_t const epnum = tu_edpt_number(desc_edpt->bEndpointAddress); uint8_t const dir = tu_edpt_dir(desc_edpt->bEndpointAddress); @@ -345,10 +361,9 @@ bool dcd_edpt_open (uint8_t rhport, tusb_desc_endpoint_t const * desc_edpt) bool dcd_edpt_xfer (uint8_t rhport, uint8_t ep_addr, uint8_t * buffer, uint16_t total_bytes) { - (void) rhport; - USB_OTG_DeviceTypeDef * dev = DEVICE_BASE; - USB_OTG_OUTEndpointTypeDef * out_ep = OUT_EP_BASE; - USB_OTG_INEndpointTypeDef * in_ep = IN_EP_BASE; + USB_OTG_DeviceTypeDef * dev = DEVICE_BASE(rhport); + USB_OTG_OUTEndpointTypeDef * out_ep = OUT_EP_BASE(rhport); + USB_OTG_INEndpointTypeDef * in_ep = IN_EP_BASE(rhport); uint8_t const epnum = tu_edpt_number(ep_addr); uint8_t const dir = tu_edpt_dir(ep_addr); @@ -393,10 +408,9 @@ bool dcd_edpt_xfer (uint8_t rhport, uint8_t ep_addr, uint8_t * buffer, uint16_t // (send STALL versus NAK handshakes back). Refactor into resuable function. void dcd_edpt_stall (uint8_t rhport, uint8_t ep_addr) { - (void) rhport; - USB_OTG_DeviceTypeDef * dev = DEVICE_BASE; - USB_OTG_OUTEndpointTypeDef * out_ep = OUT_EP_BASE; - USB_OTG_INEndpointTypeDef * in_ep = IN_EP_BASE; + USB_OTG_DeviceTypeDef * dev = DEVICE_BASE(rhport); + USB_OTG_OUTEndpointTypeDef * out_ep = OUT_EP_BASE(rhport); + USB_OTG_INEndpointTypeDef * in_ep = IN_EP_BASE(rhport); uint8_t const epnum = tu_edpt_number(ep_addr); uint8_t const dir = tu_edpt_dir(ep_addr); @@ -445,9 +459,8 @@ void dcd_edpt_stall (uint8_t rhport, uint8_t ep_addr) void dcd_edpt_clear_stall (uint8_t rhport, uint8_t ep_addr) { - (void) rhport; - USB_OTG_OUTEndpointTypeDef * out_ep = OUT_EP_BASE; - USB_OTG_INEndpointTypeDef * in_ep = IN_EP_BASE; + USB_OTG_OUTEndpointTypeDef * out_ep = OUT_EP_BASE(rhport); + USB_OTG_INEndpointTypeDef * in_ep = IN_EP_BASE(rhport); uint8_t const epnum = tu_edpt_number(ep_addr); uint8_t const dir = tu_edpt_dir(ep_addr); @@ -480,8 +493,8 @@ void dcd_edpt_clear_stall (uint8_t rhport, uint8_t ep_addr) // TODO: Split into "receive on endpoint 0" and "receive generic"; endpoint 0's // DOEPTSIZ register is smaller than the others, and so is insufficient for // determining how much of an OUT transfer is actually remaining. -static void receive_packet(xfer_ctl_t * xfer, /* USB_OTG_OUTEndpointTypeDef * out_ep, */ uint16_t xfer_size) { - usb_fifo_t rx_fifo = FIFO_BASE(0); +static void receive_packet(uint8_t rhport, xfer_ctl_t * xfer, /* USB_OTG_OUTEndpointTypeDef * out_ep, */ uint16_t xfer_size) { + usb_fifo_t rx_fifo = FIFO_BASE(rhport, 0); // See above TODO // uint16_t remaining = (out_ep->DOEPTSIZ & USB_OTG_DOEPTSIZ_XFRSIZ_Msk) >> USB_OTG_DOEPTSIZ_XFRSIZ_Pos; @@ -539,8 +552,8 @@ static void receive_packet(xfer_ctl_t * xfer, /* USB_OTG_OUTEndpointTypeDef * ou } // Write a single data packet to EPIN FIFO -static void write_fifo_packet(uint8_t fifo_num, uint8_t * src, uint16_t len){ - usb_fifo_t tx_fifo = FIFO_BASE(fifo_num); +static void write_fifo_packet(uint8_t rhport, uint8_t fifo_num, uint8_t * src, uint16_t len){ + usb_fifo_t tx_fifo = FIFO_BASE(rhport, fifo_num); // Pushing full available 32 bit words to fifo uint16_t full_words = len >> 2; @@ -564,8 +577,8 @@ static void write_fifo_packet(uint8_t fifo_num, uint8_t * src, uint16_t len){ } } -static void read_rx_fifo(USB_OTG_OUTEndpointTypeDef * out_ep) { - usb_fifo_t rx_fifo = FIFO_BASE(0); +static void read_rx_fifo(uint8_t rhport, USB_OTG_OUTEndpointTypeDef * out_ep) { + usb_fifo_t rx_fifo = FIFO_BASE(rhport, 0); // Pop control word off FIFO (completed xfers will have 2 control words, // we only pop one ctl word each interrupt). @@ -580,7 +593,7 @@ static void read_rx_fifo(USB_OTG_OUTEndpointTypeDef * out_ep) { case 0x02: // Out packet recvd { xfer_ctl_t * xfer = XFER_CTL_BASE(epnum, TUSB_DIR_OUT); - receive_packet(xfer, bcnt); + receive_packet(rhport, xfer, bcnt); } break; case 0x03: // Out packet done (Interrupt) @@ -605,7 +618,7 @@ static void read_rx_fifo(USB_OTG_OUTEndpointTypeDef * out_ep) { } } -static void handle_epout_ints(USB_OTG_DeviceTypeDef * dev, USB_OTG_OUTEndpointTypeDef * out_ep) { +static void handle_epout_ints(uint8_t rhport, USB_OTG_DeviceTypeDef * dev, USB_OTG_OUTEndpointTypeDef * out_ep) { // DAINT for a given EP clears when DOEPINTx is cleared. // OEPINT will be cleared when DAINT's out bits are cleared. for(uint8_t n = 0; n < EP_MAX; n++) { @@ -615,7 +628,7 @@ static void handle_epout_ints(USB_OTG_DeviceTypeDef * dev, USB_OTG_OUTEndpointTy // SETUP packet Setup Phase done. if(out_ep[n].DOEPINT & USB_OTG_DOEPINT_STUP) { out_ep[n].DOEPINT = USB_OTG_DOEPINT_STUP; - dcd_event_setup_received(0, (uint8_t*) &_setup_packet[2*_setup_offs], true); + dcd_event_setup_received(rhport, (uint8_t*) &_setup_packet[2*_setup_offs], true); _setup_offs = 0; } @@ -631,7 +644,7 @@ static void handle_epout_ints(USB_OTG_DeviceTypeDef * dev, USB_OTG_OUTEndpointTy // Transfer complete if short packet or total len is transferred if(xfer->short_packet || (xfer->queued_len == xfer->total_len)) { xfer->short_packet = false; - dcd_event_xfer_complete(0, n, xfer->queued_len, XFER_RESULT_SUCCESS, true); + dcd_event_xfer_complete(rhport, n, xfer->queued_len, XFER_RESULT_SUCCESS, true); } else { // Schedule another packet to be received. out_ep[n].DOEPTSIZ |= (1 << USB_OTG_DOEPTSIZ_PKTCNT_Pos) | \ @@ -643,7 +656,7 @@ static void handle_epout_ints(USB_OTG_DeviceTypeDef * dev, USB_OTG_OUTEndpointTy } } -static void handle_epin_ints(USB_OTG_DeviceTypeDef * dev, USB_OTG_INEndpointTypeDef * in_ep) { +static void handle_epin_ints(uint8_t rhport, USB_OTG_DeviceTypeDef * dev, USB_OTG_INEndpointTypeDef * in_ep) { // DAINT for a given EP clears when DIEPINTx is cleared. // IEPINT will be cleared when DAINT's out bits are cleared. for ( uint8_t n = 0; n < EP_MAX; n++ ) @@ -657,7 +670,7 @@ static void handle_epin_ints(USB_OTG_DeviceTypeDef * dev, USB_OTG_INEndpointType if ( in_ep[n].DIEPINT & USB_OTG_DIEPINT_XFRC ) { in_ep[n].DIEPINT = USB_OTG_DIEPINT_XFRC; - dcd_event_xfer_complete(0, n | TUSB_DIR_IN_MASK, xfer->total_len, XFER_RESULT_SUCCESS, true); + dcd_event_xfer_complete(rhport, n | TUSB_DIR_IN_MASK, xfer->total_len, XFER_RESULT_SUCCESS, true); } // XFER FIFO empty @@ -686,7 +699,7 @@ static void handle_epin_ints(USB_OTG_DeviceTypeDef * dev, USB_OTG_INEndpointType xfer->queued_len = xfer->total_len - remaining_bytes; // Push packet to Tx-FIFO - write_fifo_packet(n, (xfer->buffer + xfer->queued_len), packet_size); + write_fifo_packet(rhport, n, (xfer->buffer + xfer->queued_len), packet_size); } // Turn off TXFE if all bytes are written. @@ -699,20 +712,18 @@ static void handle_epin_ints(USB_OTG_DeviceTypeDef * dev, USB_OTG_INEndpointType } } -void dcd_int_handler(uint8_t rhport) { - - (void) rhport; - - USB_OTG_DeviceTypeDef * dev = DEVICE_BASE; - USB_OTG_OUTEndpointTypeDef * out_ep = OUT_EP_BASE; - USB_OTG_INEndpointTypeDef * in_ep = IN_EP_BASE; +void dcd_int_handler(uint8_t rhport) +{ + USB_OTG_DeviceTypeDef * dev = DEVICE_BASE(rhport); + USB_OTG_OUTEndpointTypeDef * out_ep = OUT_EP_BASE(rhport); + USB_OTG_INEndpointTypeDef * in_ep = IN_EP_BASE(rhport); uint32_t int_status = USB_OTG_FS->GINTSTS; if(int_status & USB_OTG_GINTSTS_USBRST) { // USBRST is start of reset. USB_OTG_FS->GINTSTS = USB_OTG_GINTSTS_USBRST; - bus_reset(); + bus_reset(rhport); } if(int_status & USB_OTG_GINTSTS_ENUMDNE) { @@ -720,20 +731,20 @@ void dcd_int_handler(uint8_t rhport) { // always expect the same value. This interrupt is considered // the end of reset. USB_OTG_FS->GINTSTS = USB_OTG_GINTSTS_ENUMDNE; - end_of_reset(); - dcd_event_bus_signal(0, DCD_EVENT_BUS_RESET, true); + end_of_reset(rhport); + dcd_event_bus_signal(rhport, DCD_EVENT_BUS_RESET, true); } if(int_status & USB_OTG_GINTSTS_USBSUSP) { USB_OTG_FS->GINTSTS = USB_OTG_GINTSTS_USBSUSP; - dcd_event_bus_signal(0, DCD_EVENT_SUSPEND, true); + dcd_event_bus_signal(rhport, DCD_EVENT_SUSPEND, true); } if(int_status & USB_OTG_GINTSTS_WKUINT) { USB_OTG_FS->GINTSTS = USB_OTG_GINTSTS_WKUINT; - dcd_event_bus_signal(0, DCD_EVENT_RESUME, true); + dcd_event_bus_signal(rhport, DCD_EVENT_RESUME, true); } if(int_status & USB_OTG_GINTSTS_OTGINT) @@ -743,7 +754,7 @@ void dcd_int_handler(uint8_t rhport) { if (otg_int & USB_OTG_GOTGINT_SEDET) { - dcd_event_bus_signal(0, DCD_EVENT_UNPLUGGED, true); + dcd_event_bus_signal(rhport, DCD_EVENT_UNPLUGGED, true); } USB_OTG_FS->GOTGINT = otg_int; @@ -761,20 +772,20 @@ void dcd_int_handler(uint8_t rhport) { // Mask out RXFLVL while reading data from FIFO USB_OTG_FS->GINTMSK &= ~USB_OTG_GINTMSK_RXFLVLM; - read_rx_fifo(out_ep); + read_rx_fifo(rhport, out_ep); USB_OTG_FS->GINTMSK |= USB_OTG_GINTMSK_RXFLVLM; } // OUT endpoint interrupt handling. if(int_status & USB_OTG_GINTSTS_OEPINT) { // OEPINT is read-only - handle_epout_ints(dev, out_ep); + handle_epout_ints(rhport, dev, out_ep); } // IN endpoint interrupt handling. if(int_status & USB_OTG_GINTSTS_IEPINT) { // IEPINT bit read-only - handle_epin_ints(dev, in_ep); + handle_epin_ints(rhport, dev, in_ep); } } From 947c3eb10dee55e7c05bee8e10d21a225e311263 Mon Sep 17 00:00:00 2001 From: hathach Date: Tue, 26 May 2020 16:07:48 +0700 Subject: [PATCH 05/48] multiple port support for global otg base --- src/portable/st/synopsys/dcd_synopsys.c | 65 ++++++++++++++----------- 1 file changed, 37 insertions(+), 28 deletions(-) diff --git a/src/portable/st/synopsys/dcd_synopsys.c b/src/portable/st/synopsys/dcd_synopsys.c index ee987b0de..b68794712 100644 --- a/src/portable/st/synopsys/dcd_synopsys.c +++ b/src/portable/st/synopsys/dcd_synopsys.c @@ -103,6 +103,7 @@ static const dcd_rhport_t _dcd_rhport[] = #endif }; +#define GLOBAL_BASE(_port) ((USB_OTG_GlobalTypeDef*) _dcd_rhport[_port].regs) #define DEVICE_BASE(_port) (USB_OTG_DeviceTypeDef *) (_dcd_rhport[_port].regs + USB_OTG_DEVICE_BASE) #define OUT_EP_BASE(_port) (USB_OTG_OUTEndpointTypeDef *) (_dcd_rhport[_port].regs + USB_OTG_OUT_ENDPOINT_BASE) #define IN_EP_BASE(_port) (USB_OTG_INEndpointTypeDef *) (_dcd_rhport[_port].regs + USB_OTG_IN_ENDPOINT_BASE) @@ -137,6 +138,7 @@ xfer_ctl_t xfer_status[EP_MAX][2]; // Setup the control endpoint 0. static void bus_reset(uint8_t rhport) { + USB_OTG_GlobalTypeDef * usb_otg = GLOBAL_BASE(rhport); USB_OTG_DeviceTypeDef * dev = DEVICE_BASE(rhport); USB_OTG_OUTEndpointTypeDef * out_ep = OUT_EP_BASE(rhport); @@ -176,14 +178,14 @@ static void bus_reset(uint8_t rhport) // * 1 location for global NAK (not required/used here). // * It is recommended to allocate 2 times the largest packet size, therefore // Recommended value = 10 + 1 + 2 x (16+2) = 47 --> Let's make it 52 - USB_OTG_FS->GRXFSIZ = 52; + usb_otg->GRXFSIZ = 52; // Control IN uses FIFO 0 with 64 bytes ( 16 32-bit word ) - USB_OTG_FS->DIEPTXF0_HNPTXFSIZ = (16 << USB_OTG_TX0FD_Pos) | (USB_OTG_FS->GRXFSIZ & 0x0000ffffUL); + usb_otg->DIEPTXF0_HNPTXFSIZ = (16 << USB_OTG_TX0FD_Pos) | (usb_otg->GRXFSIZ & 0x0000ffffUL); out_ep[0].DOEPTSIZ |= (3 << USB_OTG_DOEPTSIZ_STUPCNT_Pos); - USB_OTG_FS->GINTMSK |= USB_OTG_GINTMSK_OEPINT | USB_OTG_GINTMSK_IEPINT; + usb_otg->GINTMSK |= USB_OTG_GINTMSK_OEPINT | USB_OTG_GINTMSK_IEPINT; } static void end_of_reset(uint8_t rhport) @@ -216,22 +218,24 @@ static void end_of_reset(uint8_t rhport) *------------------------------------------------------------------*/ void dcd_init (uint8_t rhport) { + USB_OTG_GlobalTypeDef * usb_otg = GLOBAL_BASE(rhport); + // Programming model begins in the last section of the chapter on the USB // peripheral in each Reference Manual. - USB_OTG_FS->GAHBCFG |= USB_OTG_GAHBCFG_GINT; + usb_otg->GAHBCFG |= USB_OTG_GAHBCFG_GINT; // No HNP/SRP (no OTG support), program timeout later, turnaround // programmed for 32+ MHz. // TODO: PHYSEL is read-only on some cores (STM32F407). Worth gating? - USB_OTG_FS->GUSBCFG |= (0x06 << USB_OTG_GUSBCFG_TRDT_Pos) | USB_OTG_GUSBCFG_PHYSEL; + usb_otg->GUSBCFG |= (0x06 << USB_OTG_GUSBCFG_TRDT_Pos) | USB_OTG_GUSBCFG_PHYSEL; // Clear all interrupts - USB_OTG_FS->GINTSTS |= USB_OTG_FS->GINTSTS; + usb_otg->GINTSTS |= usb_otg->GINTSTS; // Required as part of core initialization. // TODO: How should mode mismatch be handled? It will cause // the core to stop working/require reset. - USB_OTG_FS->GINTMSK |= USB_OTG_GINTMSK_OTGINT | USB_OTG_GINTMSK_MMISM; + usb_otg->GINTMSK |= USB_OTG_GINTMSK_OTGINT | USB_OTG_GINTMSK_MMISM; USB_OTG_DeviceTypeDef * dev = DEVICE_BASE(rhport); @@ -239,12 +243,12 @@ void dcd_init (uint8_t rhport) // (non zero-length packet), send STALL back and discard. Full speed. dev->DCFG |= USB_OTG_DCFG_NZLSOHSK | (3 << USB_OTG_DCFG_DSPD_Pos); - USB_OTG_FS->GINTMSK |= USB_OTG_GINTMSK_USBRST | USB_OTG_GINTMSK_ENUMDNEM | + usb_otg->GINTMSK |= USB_OTG_GINTMSK_USBRST | USB_OTG_GINTMSK_ENUMDNEM | USB_OTG_GINTMSK_USBSUSPM | USB_OTG_GINTMSK_WUIM | USB_OTG_GINTMSK_RXFLVLM | (USE_SOF ? USB_OTG_GINTMSK_SOFM : 0); // Enable USB transceiver. - USB_OTG_FS->GCCFG |= USB_OTG_GCCFG_PWRDWN; + usb_otg->GCCFG |= USB_OTG_GCCFG_PWRDWN; } void dcd_int_enable (uint8_t rhport) @@ -292,6 +296,7 @@ void dcd_disconnect(uint8_t rhport) bool dcd_edpt_open (uint8_t rhport, tusb_desc_endpoint_t const * desc_edpt) { + USB_OTG_GlobalTypeDef * usb_otg = GLOBAL_BASE(rhport); USB_OTG_DeviceTypeDef * dev = DEVICE_BASE(rhport); USB_OTG_OUTEndpointTypeDef * out_ep = OUT_EP_BASE(rhport); USB_OTG_INEndpointTypeDef * in_ep = IN_EP_BASE(rhport); @@ -348,12 +353,12 @@ bool dcd_edpt_open (uint8_t rhport, tusb_desc_endpoint_t const * desc_edpt) // Both TXFD and TXSA are in unit of 32-bit words. // IN FIFO 0 was configured during enumeration, hence the "+ 16". - uint16_t const allocated_size = (USB_OTG_FS->GRXFSIZ & 0x0000ffff) + 16; + uint16_t const allocated_size = (usb_otg->GRXFSIZ & 0x0000ffff) + 16; uint16_t const fifo_size = (EP_FIFO_SIZE/4 - allocated_size) / (EP_MAX-1); uint32_t const fifo_offset = allocated_size + fifo_size*(epnum-1); // DIEPTXF starts at FIFO #1. - USB_OTG_FS->DIEPTXF[epnum - 1] = (fifo_size << USB_OTG_DIEPTXF_INEPTXFD_Pos) | fifo_offset; + usb_otg->DIEPTXF[epnum - 1] = (fifo_size << USB_OTG_DIEPTXF_INEPTXFD_Pos) | fifo_offset; } return true; @@ -408,6 +413,7 @@ bool dcd_edpt_xfer (uint8_t rhport, uint8_t ep_addr, uint8_t * buffer, uint16_t // (send STALL versus NAK handshakes back). Refactor into resuable function. void dcd_edpt_stall (uint8_t rhport, uint8_t ep_addr) { + USB_OTG_GlobalTypeDef * usb_otg = GLOBAL_BASE(rhport); USB_OTG_DeviceTypeDef * dev = DEVICE_BASE(rhport); USB_OTG_OUTEndpointTypeDef * out_ep = OUT_EP_BASE(rhport); USB_OTG_INEndpointTypeDef * in_ep = IN_EP_BASE(rhport); @@ -431,9 +437,9 @@ void dcd_edpt_stall (uint8_t rhport, uint8_t ep_addr) } // Flush the FIFO, and wait until we have confirmed it cleared. - USB_OTG_FS->GRSTCTL |= ((epnum - 1) << USB_OTG_GRSTCTL_TXFNUM_Pos); - USB_OTG_FS->GRSTCTL |= USB_OTG_GRSTCTL_TXFFLSH; - while((USB_OTG_FS->GRSTCTL & USB_OTG_GRSTCTL_TXFFLSH_Msk) != 0); + usb_otg->GRSTCTL |= ((epnum - 1) << USB_OTG_GRSTCTL_TXFNUM_Pos); + usb_otg->GRSTCTL |= USB_OTG_GRSTCTL_TXFFLSH; + while((usb_otg->GRSTCTL & USB_OTG_GRSTCTL_TXFFLSH_Msk) != 0); } else { // Only disable currently enabled non-control endpoint if ( (epnum == 0) || !(out_ep[epnum].DOEPCTL & USB_OTG_DOEPCTL_EPENA) ){ @@ -444,7 +450,7 @@ void dcd_edpt_stall (uint8_t rhport, uint8_t ep_addr) // anyway, and it can't be cleared by user code. If this while loop never // finishes, we have bigger problems than just the stack. dev->DCTL |= USB_OTG_DCTL_SGONAK; - while((USB_OTG_FS->GINTSTS & USB_OTG_GINTSTS_BOUTNAKEFF_Msk) == 0); + while((usb_otg->GINTSTS & USB_OTG_GINTSTS_BOUTNAKEFF_Msk) == 0); // Ditto here- disable the endpoint. out_ep[epnum].DOEPCTL |= (USB_OTG_DOEPCTL_STALL | USB_OTG_DOEPCTL_EPDIS); @@ -577,12 +583,14 @@ static void write_fifo_packet(uint8_t rhport, uint8_t fifo_num, uint8_t * src, u } } -static void read_rx_fifo(uint8_t rhport, USB_OTG_OUTEndpointTypeDef * out_ep) { +static void read_rx_fifo(uint8_t rhport, USB_OTG_OUTEndpointTypeDef * out_ep) +{ + USB_OTG_GlobalTypeDef * usb_otg = GLOBAL_BASE(rhport); usb_fifo_t rx_fifo = FIFO_BASE(rhport, 0); // Pop control word off FIFO (completed xfers will have 2 control words, // we only pop one ctl word each interrupt). - uint32_t ctl_word = USB_OTG_FS->GRXSTSP; + uint32_t ctl_word = usb_otg->GRXSTSP; uint8_t pktsts = (ctl_word & USB_OTG_GRXSTSP_PKTSTS_Msk) >> USB_OTG_GRXSTSP_PKTSTS_Pos; uint8_t epnum = (ctl_word & USB_OTG_GRXSTSP_EPNUM_Msk) >> USB_OTG_GRXSTSP_EPNUM_Pos; uint16_t bcnt = (ctl_word & USB_OTG_GRXSTSP_BCNT_Msk) >> USB_OTG_GRXSTSP_BCNT_Pos; @@ -714,15 +722,16 @@ static void handle_epin_ints(uint8_t rhport, USB_OTG_DeviceTypeDef * dev, USB_OT void dcd_int_handler(uint8_t rhport) { + USB_OTG_GlobalTypeDef * usb_otg = GLOBAL_BASE(rhport); USB_OTG_DeviceTypeDef * dev = DEVICE_BASE(rhport); USB_OTG_OUTEndpointTypeDef * out_ep = OUT_EP_BASE(rhport); USB_OTG_INEndpointTypeDef * in_ep = IN_EP_BASE(rhport); - uint32_t int_status = USB_OTG_FS->GINTSTS; + uint32_t int_status = usb_otg->GINTSTS; if(int_status & USB_OTG_GINTSTS_USBRST) { // USBRST is start of reset. - USB_OTG_FS->GINTSTS = USB_OTG_GINTSTS_USBRST; + usb_otg->GINTSTS = USB_OTG_GINTSTS_USBRST; bus_reset(rhport); } @@ -730,40 +739,40 @@ void dcd_int_handler(uint8_t rhport) // ENUMDNE detects speed of the link. For full-speed, we // always expect the same value. This interrupt is considered // the end of reset. - USB_OTG_FS->GINTSTS = USB_OTG_GINTSTS_ENUMDNE; + usb_otg->GINTSTS = USB_OTG_GINTSTS_ENUMDNE; end_of_reset(rhport); dcd_event_bus_signal(rhport, DCD_EVENT_BUS_RESET, true); } if(int_status & USB_OTG_GINTSTS_USBSUSP) { - USB_OTG_FS->GINTSTS = USB_OTG_GINTSTS_USBSUSP; + usb_otg->GINTSTS = USB_OTG_GINTSTS_USBSUSP; dcd_event_bus_signal(rhport, DCD_EVENT_SUSPEND, true); } if(int_status & USB_OTG_GINTSTS_WKUINT) { - USB_OTG_FS->GINTSTS = USB_OTG_GINTSTS_WKUINT; + usb_otg->GINTSTS = USB_OTG_GINTSTS_WKUINT; dcd_event_bus_signal(rhport, DCD_EVENT_RESUME, true); } if(int_status & USB_OTG_GINTSTS_OTGINT) { // OTG INT bit is read-only - uint32_t const otg_int = USB_OTG_FS->GOTGINT; + uint32_t const otg_int = usb_otg->GOTGINT; if (otg_int & USB_OTG_GOTGINT_SEDET) { dcd_event_bus_signal(rhport, DCD_EVENT_UNPLUGGED, true); } - USB_OTG_FS->GOTGINT = otg_int; + usb_otg->GOTGINT = otg_int; } #if USE_SOF if(int_status & USB_OTG_GINTSTS_SOF) { - USB_OTG_FS->GINTSTS = USB_OTG_GINTSTS_SOF; - dcd_event_bus_signal(0, DCD_EVENT_SOF, true); + usb_otg->GINTSTS = USB_OTG_GINTSTS_SOF; + dcd_event_bus_signal(rhport, DCD_EVENT_SOF, true); } #endif @@ -771,9 +780,9 @@ void dcd_int_handler(uint8_t rhport) // RXFLVL bit is read-only // Mask out RXFLVL while reading data from FIFO - USB_OTG_FS->GINTMSK &= ~USB_OTG_GINTMSK_RXFLVLM; + usb_otg->GINTMSK &= ~USB_OTG_GINTMSK_RXFLVLM; read_rx_fifo(rhport, out_ep); - USB_OTG_FS->GINTMSK |= USB_OTG_GINTMSK_RXFLVLM; + usb_otg->GINTMSK |= USB_OTG_GINTMSK_RXFLVLM; } // OUT endpoint interrupt handling. From 0482f0d6867835d3dbb3939452fbcfaf9727b555 Mon Sep 17 00:00:00 2001 From: hathach Date: Tue, 26 May 2020 22:11:26 +0700 Subject: [PATCH 06/48] update h743eval with rhport=1 highspeed --- hw/bsp/stm32h743eval/board.mk | 7 +- hw/bsp/stm32h743eval/stm32h743eval.c | 97 +++++++++++++++++++++++++--- src/tusb_option.h | 4 -- test/test/support/tusb_config.h | 5 -- 4 files changed, 89 insertions(+), 24 deletions(-) diff --git a/hw/bsp/stm32h743eval/board.mk b/hw/bsp/stm32h743eval/board.mk index 5044cdc08..68d142435 100644 --- a/hw/bsp/stm32h743eval/board.mk +++ b/hw/bsp/stm32h743eval/board.mk @@ -8,11 +8,8 @@ CFLAGS += \ -nostdlib -nostartfiles \ -DSTM32H743xx \ -DCFG_TUSB_MCU=OPT_MCU_STM32H7 \ - -# Board specific for using usb ports -CFLAGS += \ - -DCFG_BOARD_DEVICE_RHPORT_NUM=1 \ - -DCFG_BOARD_DEVICE_RHPORT_HIGHSPEED + -DBOARD_DEVICE_RHPORT_NUM=1 \ + -DBOARD_DEVICE_RHPORT_SPEED=OPT_MODE_HIGH_SPEED # suppress warning caused by vendor mcu driver CFLAGS += -Wno-error=maybe-uninitialized diff --git a/hw/bsp/stm32h743eval/stm32h743eval.c b/hw/bsp/stm32h743eval/stm32h743eval.c index 5a7934ea2..fd3d33047 100644 --- a/hw/bsp/stm32h743eval/stm32h743eval.c +++ b/hw/bsp/stm32h743eval/stm32h743eval.c @@ -32,11 +32,22 @@ //--------------------------------------------------------------------+ // Forward USB interrupt events to TinyUSB IRQ Handler //--------------------------------------------------------------------+ + +// Despite being call USB2_OTG +// OTG_FS is marked as RHPort0 by TinyUSB to be consistent across stm32 port void OTG_FS_IRQHandler(void) { tud_int_handler(0); } +// Despite being call USB2_OTG +// OTG_HS is marked as RHPort1 by TinyUSB to be consistent across stm32 port +void OTG_HS_IRQHandler(void) +{ + tud_int_handler(1); +} + + //--------------------------------------------------------------------+ // MACRO TYPEDEF CONSTANT ENUM //--------------------------------------------------------------------+ @@ -53,7 +64,7 @@ void OTG_FS_IRQHandler(void) // enable all LED, Button, Uart, USB clock static void all_rcc_clk_enable(void) { - __HAL_RCC_GPIOA_CLK_ENABLE(); // LED, USB D+, D- + __HAL_RCC_GPIOA_CLK_ENABLE(); // LED __HAL_RCC_GPIOC_CLK_ENABLE(); // Button // __HAL_RCC_GPIOD_CLK_ENABLE(); // Uart tx, rx // __HAL_RCC_USART3_CLK_ENABLE(); // Uart module @@ -187,17 +198,13 @@ void board_init(void) GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_HIGH; HAL_GPIO_Init(BUTTON_PORT, &GPIO_InitStruct); -#if CFG_TUSB_RHPORT0_MODE & OPT_MODE_DEVICE - - // USB1 HS (ULPI Phy), internal FS PHY - // PB12 ID, PB13 VBUS, PB14 DM, PB15 DP - -#endif - -#if CFG_TUSB_RHPORT1_MODE & OPT_MODE_DEVICE - // USB2 FS Pin Init +#if BOARD_DEVICE_RHPORT_NUM == 0 + // Despite being call USB2_OTG + // OTG_FS is marked as RHPort0 by TinyUSB to be consistent across stm32 port // PA9 VUSB, PA10 ID, PA11 DM, PA12 DP + __HAL_RCC_GPIOA_CLK_ENABLE(); + /* Configure DM DP Pins */ GPIO_InitStruct.Pin = GPIO_PIN_11 | GPIO_PIN_12; GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_HIGH; @@ -228,6 +235,76 @@ void board_init(void) // Enable VBUS sense (B device) via pin PA9 USB_OTG_FS->GCCFG |= USB_OTG_GCCFG_VBDEN; #endif + +#if BOARD_DEVICE_RHPORT_NUM == 1 + // Despite being call USB2_OTG + // OTG_HS is marked as RHPort1 by TinyUSB to be consistent across stm32 port + __GPIOA_CLK_ENABLE(); + __GPIOB_CLK_ENABLE(); + __GPIOC_CLK_ENABLE(); + __GPIOH_CLK_ENABLE(); + __GPIOI_CLK_ENABLE(); + + /* CLK */ + GPIO_InitStruct.Pin = GPIO_PIN_5; + GPIO_InitStruct.Mode = GPIO_MODE_AF_PP; + GPIO_InitStruct.Pull = GPIO_NOPULL; + GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_VERY_HIGH; + GPIO_InitStruct.Alternate = GPIO_AF10_OTG2_HS; + HAL_GPIO_Init(GPIOA, &GPIO_InitStruct); + + /* D0 */ + GPIO_InitStruct.Pin = GPIO_PIN_3; + GPIO_InitStruct.Mode = GPIO_MODE_AF_PP; + GPIO_InitStruct.Pull = GPIO_NOPULL; + GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_VERY_HIGH; + GPIO_InitStruct.Alternate = GPIO_AF10_OTG2_HS; + HAL_GPIO_Init(GPIOA, &GPIO_InitStruct); + + /* D1 D2 D3 D4 D5 D6 D7 */ + GPIO_InitStruct.Pin = GPIO_PIN_0 | GPIO_PIN_1 | GPIO_PIN_5 | GPIO_PIN_10 | GPIO_PIN_11 | GPIO_PIN_12 | GPIO_PIN_13; + GPIO_InitStruct.Mode = GPIO_MODE_AF_PP; + GPIO_InitStruct.Pull = GPIO_NOPULL; + GPIO_InitStruct.Alternate = GPIO_AF10_OTG2_HS; + HAL_GPIO_Init(GPIOB, &GPIO_InitStruct); + + /* STP */ + GPIO_InitStruct.Pin = GPIO_PIN_0; + GPIO_InitStruct.Mode = GPIO_MODE_AF_PP; + GPIO_InitStruct.Pull = GPIO_NOPULL; + GPIO_InitStruct.Alternate = GPIO_AF10_OTG2_HS; + HAL_GPIO_Init(GPIOC, &GPIO_InitStruct); + + /* NXT */ + GPIO_InitStruct.Pin = GPIO_PIN_4; + GPIO_InitStruct.Mode = GPIO_MODE_AF_PP; + GPIO_InitStruct.Pull = GPIO_NOPULL; + GPIO_InitStruct.Alternate = GPIO_AF10_OTG2_HS; + HAL_GPIO_Init(GPIOH, &GPIO_InitStruct); + + /* DIR */ + GPIO_InitStruct.Pin = GPIO_PIN_11; + GPIO_InitStruct.Mode = GPIO_MODE_AF_PP; + GPIO_InitStruct.Pull = GPIO_NOPULL; + GPIO_InitStruct.Alternate = GPIO_AF10_OTG2_HS; + HAL_GPIO_Init(GPIOI, &GPIO_InitStruct); + __HAL_RCC_USB1_OTG_HS_ULPI_CLK_ENABLE(); + + /* Enable USB HS Clocks */ + __HAL_RCC_USB1_OTG_HS_CLK_ENABLE(); + + // No VBUS sense + USB_OTG_HS->GCCFG &= ~USB_OTG_GCCFG_VBDEN; + + // Force device mode + // USB_OTG_HS->GUSBCFG &= ~USB_OTG_GUSBCFG_FHMOD; + // USB_OTG_HS->GUSBCFG |= USB_OTG_GUSBCFG_FDMOD; + + // B-peripheral session valid override enabl +// USB_OTG_HS->GOTGCTL |= USB_OTG_GOTGCTL_BVALOEN; +// USB_OTG_HS->GOTGCTL |= USB_OTG_GOTGCTL_BVALOVAL; +#endif // rhport = 1 + } //--------------------------------------------------------------------+ diff --git a/src/tusb_option.h b/src/tusb_option.h index 472656424..c251d578a 100644 --- a/src/tusb_option.h +++ b/src/tusb_option.h @@ -138,10 +138,6 @@ #define CFG_TUSB_RHPORT0_MODE OPT_MODE_NONE #endif -//#ifndef CFG_TUSB_RHPORT1_MODE -// #define CFG_TUSB_RHPORT1_MODE OPT_MODE_NONE -//#endif - #if ((CFG_TUSB_RHPORT0_MODE & OPT_MODE_HOST ) && (CFG_TUSB_RHPORT0_MODE & (OPT_MODE_HOST << 8)) ) || \ ((CFG_TUSB_RHPORT0_MODE & OPT_MODE_DEVICE) && (CFG_TUSB_RHPORT0_MODE & (OPT_MODE_DEVICE << 8)) ) #error "TinyUSB currently does not support same modes on more than 1 roothub port" diff --git a/test/test/support/tusb_config.h b/test/test/support/tusb_config.h index 5258513ec..76f975323 100644 --- a/test/test/support/tusb_config.h +++ b/test/test/support/tusb_config.h @@ -43,12 +43,7 @@ #define CFG_TUSB_MCU OPT_MCU_NRF5X #endif -#if CFG_TUSB_MCU == OPT_MCU_LPC43XX || CFG_TUSB_MCU == OPT_MCU_LPC18XX || CFG_TUSB_MCU == OPT_MCU_MIMXRT10XX #define CFG_TUSB_RHPORT0_MODE (OPT_MODE_DEVICE | OPT_MODE_HIGH_SPEED) -#else -#define CFG_TUSB_RHPORT0_MODE OPT_MODE_DEVICE -#endif - #define CFG_TUSB_OS OPT_OS_NONE // CFG_TUSB_DEBUG is defined by compiler in DEBUG build From b4804d1592901ee202f661f4e44e621a05aca315 Mon Sep 17 00:00:00 2001 From: hathach Date: Tue, 26 May 2020 22:15:38 +0700 Subject: [PATCH 07/48] random clean up for tdi --- src/portable/nxp/transdimension/dcd_transdimension.c | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/src/portable/nxp/transdimension/dcd_transdimension.c b/src/portable/nxp/transdimension/dcd_transdimension.c index 7baf43e23..68cf145ea 100644 --- a/src/portable/nxp/transdimension/dcd_transdimension.c +++ b/src/portable/nxp/transdimension/dcd_transdimension.c @@ -236,7 +236,7 @@ typedef struct { dcd_registers_t* regs; // registers const IRQn_Type irqnum; // IRQ number - const uint8_t ep_count; // Max bi-directional Endpoints + const uint8_t ep_count; // Max bi-directional Endpoints }dcd_controller_t; #if CFG_TUSB_MCU == OPT_MCU_MIMXRT10XX @@ -244,7 +244,7 @@ typedef struct // Therefore QHD_MAX is 2 x max endpoint count #define QHD_MAX (8*2) - dcd_controller_t _dcd_controller[] = + static const dcd_controller_t _dcd_controller[] = { // RT1010 and RT1020 only has 1 USB controller #if FSL_FEATURE_SOC_USBHS_COUNT == 1 @@ -258,7 +258,7 @@ typedef struct #else #define QHD_MAX (6*2) - dcd_controller_t _dcd_controller[] = + static const dcd_controller_t _dcd_controller[] = { { .regs = (dcd_registers_t*) LPC_USB0_BASE, .irqnum = USB0_IRQn, .ep_count = 6 }, { .regs = (dcd_registers_t*) LPC_USB1_BASE, .irqnum = USB1_IRQn, .ep_count = 4 } From 227bffe04b5d61e49a6f7e777c12e1efd7b498d1 Mon Sep 17 00:00:00 2001 From: hathach Date: Wed, 27 May 2020 01:14:52 +0700 Subject: [PATCH 08/48] adding h743 uart, but not enabled yet since it conflict with OTG_FS2 --- hw/bsp/stm32h743eval/board.mk | 7 ++++- hw/bsp/stm32h743eval/stm32h743eval.c | 35 +++++++++++++++++++++-- hw/bsp/stm32h743eval/stm32h7xx_hal_conf.h | 4 ++- 3 files changed, 41 insertions(+), 5 deletions(-) diff --git a/hw/bsp/stm32h743eval/board.mk b/hw/bsp/stm32h743eval/board.mk index 68d142435..5c6c6ea4f 100644 --- a/hw/bsp/stm32h743eval/board.mk +++ b/hw/bsp/stm32h743eval/board.mk @@ -12,7 +12,7 @@ CFLAGS += \ -DBOARD_DEVICE_RHPORT_SPEED=OPT_MODE_HIGH_SPEED # suppress warning caused by vendor mcu driver -CFLAGS += -Wno-error=maybe-uninitialized +CFLAGS += -Wno-error=maybe-uninitialized -Wno-error=cast-align ST_HAL_DRIVER = hw/mcu/st/st_driver/STM32H7xx_HAL_Driver ST_CMSIS = hw/mcu/st/st_driver/CMSIS/Device/ST/STM32H7xx @@ -27,6 +27,7 @@ SRC_C += \ $(ST_HAL_DRIVER)/Src/stm32h7xx_hal_rcc.c \ $(ST_HAL_DRIVER)/Src/stm32h7xx_hal_rcc_ex.c \ $(ST_HAL_DRIVER)/Src/stm32h7xx_hal_gpio.c \ + $(ST_HAL_DRIVER)/Src/stm32h7xx_hal_uart.c \ $(ST_HAL_DRIVER)/Src/stm32h7xx_hal_pwr_ex.c SRC_S += \ @@ -45,5 +46,9 @@ CHIP_FAMILY = synopsys # For freeRTOS port source FREERTOS_PORT = ARM_CM7/r0p1 +# For flash-jlink target +JLINK_DEVICE = stm32h743xi +JLINK_IF = jtag + # flash target using on-board stlink flash: flash-stlink diff --git a/hw/bsp/stm32h743eval/stm32h743eval.c b/hw/bsp/stm32h743eval/stm32h743eval.c index fd3d33047..d149c1230 100644 --- a/hw/bsp/stm32h743eval/stm32h743eval.c +++ b/hw/bsp/stm32h743eval/stm32h743eval.c @@ -61,13 +61,21 @@ void OTG_HS_IRQHandler(void) #define BUTTON_PIN GPIO_PIN_13 #define BUTTON_STATE_ACTIVE 0 +#define UARTx USART1 +#define UART_GPIO_PORT GPIOB +#define UART_GPIO_AF GPIO_AF4_USART1 +#define UART_TX_PIN GPIO_PIN_14 +#define UART_RX_PIN GPIO_PIN_15 + +UART_HandleTypeDef UartHandle; + // enable all LED, Button, Uart, USB clock static void all_rcc_clk_enable(void) { __HAL_RCC_GPIOA_CLK_ENABLE(); // LED __HAL_RCC_GPIOC_CLK_ENABLE(); // Button -// __HAL_RCC_GPIOD_CLK_ENABLE(); // Uart tx, rx -// __HAL_RCC_USART3_CLK_ENABLE(); // Uart module +// __HAL_RCC_GPIOB_CLK_ENABLE(); // Uart tx, rx +// __HAL_RCC_USART1_CLK_ENABLE(); // Uart module } /* PWR, RCC, GPIO (All): AHB4 (D3 domain) @@ -198,6 +206,26 @@ void board_init(void) GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_HIGH; HAL_GPIO_Init(BUTTON_PORT, &GPIO_InitStruct); +#if 0 + // 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_VERY_HIGH; + GPIO_InitStruct.Alternate = UART_GPIO_AF; + HAL_GPIO_Init(UART_GPIO_PORT, &GPIO_InitStruct); + + UartHandle.Instance = UARTx; + UartHandle.Init.BaudRate = CFG_BOARD_UART_BAUDRATE; + UartHandle.Init.WordLength = UART_WORDLENGTH_8B; + UartHandle.Init.StopBits = UART_STOPBITS_1; + UartHandle.Init.Parity = UART_PARITY_NONE; + UartHandle.Init.HwFlowCtl = UART_HWCONTROL_NONE; + UartHandle.Init.Mode = UART_MODE_TX_RX; + UartHandle.Init.OverSampling = UART_OVERSAMPLING_16; + HAL_UART_Init(&UartHandle); +#endif + #if BOARD_DEVICE_RHPORT_NUM == 0 // Despite being call USB2_OTG // OTG_FS is marked as RHPort0 by TinyUSB to be consistent across stm32 port @@ -330,7 +358,8 @@ int board_uart_read(uint8_t* buf, int len) int board_uart_write(void const * buf, int len) { (void) buf; (void) len; - return 0; +// HAL_UART_Transmit(&UartHandle, (uint8_t*) buf, len, 0xffff); + return len; } diff --git a/hw/bsp/stm32h743eval/stm32h7xx_hal_conf.h b/hw/bsp/stm32h743eval/stm32h7xx_hal_conf.h index 2a9eb37ae..b9fa348ec 100644 --- a/hw/bsp/stm32h743eval/stm32h7xx_hal_conf.h +++ b/hw/bsp/stm32h743eval/stm32h7xx_hal_conf.h @@ -100,7 +100,7 @@ /* #define HAL_SRAM_MODULE_ENABLED */ /* #define HAL_SWPMI_MODULE_ENABLED */ /* #define HAL_TIM_MODULE_ENABLED */ -/* #define HAL_UART_MODULE_ENABLED */ +#define HAL_UART_MODULE_ENABLED /* #define HAL_USART_MODULE_ENABLED */ /* #define HAL_WWDG_MODULE_ENABLED */ @@ -211,6 +211,8 @@ #define USE_HAL_SPI_REGISTER_CALLBACKS 0U /* SPI register callback disabled */ #define USE_HAL_SWPMI_REGISTER_CALLBACKS 0U /* SWPMI register callback disabled */ #define USE_HAL_TIM_REGISTER_CALLBACKS 0U /* TIM register callback disabled */ +#define USE_HAL_UART_REGISTER_CALLBACKS 0U /* UART register callback disabled */ +#define USE_HAL_USART_REGISTER_CALLBACKS 0U /* USART register callback disabled */ #define USE_HAL_WWDG_REGISTER_CALLBACKS 0U /* WWDG register callback disabled */ /* ########################### Ethernet Configuration ######################### */ From d4bf777c943659a4e985ce8514ef077c5bf2b40d Mon Sep 17 00:00:00 2001 From: hathach Date: Wed, 27 May 2020 11:01:33 +0700 Subject: [PATCH 09/48] try to get synopsys work with OTG HS + external PHY --- src/device/usbd.c | 1 + src/portable/st/synopsys/dcd_synopsys.c | 80 +++++++++++++++++++++---- 2 files changed, 68 insertions(+), 13 deletions(-) diff --git a/src/device/usbd.c b/src/device/usbd.c index f7918c07e..bd892e389 100644 --- a/src/device/usbd.c +++ b/src/device/usbd.c @@ -384,6 +384,7 @@ void tud_task (void) { case DCD_EVENT_BUS_RESET: usbd_reset(event.rhport); + // TODO DCD should report operational speed (LS/FS/HS) break; case DCD_EVENT_UNPLUGGED: diff --git a/src/portable/st/synopsys/dcd_synopsys.c b/src/portable/st/synopsys/dcd_synopsys.c index b68794712..8ca67dbb4 100644 --- a/src/portable/st/synopsys/dcd_synopsys.c +++ b/src/portable/st/synopsys/dcd_synopsys.c @@ -99,7 +99,7 @@ static const dcd_rhport_t _dcd_rhport[] = { .regs = USB_OTG_FS_PERIPH_BASE, .irqnum = OTG_FS_IRQn } #ifdef USB_OTG_HS - ,{ .regs = USB_OTG_HS_PERIPH_BASE, .irqnum = OTG_HS_IRQn } + ,{ .regs = USB_OTG_HS_PERIPH_BASE, .irqnum = OTG_HS_IRQn } #endif }; @@ -218,16 +218,48 @@ static void end_of_reset(uint8_t rhport) *------------------------------------------------------------------*/ void dcd_init (uint8_t rhport) { + dcd_disconnect(rhport); + USB_OTG_GlobalTypeDef * usb_otg = GLOBAL_BASE(rhport); - // Programming model begins in the last section of the chapter on the USB - // peripheral in each Reference Manual. - usb_otg->GAHBCFG |= USB_OTG_GAHBCFG_GINT; + // No HNP/SRP (no OTG support), program timeout later. +#if TUD_OPT_HIGH_SPEED // TODO may pass parameter instead of using macro for HighSpeed + if ( rhport == 1 ) + { + // Highspeed with external ULPI PHY - // No HNP/SRP (no OTG support), program timeout later, turnaround - // programmed for 32+ MHz. - // TODO: PHYSEL is read-only on some cores (STM32F407). Worth gating? - usb_otg->GUSBCFG |= (0x06 << USB_OTG_GUSBCFG_TRDT_Pos) | USB_OTG_GUSBCFG_PHYSEL; + // deactivate internal PHY + usb_otg->GCCFG &= ~USB_OTG_GCCFG_PWRDWN; + + // On selected MCUs HS port1 can be used with external PHY via ULPI interface + // Select ULPI highspeed PHY with default external VBUS Indicator and Drive + usb_otg->GUSBCFG &= ~(USB_OTG_GUSBCFG_TSDPS | USB_OTG_GUSBCFG_ULPIFSLS | USB_OTG_GUSBCFG_PHYSEL | + USB_OTG_GUSBCFG_ULPIEVBUSD | USB_OTG_GUSBCFG_ULPIEVBUSI); + + // Turn around time for Highspeed is 0x09 + usb_otg->GUSBCFG &= ~USB_OTG_GUSBCFG_TRDT; + usb_otg->GUSBCFG |= (0x09 << USB_OTG_GUSBCFG_TRDT_Pos); + }else +#endif + { + // Turn around programmed for 32+ MHz is 0x06 + usb_otg->GUSBCFG &= ~USB_OTG_GUSBCFG_TRDT; + usb_otg->GUSBCFG |= (0x06 << USB_OTG_GUSBCFG_TRDT_Pos) | USB_OTG_GUSBCFG_PHYSEL; + } + + // Reset core after selecting PHY + // Wait AHB IDLE, reset then wait until it is cleared + while ((usb_otg->GRSTCTL & USB_OTG_GRSTCTL_AHBIDL) == 0U) {} + usb_otg->GRSTCTL |= USB_OTG_GRSTCTL_CSRST; + while ((usb_otg->GRSTCTL & USB_OTG_GRSTCTL_CSRST) == USB_OTG_GRSTCTL_CSRST) {} + + // Force device mode + usb_otg->GUSBCFG |= USB_OTG_GUSBCFG_FDMOD; + + TU_LOG2_LOCATION(); + + // Restart PHY clock + *((volatile uint32_t *)(_dcd_rhport[rhport].regs + USB_OTG_PCGCCTL_BASE)) = 0; // Clear all interrupts usb_otg->GINTSTS |= usb_otg->GINTSTS; @@ -241,14 +273,33 @@ void dcd_init (uint8_t rhport) // If USB host misbehaves during status portion of control xfer // (non zero-length packet), send STALL back and discard. Full speed. - dev->DCFG |= USB_OTG_DCFG_NZLSOHSK | (3 << USB_OTG_DCFG_DSPD_Pos); + dev->DCFG |= USB_OTG_DCFG_NZLSOHSK; + +#if TUD_OPT_HIGH_SPEED + if ( rhport == 1 ) + { + // high speed = 0x00 + dev->DCFG &= ~(3 << USB_OTG_DCFG_DSPD_Pos); + + // Transceiver delay, necessary for some ULPI PHYs + dev->DCFG |= (1 << 14); + } +#endif + { + // full speed with internal phy + dev->DCFG |= (3 << USB_OTG_DCFG_DSPD_Pos); + + // Enable USB transceiver. + usb_otg->GCCFG |= USB_OTG_GCCFG_PWRDWN; + } usb_otg->GINTMSK |= USB_OTG_GINTMSK_USBRST | USB_OTG_GINTMSK_ENUMDNEM | - USB_OTG_GINTMSK_USBSUSPM | USB_OTG_GINTMSK_WUIM | - USB_OTG_GINTMSK_RXFLVLM | (USE_SOF ? USB_OTG_GINTMSK_SOFM : 0); + USB_OTG_GINTMSK_USBSUSPM | USB_OTG_GINTMSK_WUIM | + USB_OTG_GINTMSK_RXFLVLM | (USE_SOF ? USB_OTG_GINTMSK_SOFM : 0); - // Enable USB transceiver. - usb_otg->GCCFG |= USB_OTG_GCCFG_PWRDWN; + // Programming model begins in the last section of the chapter on the USB + // peripheral in each Reference Manual. + usb_otg->GAHBCFG |= USB_OTG_GAHBCFG_GINT; } void dcd_int_enable (uint8_t rhport) @@ -739,6 +790,9 @@ void dcd_int_handler(uint8_t rhport) // ENUMDNE detects speed of the link. For full-speed, we // always expect the same value. This interrupt is considered // the end of reset. + + TU_LOG2_HEX(dev->DSTS); + usb_otg->GINTSTS = USB_OTG_GINTSTS_ENUMDNE; end_of_reset(rhport); dcd_event_bus_signal(rhport, DCD_EVENT_BUS_RESET, true); From 5ffba8536dfaa4602e3e7f1c94be124bfeb3a5ae Mon Sep 17 00:00:00 2001 From: hathach Date: Sun, 31 May 2020 19:41:22 +0700 Subject: [PATCH 10/48] able to detect as hs --- hw/bsp/stm32h743eval/stm32h743eval.c | 13 +++++++++---- src/common/tusb_common.h | 4 +++- src/portable/st/synopsys/dcd_synopsys.c | 10 ++++++---- 3 files changed, 18 insertions(+), 9 deletions(-) diff --git a/hw/bsp/stm32h743eval/stm32h743eval.c b/hw/bsp/stm32h743eval/stm32h743eval.c index d149c1230..836f1ecab 100644 --- a/hw/bsp/stm32h743eval/stm32h743eval.c +++ b/hw/bsp/stm32h743eval/stm32h743eval.c @@ -265,6 +265,7 @@ void board_init(void) #endif #if BOARD_DEVICE_RHPORT_NUM == 1 + // Despite being call USB2_OTG // OTG_HS is marked as RHPort1 by TinyUSB to be consistent across stm32 port __GPIOA_CLK_ENABLE(); @@ -316,6 +317,8 @@ void board_init(void) GPIO_InitStruct.Pull = GPIO_NOPULL; GPIO_InitStruct.Alternate = GPIO_AF10_OTG2_HS; HAL_GPIO_Init(GPIOI, &GPIO_InitStruct); + + // Enable ULPI clock __HAL_RCC_USB1_OTG_HS_ULPI_CLK_ENABLE(); /* Enable USB HS Clocks */ @@ -325,12 +328,14 @@ void board_init(void) USB_OTG_HS->GCCFG &= ~USB_OTG_GCCFG_VBDEN; // Force device mode - // USB_OTG_HS->GUSBCFG &= ~USB_OTG_GUSBCFG_FHMOD; - // USB_OTG_HS->GUSBCFG |= USB_OTG_GUSBCFG_FDMOD; + USB_OTG_HS->GUSBCFG &= ~USB_OTG_GUSBCFG_FHMOD; + USB_OTG_HS->GUSBCFG |= USB_OTG_GUSBCFG_FDMOD; // B-peripheral session valid override enabl -// USB_OTG_HS->GOTGCTL |= USB_OTG_GOTGCTL_BVALOEN; -// USB_OTG_HS->GOTGCTL |= USB_OTG_GOTGCTL_BVALOVAL; + USB_OTG_HS->GOTGCTL |= USB_OTG_GOTGCTL_BVALOEN; + USB_OTG_HS->GOTGCTL |= USB_OTG_GOTGCTL_BVALOVAL; + + HAL_PWREx_EnableUSBVoltageDetector(); #endif // rhport = 1 } diff --git a/src/common/tusb_common.h b/src/common/tusb_common.h index f144cda73..d77893b6b 100644 --- a/src/common/tusb_common.h +++ b/src/common/tusb_common.h @@ -241,9 +241,9 @@ void tu_print_var(uint8_t const* buf, uint32_t bufsize) #define TU_LOG2 TU_LOG1 #define TU_LOG2_MEM TU_LOG1_MEM #define TU_LOG2_VAR TU_LOG1_VAR - #define TU_LOG2_LOCATION() TU_LOG1_LOCATION() #define TU_LOG2_INT TU_LOG1_INT #define TU_LOG2_HEX TU_LOG1_HEX + #define TU_LOG2_LOCATION() TU_LOG1_LOCATION() #endif @@ -277,6 +277,7 @@ static inline char const* lookup_find(lookup_table_t const* p_table, uint32_t ke #define TU_LOG1_VAR(...) #define TU_LOG1_INT(...) #define TU_LOG1_HEX(...) + #define TU_LOG1_LOCATION() #endif #ifndef TU_LOG2 @@ -285,6 +286,7 @@ static inline char const* lookup_find(lookup_table_t const* p_table, uint32_t ke #define TU_LOG2_VAR(...) #define TU_LOG2_INT(...) #define TU_LOG2_HEX(...) + #define TU_LOG2_LOCATION() #endif #ifdef __cplusplus diff --git a/src/portable/st/synopsys/dcd_synopsys.c b/src/portable/st/synopsys/dcd_synopsys.c index 8ca67dbb4..fe6fe5cea 100644 --- a/src/portable/st/synopsys/dcd_synopsys.c +++ b/src/portable/st/synopsys/dcd_synopsys.c @@ -197,6 +197,8 @@ static void end_of_reset(uint8_t rhport) // However, keep for debugging and in case Low Speed is ever supported. uint32_t enum_spd = (dev->DSTS & USB_OTG_DSTS_ENUMSPD_Msk) >> USB_OTG_DSTS_ENUMSPD_Pos; + // TODO set turnaround in GUSBCFG accordingly to the speed + // Maximum packet size for EP 0 is set for both directions by writing // DIEPCTL. if(enum_spd == 0x03) { @@ -239,7 +241,8 @@ void dcd_init (uint8_t rhport) // Turn around time for Highspeed is 0x09 usb_otg->GUSBCFG &= ~USB_OTG_GUSBCFG_TRDT; usb_otg->GUSBCFG |= (0x09 << USB_OTG_GUSBCFG_TRDT_Pos); - }else + } + else #endif { // Turn around programmed for 32+ MHz is 0x06 @@ -256,8 +259,6 @@ void dcd_init (uint8_t rhport) // Force device mode usb_otg->GUSBCFG |= USB_OTG_GUSBCFG_FDMOD; - TU_LOG2_LOCATION(); - // Restart PHY clock *((volatile uint32_t *)(_dcd_rhport[rhport].regs + USB_OTG_PCGCCTL_BASE)) = 0; @@ -282,8 +283,9 @@ void dcd_init (uint8_t rhport) dev->DCFG &= ~(3 << USB_OTG_DCFG_DSPD_Pos); // Transceiver delay, necessary for some ULPI PHYs - dev->DCFG |= (1 << 14); + //dev->DCFG |= (1 << 14); } + else #endif { // full speed with internal phy From f771afe6af894a5f3ee029756d4521b56d74c1c0 Mon Sep 17 00:00:00 2001 From: hathach Date: Sun, 31 May 2020 23:43:29 +0700 Subject: [PATCH 11/48] fixed EP0 size to 64 since LS is not supported in device mode - set turn-around and report actual speed in Enum Done - add dcd_event_bus_reset() helper to report speed --- src/device/dcd.h | 15 ++++- src/device/usbd.c | 9 ++- src/portable/st/synopsys/dcd_synopsys.c | 85 ++++++++++++------------- 3 files changed, 62 insertions(+), 47 deletions(-) diff --git a/src/device/dcd.h b/src/device/dcd.h index 68798c259..a4635346b 100644 --- a/src/device/dcd.h +++ b/src/device/dcd.h @@ -60,11 +60,17 @@ typedef struct TU_ATTR_ALIGNED(4) uint8_t rhport; uint8_t event_id; - union { - // USBD_EVT_SETUP_RECEIVED + union + { + // BUS RESET + struct { + tusb_speed_t speed; + } bus_reset; + + // SETUP_RECEIVED tusb_control_request_t setup_received; - // USBD_EVT_XFER_COMPLETE + // XFER_COMPLETE struct { uint8_t ep_addr; uint8_t result; @@ -143,6 +149,9 @@ extern void dcd_event_handler(dcd_event_t const * event, bool in_isr); // helper to send bus signal event extern void dcd_event_bus_signal (uint8_t rhport, dcd_eventid_t eid, bool in_isr); +// helper to send bus reset event +extern void dcd_event_bus_reset (uint8_t rhport, tusb_speed_t speed, bool in_isr); + // helper to send setup received extern void dcd_event_setup_received(uint8_t rhport, uint8_t const * setup, bool in_isr); diff --git a/src/device/usbd.c b/src/device/usbd.c index bd892e389..275792ab9 100644 --- a/src/device/usbd.c +++ b/src/device/usbd.c @@ -920,7 +920,14 @@ void dcd_event_handler(dcd_event_t const * event, bool in_isr) void dcd_event_bus_signal (uint8_t rhport, dcd_eventid_t eid, bool in_isr) { - dcd_event_t event = { .rhport = rhport, .event_id = eid, }; + dcd_event_t event = { .rhport = rhport, .event_id = eid }; + dcd_event_handler(&event, in_isr); +} + +void dcd_event_bus_reset (uint8_t rhport, tusb_speed_t speed, bool in_isr) +{ + dcd_event_t event = { .rhport = rhport, .event_id = DCD_EVENT_BUS_RESET }; + event.bus_reset.speed = speed; dcd_event_handler(&event, in_isr); } diff --git a/src/portable/st/synopsys/dcd_synopsys.c b/src/portable/st/synopsys/dcd_synopsys.c index fe6fe5cea..ed16308da 100644 --- a/src/portable/st/synopsys/dcd_synopsys.c +++ b/src/portable/st/synopsys/dcd_synopsys.c @@ -109,6 +109,13 @@ static const dcd_rhport_t _dcd_rhport[] = #define IN_EP_BASE(_port) (USB_OTG_INEndpointTypeDef *) (_dcd_rhport[_port].regs + USB_OTG_IN_ENDPOINT_BASE) #define FIFO_BASE(_port, _x) ((volatile uint32_t *) (_dcd_rhport[_port].regs + USB_OTG_FIFO_BASE + (_x) * USB_OTG_FIFO_SIZE)) +enum +{ + DCD_HIGH_SPEED = 0, // Highspeed mode + DCD_FULL_SPEED_USE_HS = 1, // Full speed in Highspeed port (probably with internal PHY) + DCD_FULL_SPEED = 3, // Full speed with internal PHY +}; + /*------------------------------------------------------------------*/ /* MACRO TYPEDEF CONSTANT ENUM @@ -141,6 +148,7 @@ static void bus_reset(uint8_t rhport) USB_OTG_GlobalTypeDef * usb_otg = GLOBAL_BASE(rhport); USB_OTG_DeviceTypeDef * dev = DEVICE_BASE(rhport); USB_OTG_OUTEndpointTypeDef * out_ep = OUT_EP_BASE(rhport); + USB_OTG_INEndpointTypeDef * in_ep = IN_EP_BASE(rhport); for(uint8_t n = 0; n < EP_MAX; n++) { out_ep[n].DOEPCTL |= USB_OTG_DOEPCTL_SNAK; @@ -183,34 +191,29 @@ static void bus_reset(uint8_t rhport) // Control IN uses FIFO 0 with 64 bytes ( 16 32-bit word ) usb_otg->DIEPTXF0_HNPTXFSIZ = (16 << USB_OTG_TX0FD_Pos) | (usb_otg->GRXFSIZ & 0x0000ffffUL); + // Fixed control EP0 size to 64 bytes + in_ep[0].DIEPCTL &= ~(0x03 << USB_OTG_DIEPCTL_MPSIZ_Pos); + xfer_status[0][TUSB_DIR_OUT].max_size = xfer_status[0][TUSB_DIR_IN].max_size = 64; + out_ep[0].DOEPTSIZ |= (3 << USB_OTG_DOEPTSIZ_STUPCNT_Pos); usb_otg->GINTMSK |= USB_OTG_GINTMSK_OEPINT | USB_OTG_GINTMSK_IEPINT; } -static void end_of_reset(uint8_t rhport) +// speed is native DCD speed +static void set_turnaround(USB_OTG_GlobalTypeDef * usb_otg, uint32_t speed) { - USB_OTG_DeviceTypeDef * dev = DEVICE_BASE(rhport); - USB_OTG_INEndpointTypeDef * in_ep = IN_EP_BASE(rhport); + usb_otg->GUSBCFG &= ~USB_OTG_GUSBCFG_TRDT; - // On current silicon on the Full Speed core, speed is fixed to Full Speed. - // However, keep for debugging and in case Low Speed is ever supported. - uint32_t enum_spd = (dev->DSTS & USB_OTG_DSTS_ENUMSPD_Msk) >> USB_OTG_DSTS_ENUMSPD_Pos; - - // TODO set turnaround in GUSBCFG accordingly to the speed - - // Maximum packet size for EP 0 is set for both directions by writing - // DIEPCTL. - if(enum_spd == 0x03) { - // 64 bytes - in_ep[0].DIEPCTL &= ~(0x03 << USB_OTG_DIEPCTL_MPSIZ_Pos); - xfer_status[0][TUSB_DIR_OUT].max_size = 64; - xfer_status[0][TUSB_DIR_IN].max_size = 64; - } else { - // 8 bytes - in_ep[0].DIEPCTL |= (0x03 << USB_OTG_DIEPCTL_MPSIZ_Pos); - xfer_status[0][TUSB_DIR_OUT].max_size = 8; - xfer_status[0][TUSB_DIR_IN].max_size = 8; + if ( speed == DCD_HIGH_SPEED ) + { + // Use fixed 0x09 for Highspeed + usb_otg->GUSBCFG |= (0x09 << USB_OTG_GUSBCFG_TRDT_Pos); + } + else + { + // Fullspeed depends on MCU clocks, but we will use 0x06 for 32+ Mhz + usb_otg->GUSBCFG |= (0x06 << USB_OTG_GUSBCFG_TRDT_Pos); } } @@ -220,7 +223,8 @@ static void end_of_reset(uint8_t rhport) *------------------------------------------------------------------*/ void dcd_init (uint8_t rhport) { - dcd_disconnect(rhport); + // Programming model begins in the last section of the chapter on the USB + // peripheral in each Reference Manual. USB_OTG_GlobalTypeDef * usb_otg = GLOBAL_BASE(rhport); @@ -238,16 +242,15 @@ void dcd_init (uint8_t rhport) usb_otg->GUSBCFG &= ~(USB_OTG_GUSBCFG_TSDPS | USB_OTG_GUSBCFG_ULPIFSLS | USB_OTG_GUSBCFG_PHYSEL | USB_OTG_GUSBCFG_ULPIEVBUSD | USB_OTG_GUSBCFG_ULPIEVBUSI); - // Turn around time for Highspeed is 0x09 - usb_otg->GUSBCFG &= ~USB_OTG_GUSBCFG_TRDT; - usb_otg->GUSBCFG |= (0x09 << USB_OTG_GUSBCFG_TRDT_Pos); + set_turnaround(usb_otg, DCD_HIGH_SPEED); } else #endif { - // Turn around programmed for 32+ MHz is 0x06 - usb_otg->GUSBCFG &= ~USB_OTG_GUSBCFG_TRDT; - usb_otg->GUSBCFG |= (0x06 << USB_OTG_GUSBCFG_TRDT_Pos) | USB_OTG_GUSBCFG_PHYSEL; + set_turnaround(usb_otg, DCD_FULL_SPEED); + + // Enable internal PHY + usb_otg->GUSBCFG |= USB_OTG_GUSBCFG_PHYSEL; } // Reset core after selecting PHY @@ -256,9 +259,6 @@ void dcd_init (uint8_t rhport) usb_otg->GRSTCTL |= USB_OTG_GRSTCTL_CSRST; while ((usb_otg->GRSTCTL & USB_OTG_GRSTCTL_CSRST) == USB_OTG_GRSTCTL_CSRST) {} - // Force device mode - usb_otg->GUSBCFG |= USB_OTG_GUSBCFG_FDMOD; - // Restart PHY clock *((volatile uint32_t *)(_dcd_rhport[rhport].regs + USB_OTG_PCGCCTL_BASE)) = 0; @@ -273,7 +273,7 @@ void dcd_init (uint8_t rhport) USB_OTG_DeviceTypeDef * dev = DEVICE_BASE(rhport); // If USB host misbehaves during status portion of control xfer - // (non zero-length packet), send STALL back and discard. Full speed. + // (non zero-length packet), send STALL back and discard. dev->DCFG |= USB_OTG_DCFG_NZLSOHSK; #if TUD_OPT_HIGH_SPEED @@ -288,10 +288,10 @@ void dcd_init (uint8_t rhport) else #endif { - // full speed with internal phy + // full speed with internal PHY dev->DCFG |= (3 << USB_OTG_DCFG_DSPD_Pos); - // Enable USB transceiver. + // Enable internal USB transceiver. usb_otg->GCCFG |= USB_OTG_GCCFG_PWRDWN; } @@ -299,8 +299,8 @@ void dcd_init (uint8_t rhport) USB_OTG_GINTMSK_USBSUSPM | USB_OTG_GINTMSK_WUIM | USB_OTG_GINTMSK_RXFLVLM | (USE_SOF ? USB_OTG_GINTMSK_SOFM : 0); - // Programming model begins in the last section of the chapter on the USB - // peripheral in each Reference Manual. + + // Enable global interrupt usb_otg->GAHBCFG |= USB_OTG_GAHBCFG_GINT; } @@ -789,15 +789,14 @@ void dcd_int_handler(uint8_t rhport) } if(int_status & USB_OTG_GINTSTS_ENUMDNE) { - // ENUMDNE detects speed of the link. For full-speed, we - // always expect the same value. This interrupt is considered - // the end of reset. - - TU_LOG2_HEX(dev->DSTS); + // ENUMDNE is the end of reset where speed of the link is detected usb_otg->GINTSTS = USB_OTG_GINTSTS_ENUMDNE; - end_of_reset(rhport); - dcd_event_bus_signal(rhport, DCD_EVENT_BUS_RESET, true); + + uint32_t const enum_spd = (dev->DSTS & USB_OTG_DSTS_ENUMSPD_Msk) >> USB_OTG_DSTS_ENUMSPD_Pos; + + set_turnaround(usb_otg, enum_spd); + dcd_event_bus_reset(rhport, (enum_spd == DCD_HIGH_SPEED) ? TUSB_SPEED_HIGH : TUSB_SPEED_FULL, true); } if(int_status & USB_OTG_GINTSTS_USBSUSP) From 710c54f8cbee2134334262cf872f538909b264c5 Mon Sep 17 00:00:00 2001 From: hathach Date: Mon, 1 Jun 2020 01:36:09 +0700 Subject: [PATCH 12/48] allow hs ep open with 512 bytes --- examples/device/cdc_msc/src/usb_descriptors.c | 2 +- src/portable/st/synopsys/dcd_synopsys.c | 30 ++++++++++++------- 2 files changed, 21 insertions(+), 11 deletions(-) diff --git a/examples/device/cdc_msc/src/usb_descriptors.c b/examples/device/cdc_msc/src/usb_descriptors.c index 7b22d46a7..62ab4f10f 100644 --- a/examples/device/cdc_msc/src/usb_descriptors.c +++ b/examples/device/cdc_msc/src/usb_descriptors.c @@ -123,7 +123,7 @@ uint8_t const desc_configuration[] = TUD_CDC_DESCRIPTOR(ITF_NUM_CDC, 4, EPNUM_CDC_NOTIF, 8, EPNUM_CDC_OUT, EPNUM_CDC_IN, 64), // Interface number, string index, EP Out & EP In address, EP size - TUD_MSC_DESCRIPTOR(ITF_NUM_MSC, 5, EPNUM_MSC_OUT, EPNUM_MSC_IN, (CFG_TUSB_RHPORT0_MODE & OPT_MODE_HIGH_SPEED) ? 512 : 64), + TUD_MSC_DESCRIPTOR(ITF_NUM_MSC, 5, EPNUM_MSC_OUT, EPNUM_MSC_IN, TUD_OPT_HIGH_SPEED ? 512 : 64), }; diff --git a/src/portable/st/synopsys/dcd_synopsys.c b/src/portable/st/synopsys/dcd_synopsys.c index ed16308da..739361da9 100644 --- a/src/portable/st/synopsys/dcd_synopsys.c +++ b/src/portable/st/synopsys/dcd_synopsys.c @@ -185,8 +185,9 @@ static void bus_reset(uint8_t rhport) // * 16 for largest packet size of 64 bytes. ( TODO Highspeed is 512 bytes) // * 1 location for global NAK (not required/used here). // * It is recommended to allocate 2 times the largest packet size, therefore - // Recommended value = 10 + 1 + 2 x (16+2) = 47 --> Let's make it 52 - usb_otg->GRXFSIZ = 52; + // Recommended value = 10 + 1 + 2 x (16+2) = 47. To make it scale better with large FIFO size + // and work better with Highspeed. We use 1/5 of total FIFO size + usb_otg->GRXFSIZ = (EP_FIFO_SIZE/4)/5; // Control IN uses FIFO 0 with 64 bytes ( 16 32-bit word ) usb_otg->DIEPTXF0_HNPTXFSIZ = (16 << USB_OTG_TX0FD_Pos) | (usb_otg->GRXFSIZ & 0x0000ffffUL); @@ -201,11 +202,11 @@ static void bus_reset(uint8_t rhport) } // speed is native DCD speed -static void set_turnaround(USB_OTG_GlobalTypeDef * usb_otg, uint32_t speed) +static void set_turnaround(USB_OTG_GlobalTypeDef * usb_otg, tusb_speed_t speed) { usb_otg->GUSBCFG &= ~USB_OTG_GUSBCFG_TRDT; - if ( speed == DCD_HIGH_SPEED ) + if ( speed == TUSB_SPEED_HIGH ) { // Use fixed 0x09 for Highspeed usb_otg->GUSBCFG |= (0x09 << USB_OTG_GUSBCFG_TRDT_Pos); @@ -217,6 +218,12 @@ static void set_turnaround(USB_OTG_GlobalTypeDef * usb_otg, uint32_t speed) } } +static tusb_speed_t get_speed(USB_OTG_DeviceTypeDef* dev) +{ + uint32_t const enum_spd = (dev->DSTS & USB_OTG_DSTS_ENUMSPD_Msk) >> USB_OTG_DSTS_ENUMSPD_Pos; + return (enum_spd == DCD_HIGH_SPEED) ? TUSB_SPEED_HIGH : TUSB_SPEED_FULL; +} + /*------------------------------------------------------------------*/ /* Controller API @@ -242,12 +249,12 @@ void dcd_init (uint8_t rhport) usb_otg->GUSBCFG &= ~(USB_OTG_GUSBCFG_TSDPS | USB_OTG_GUSBCFG_ULPIFSLS | USB_OTG_GUSBCFG_PHYSEL | USB_OTG_GUSBCFG_ULPIEVBUSD | USB_OTG_GUSBCFG_ULPIEVBUSI); - set_turnaround(usb_otg, DCD_HIGH_SPEED); + set_turnaround(usb_otg, TUSB_SPEED_HIGH); } else #endif { - set_turnaround(usb_otg, DCD_FULL_SPEED); + set_turnaround(usb_otg, TUSB_SPEED_FULL); // Enable internal PHY usb_otg->GUSBCFG |= USB_OTG_GUSBCFG_PHYSEL; @@ -357,9 +364,11 @@ bool dcd_edpt_open (uint8_t rhport, tusb_desc_endpoint_t const * desc_edpt) uint8_t const epnum = tu_edpt_number(desc_edpt->bEndpointAddress); uint8_t const dir = tu_edpt_dir(desc_edpt->bEndpointAddress); - TU_ASSERT(desc_edpt->wMaxPacketSize.size <= 64); TU_ASSERT(epnum < EP_MAX); + // TODO ISO endpoint can be up to 1024 bytes + TU_ASSERT(desc_edpt->wMaxPacketSize.size <= (get_speed(dev) == TUSB_SPEED_HIGH ? 512 : 64)); + xfer_ctl_t * xfer = XFER_CTL_BASE(epnum, dir); xfer->max_size = desc_edpt->wMaxPacketSize.size; @@ -447,6 +456,7 @@ bool dcd_edpt_xfer (uint8_t rhport, uint8_t ep_addr, uint8_t * buffer, uint16_t ((total_bytes & USB_OTG_DIEPTSIZ_XFRSIZ_Msk) << USB_OTG_DIEPTSIZ_XFRSIZ_Pos); in_ep[epnum].DIEPCTL |= USB_OTG_DIEPCTL_EPENA | USB_OTG_DIEPCTL_CNAK; + // Enable fifo empty interrupt only if there are something to put in the fifo. if(total_bytes != 0) { dev->DIEPEMPMSK |= (1 << epnum); @@ -793,10 +803,10 @@ void dcd_int_handler(uint8_t rhport) usb_otg->GINTSTS = USB_OTG_GINTSTS_ENUMDNE; - uint32_t const enum_spd = (dev->DSTS & USB_OTG_DSTS_ENUMSPD_Msk) >> USB_OTG_DSTS_ENUMSPD_Pos; + tusb_speed_t const speed = get_speed(dev); - set_turnaround(usb_otg, enum_spd); - dcd_event_bus_reset(rhport, (enum_spd == DCD_HIGH_SPEED) ? TUSB_SPEED_HIGH : TUSB_SPEED_FULL, true); + set_turnaround(usb_otg, speed); + dcd_event_bus_reset(rhport, speed, true); } if(int_status & USB_OTG_GINTSTS_USBSUSP) From e92118635cc8055a5ca599eaf9919d99a55bf584 Mon Sep 17 00:00:00 2001 From: hathach Date: Mon, 1 Jun 2020 13:40:18 +0700 Subject: [PATCH 13/48] adding speed detect on bus reset --- hw/bsp/stm32h743eval/board.mk | 2 +- src/device/usbd.c | 7 +++++-- 2 files changed, 6 insertions(+), 3 deletions(-) diff --git a/hw/bsp/stm32h743eval/board.mk b/hw/bsp/stm32h743eval/board.mk index 5c6c6ea4f..cbf37a95d 100644 --- a/hw/bsp/stm32h743eval/board.mk +++ b/hw/bsp/stm32h743eval/board.mk @@ -48,7 +48,7 @@ FREERTOS_PORT = ARM_CM7/r0p1 # For flash-jlink target JLINK_DEVICE = stm32h743xi -JLINK_IF = jtag +JLINK_IF = swd # flash target using on-board stlink flash: flash-stlink diff --git a/src/device/usbd.c b/src/device/usbd.c index 275792ab9..eeb5011ec 100644 --- a/src/device/usbd.c +++ b/src/device/usbd.c @@ -40,7 +40,8 @@ //--------------------------------------------------------------------+ // Device Data //--------------------------------------------------------------------+ -typedef struct { +typedef struct +{ struct TU_ATTR_PACKED { volatile uint8_t connected : 1; @@ -53,6 +54,8 @@ typedef struct { uint8_t self_powered : 1; // configuration descriptor's attribute }; + uint8_t speed; + uint8_t itf2drv[16]; // map interface number to driver (0xff is invalid) uint8_t ep2drv[8][2]; // map endpoint to driver ( 0xff is invalid ) @@ -384,7 +387,7 @@ void tud_task (void) { case DCD_EVENT_BUS_RESET: usbd_reset(event.rhport); - // TODO DCD should report operational speed (LS/FS/HS) + _usbd_dev.speed = event.bus_reset.speed; break; case DCD_EVENT_UNPLUGGED: From a347de6e50e98b339a1605dc927c0417e79b86a5 Mon Sep 17 00:00:00 2001 From: hathach Date: Sun, 14 Jun 2020 18:28:45 +0700 Subject: [PATCH 14/48] revert CFG_TUSB_RHPORT0_MODE to previous way --- examples/device/cdc_msc/src/tusb_config.h | 9 ++++++++- hw/bsp/stm32h743eval/stm32h743eval.c | 3 +-- src/tusb_option.h | 23 ++++++++++++----------- 3 files changed, 21 insertions(+), 14 deletions(-) diff --git a/examples/device/cdc_msc/src/tusb_config.h b/examples/device/cdc_msc/src/tusb_config.h index 9beb9f6a2..b05d219c6 100644 --- a/examples/device/cdc_msc/src/tusb_config.h +++ b/examples/device/cdc_msc/src/tusb_config.h @@ -56,7 +56,14 @@ #endif // Device mode with rhport and speed defined by board.mk -#define CFG_TUSB_RHPORT0_MODE ((OPT_MODE_DEVICE | BOARD_DEVICE_RHPORT_SPEED) << (8*BOARD_DEVICE_RHPORT_NUM)) +#if BOARD_DEVICE_RHPORT_NUM == 0 + #define CFG_TUSB_RHPORT0_MODE (OPT_MODE_DEVICE | BOARD_DEVICE_RHPORT_SPEED) +#elif BOARD_DEVICE_RHPORT_NUM == 1 + #define CFG_TUSB_RHPORT1_MODE (OPT_MODE_DEVICE | BOARD_DEVICE_RHPORT_SPEED) +#else + #error "Incorrect RHPort configuration" +#endif + #define CFG_TUSB_OS OPT_OS_NONE // CFG_TUSB_DEBUG is defined by compiler in DEBUG build diff --git a/hw/bsp/stm32h743eval/stm32h743eval.c b/hw/bsp/stm32h743eval/stm32h743eval.c index 836f1ecab..a28110920 100644 --- a/hw/bsp/stm32h743eval/stm32h743eval.c +++ b/hw/bsp/stm32h743eval/stm32h743eval.c @@ -262,9 +262,8 @@ void board_init(void) // Enable VBUS sense (B device) via pin PA9 USB_OTG_FS->GCCFG |= USB_OTG_GCCFG_VBDEN; -#endif -#if BOARD_DEVICE_RHPORT_NUM == 1 +#elif BOARD_DEVICE_RHPORT_NUM == 1 // Despite being call USB2_OTG // OTG_HS is marked as RHPort1 by TinyUSB to be consistent across stm32 port diff --git a/src/tusb_option.h b/src/tusb_option.h index c251d578a..01bb1301a 100644 --- a/src/tusb_option.h +++ b/src/tusb_option.h @@ -117,10 +117,7 @@ //-------------------------------------------------------------------- // RootHub Mode Configuration -// -// Each byte of the CFG_TUSB_RHPORTx_MODE contains operation mode for -// a roothub port (device or host). Therefore each macro can have up to -// 4 ports. +// CFG_TUSB_RHPORTx_MODE contains operation mode and speed for that port //-------------------------------------------------------------------- // Lower 4-bit is operational mode @@ -138,27 +135,31 @@ #define CFG_TUSB_RHPORT0_MODE OPT_MODE_NONE #endif -#if ((CFG_TUSB_RHPORT0_MODE & OPT_MODE_HOST ) && (CFG_TUSB_RHPORT0_MODE & (OPT_MODE_HOST << 8)) ) || \ - ((CFG_TUSB_RHPORT0_MODE & OPT_MODE_DEVICE) && (CFG_TUSB_RHPORT0_MODE & (OPT_MODE_DEVICE << 8)) ) + +#ifndef CFG_TUSB_RHPORT1_MODE + #define CFG_TUSB_RHPORT1_MODE OPT_MODE_NONE +#endif + +#if ((CFG_TUSB_RHPORT0_MODE & OPT_MODE_HOST ) && (CFG_TUSB_RHPORT1_MODE & OPT_MODE_HOST )) || \ + ((CFG_TUSB_RHPORT0_MODE & OPT_MODE_DEVICE) && (CFG_TUSB_RHPORT1_MODE & OPT_MODE_DEVICE)) #error "TinyUSB currently does not support same modes on more than 1 roothub port" #endif // Which roothub port is configured as host -#define TUH_OPT_RHPORT ( (CFG_TUSB_RHPORT0_MODE & OPT_MODE_HOST) ? 0 : ((CFG_TUSB_RHPORT0_MODE & (OPT_MODE_HOST << 8)) ? 1 : -1) ) +#define TUH_OPT_RHPORT ( (CFG_TUSB_RHPORT0_MODE & OPT_MODE_HOST) ? 0 : ((CFG_TUSB_RHPORT1_MODE & OPT_MODE_HOST) ? 1 : -1) ) #define TUSB_OPT_HOST_ENABLED ( TUH_OPT_RHPORT >= 0 ) // Which roothub port is configured as device -#define TUD_OPT_RHPORT ( (CFG_TUSB_RHPORT0_MODE & OPT_MODE_DEVICE) ? 0 : ((CFG_TUSB_RHPORT0_MODE & (OPT_MODE_DEVICE << 8)) ? 1 : -1) ) +#define TUD_OPT_RHPORT ( (CFG_TUSB_RHPORT0_MODE & OPT_MODE_DEVICE) ? 0 : ((CFG_TUSB_RHPORT1_MODE & OPT_MODE_DEVICE) ? 1 : -1) ) #if TUD_OPT_RHPORT == 0 - #define TUD_OPT_HIGH_SPEED ( CFG_TUSB_RHPORT0_MODE & OPT_MODE_HIGH_SPEED ) +#define TUD_OPT_HIGH_SPEED ( CFG_TUSB_RHPORT0_MODE & OPT_MODE_HIGH_SPEED ) #else - #define TUD_OPT_HIGH_SPEED ( CFG_TUSB_RHPORT0_MODE & (OPT_MODE_HIGH_SPEED << 8) ) +#define TUD_OPT_HIGH_SPEED ( CFG_TUSB_RHPORT1_MODE & OPT_MODE_HIGH_SPEED ) #endif #define TUSB_OPT_DEVICE_ENABLED ( TUD_OPT_RHPORT >= 0 ) - //--------------------------------------------------------------------+ // COMMON OPTIONS //--------------------------------------------------------------------+ From 95966c22010bf01579f39847624395724298c459 Mon Sep 17 00:00:00 2001 From: hathach Date: Sun, 14 Jun 2020 18:29:02 +0700 Subject: [PATCH 15/48] improve usbd log for control transfer --- src/device/usbd.c | 12 ++++++++++-- 1 file changed, 10 insertions(+), 2 deletions(-) diff --git a/src/device/usbd.c b/src/device/usbd.c index eeb5011ec..c337f1be1 100644 --- a/src/device/usbd.c +++ b/src/device/usbd.c @@ -380,17 +380,21 @@ void tud_task (void) if ( !osal_queue_receive(_usbd_q, &event) ) return; - TU_LOG2("USBD %s", event.event_id < DCD_EVENT_COUNT ? _usbd_event_str[event.event_id] : "CORRUPTED"); - TU_LOG2("%s", (event.event_id != DCD_EVENT_XFER_COMPLETE && event.event_id != DCD_EVENT_SETUP_RECEIVED) ? "\r\n" : " "); +#if CFG_TUSB_DEBUG >= 2 + if (event.event_id == DCD_EVENT_SETUP_RECEIVED) TU_LOG2("\r\n"); // extra line for setup + TU_LOG2("USBD %s ", event.event_id < DCD_EVENT_COUNT ? _usbd_event_str[event.event_id] : "CORRUPTED"); +#endif switch ( event.event_id ) { case DCD_EVENT_BUS_RESET: + TU_LOG2("\r\n"); usbd_reset(event.rhport); _usbd_dev.speed = event.bus_reset.speed; break; case DCD_EVENT_UNPLUGGED: + TU_LOG2("\r\n"); usbd_reset(event.rhport); // invoke callback @@ -442,14 +446,17 @@ void tud_task (void) break; case DCD_EVENT_SUSPEND: + TU_LOG2("\r\n"); if (tud_suspend_cb) tud_suspend_cb(_usbd_dev.remote_wakeup_en); break; case DCD_EVENT_RESUME: + TU_LOG2("\r\n"); if (tud_resume_cb) tud_resume_cb(); break; case DCD_EVENT_SOF: + TU_LOG2("\r\n"); for ( uint8_t i = 0; i < USBD_CLASS_DRIVER_COUNT; i++ ) { if ( _usbd_driver[i].sof ) @@ -460,6 +467,7 @@ void tud_task (void) break; case USBD_EVENT_FUNC_CALL: + TU_LOG2("\r\n"); if ( event.func_call.func ) event.func_call.func(event.func_call.param); break; From f438aedccba2b48d4ea9e606c3529c9fd6cb6985 Mon Sep 17 00:00:00 2001 From: hathach Date: Sun, 14 Jun 2020 18:29:38 +0700 Subject: [PATCH 16/48] overwrite setup packet --- src/portable/st/synopsys/dcd_synopsys.c | 14 ++++---------- 1 file changed, 4 insertions(+), 10 deletions(-) diff --git a/src/portable/st/synopsys/dcd_synopsys.c b/src/portable/st/synopsys/dcd_synopsys.c index 739361da9..39d8fe73d 100644 --- a/src/portable/st/synopsys/dcd_synopsys.c +++ b/src/portable/st/synopsys/dcd_synopsys.c @@ -125,8 +125,7 @@ enum // We disable SOF for now until needed later on #define USE_SOF 0 -static TU_ATTR_ALIGNED(4) uint32_t _setup_packet[6]; -static uint8_t _setup_offs; // We store up to 3 setup packets. +static TU_ATTR_ALIGNED(4) uint32_t _setup_packet[2]; typedef struct { uint8_t * buffer; @@ -670,17 +669,14 @@ static void read_rx_fifo(uint8_t rhport, USB_OTG_OUTEndpointTypeDef * out_ep) case 0x03: // Out packet done (Interrupt) break; case 0x04: // Setup packet done (Interrupt) - _setup_offs = 2 - ((out_ep[epnum].DOEPTSIZ & USB_OTG_DOEPTSIZ_STUPCNT_Msk) >> USB_OTG_DOEPTSIZ_STUPCNT_Pos); out_ep[epnum].DOEPTSIZ |= (3 << USB_OTG_DOEPTSIZ_STUPCNT_Pos); break; case 0x06: // Setup packet recvd { - uint8_t setup_left = ((out_ep[epnum].DOEPTSIZ & USB_OTG_DOEPTSIZ_STUPCNT_Msk) >> USB_OTG_DOEPTSIZ_STUPCNT_Pos); - // We can receive up to three setup packets in succession, but // only the last one is valid. - _setup_packet[4 - 2*setup_left] = (* rx_fifo); - _setup_packet[5 - 2*setup_left] = (* rx_fifo); + _setup_packet[0] = (* rx_fifo); + _setup_packet[1] = (* rx_fifo); } break; default: // Invalid @@ -699,8 +695,7 @@ static void handle_epout_ints(uint8_t rhport, USB_OTG_DeviceTypeDef * dev, USB_O // SETUP packet Setup Phase done. if(out_ep[n].DOEPINT & USB_OTG_DOEPINT_STUP) { out_ep[n].DOEPINT = USB_OTG_DOEPINT_STUP; - dcd_event_setup_received(rhport, (uint8_t*) &_setup_packet[2*_setup_offs], true); - _setup_offs = 0; + dcd_event_setup_received(rhport, (uint8_t*) &_setup_packet[0], true); } // OUT XFER complete (single packet). @@ -736,7 +731,6 @@ static void handle_epin_ints(uint8_t rhport, USB_OTG_DeviceTypeDef * dev, USB_OT if ( dev->DAINT & (1 << (USB_OTG_DAINT_IEPINT_Pos + n)) ) { - // IN XFER complete (entire xfer). if ( in_ep[n].DIEPINT & USB_OTG_DIEPINT_XFRC ) { From 4399dd1b068ae5ffff4b78848d69a41aa1915045 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Jan=20D=C3=BCmpelmann?= Date: Fri, 15 May 2020 18:21:44 +0200 Subject: [PATCH 17/48] cherry pick PR399 commit : Interrupt time improvements --- src/portable/st/synopsys/dcd_synopsys.c | 135 +++++++++--------------- 1 file changed, 47 insertions(+), 88 deletions(-) diff --git a/src/portable/st/synopsys/dcd_synopsys.c b/src/portable/st/synopsys/dcd_synopsys.c index 39d8fe73d..24cfadfe4 100644 --- a/src/portable/st/synopsys/dcd_synopsys.c +++ b/src/portable/st/synopsys/dcd_synopsys.c @@ -130,9 +130,7 @@ static TU_ATTR_ALIGNED(4) uint32_t _setup_packet[2]; typedef struct { uint8_t * buffer; uint16_t total_len; - uint16_t queued_len; uint16_t max_size; - bool short_packet; } xfer_ctl_t; typedef volatile uint32_t * usb_fifo_t; @@ -437,8 +435,6 @@ bool dcd_edpt_xfer (uint8_t rhport, uint8_t ep_addr, uint8_t * buffer, uint16_t xfer_ctl_t * xfer = XFER_CTL_BASE(epnum, dir); xfer->buffer = buffer; xfer->total_len = total_bytes; - xfer->queued_len = 0; - xfer->short_packet = false; uint16_t num_packets = (total_bytes / xfer->max_size); uint8_t short_packet_size = total_bytes % xfer->max_size; @@ -461,9 +457,10 @@ bool dcd_edpt_xfer (uint8_t rhport, uint8_t ep_addr, uint8_t * buffer, uint16_t dev->DIEPEMPMSK |= (1 << epnum); } } else { - // Each complete packet for OUT xfers triggers XFRC. - out_ep[epnum].DOEPTSIZ |= (1 << USB_OTG_DOEPTSIZ_PKTCNT_Pos) | - ((xfer->max_size & USB_OTG_DOEPTSIZ_XFRSIZ_Msk) << USB_OTG_DOEPTSIZ_XFRSIZ_Pos); + // A full OUT transfer (multiple packets, possibly) triggers XFRC. + out_ep[epnum].DOEPTSIZ &= ~(USB_OTG_DOEPTSIZ_PKTCNT_Msk | USB_OTG_DOEPTSIZ_XFRSIZ); + out_ep[epnum].DOEPTSIZ |= (num_packets << USB_OTG_DOEPTSIZ_PKTCNT_Pos) | + ((total_bytes << USB_OTG_DOEPTSIZ_XFRSIZ_Pos) & USB_OTG_DOEPTSIZ_XFRSIZ_Msk); out_ep[epnum].DOEPCTL |= USB_OTG_DOEPCTL_EPENA | USB_OTG_DOEPCTL_CNAK; } @@ -558,65 +555,33 @@ void dcd_edpt_clear_stall (uint8_t rhport, uint8_t ep_addr) /*------------------------------------------------------------------*/ -// TODO: Split into "receive on endpoint 0" and "receive generic"; endpoint 0's -// DOEPTSIZ register is smaller than the others, and so is insufficient for -// determining how much of an OUT transfer is actually remaining. -static void receive_packet(uint8_t rhport, xfer_ctl_t * xfer, /* USB_OTG_OUTEndpointTypeDef * out_ep, */ uint16_t xfer_size) { +// Read a single data packet from receive FIFO +static void read_fifo_packet(uint8_t rhport, uint8_t * dst, uint16_t len){ usb_fifo_t rx_fifo = FIFO_BASE(rhport, 0); - // See above TODO - // uint16_t remaining = (out_ep->DOEPTSIZ & USB_OTG_DOEPTSIZ_XFRSIZ_Msk) >> USB_OTG_DOEPTSIZ_XFRSIZ_Pos; - // xfer->queued_len = xfer->total_len - remaining; - - uint16_t remaining = xfer->total_len - xfer->queued_len; - uint16_t to_recv_size; - - if(remaining <= xfer->max_size) { - // Avoid buffer overflow. - to_recv_size = (xfer_size > remaining) ? remaining : xfer_size; - } else { - // Room for full packet, choose recv_size based on what the microcontroller - // claims. - to_recv_size = (xfer_size > xfer->max_size) ? xfer->max_size : xfer_size; + // Reading full available 32 bit words from fifo + uint16_t full_words = len >> 2; + for(uint16_t i = 0; i < full_words; i++) { + uint32_t tmp = *rx_fifo; + dst[0] = tmp & 0x000000FF; + dst[1] = (tmp & 0x0000FF00) >> 8; + dst[2] = (tmp & 0x00FF0000) >> 16; + dst[3] = (tmp & 0xFF000000) >> 24; + dst += 4; } - uint8_t to_recv_rem = to_recv_size % 4; - uint16_t to_recv_size_aligned = to_recv_size - to_recv_rem; - - // Do not assume xfer buffer is aligned. - uint8_t * base = (xfer->buffer + xfer->queued_len); - - // This for loop always runs at least once- skip if less than 4 bytes - // to collect. - if(to_recv_size >= 4) { - for(uint16_t i = 0; i < to_recv_size_aligned; i += 4) { - uint32_t tmp = (* rx_fifo); - base[i] = tmp & 0x000000FF; - base[i + 1] = (tmp & 0x0000FF00) >> 8; - base[i + 2] = (tmp & 0x00FF0000) >> 16; - base[i + 3] = (tmp & 0xFF000000) >> 24; + // Read the remaining 1-3 bytes from fifo + uint8_t bytes_rem = len & 0x03; + if(bytes_rem != 0) { + uint32_t tmp = *rx_fifo; + dst[0] = tmp & 0x000000FF; + if(bytes_rem > 1) { + dst[1] = (tmp & 0x0000FF00) >> 8; + } + if(bytes_rem > 2) { + dst[2] = (tmp & 0x00FF0000) >> 16; } } - - // Do not read invalid bytes from RX FIFO. - if(to_recv_rem != 0) { - uint32_t tmp = (* rx_fifo); - uint8_t * last_32b_bound = base + to_recv_size_aligned; - - last_32b_bound[0] = tmp & 0x000000FF; - if(to_recv_rem > 1) { - last_32b_bound[1] = (tmp & 0x0000FF00) >> 8; - } - if(to_recv_rem > 2) { - last_32b_bound[2] = (tmp & 0x00FF0000) >> 16; - } - } - - xfer->queued_len += xfer_size; - - // Per USB spec, a short OUT packet (including length 0) is always - // indicative of the end of a transfer (at least for ctl, bulk, int). - xfer->short_packet = (xfer_size < xfer->max_size); } // Write a single data packet to EPIN FIFO @@ -645,13 +610,11 @@ static void write_fifo_packet(uint8_t rhport, uint8_t fifo_num, uint8_t * src, u } } -static void read_rx_fifo(uint8_t rhport, USB_OTG_OUTEndpointTypeDef * out_ep) -{ +static void handle_rxflvl_ints(uint8_t rhport, USB_OTG_OUTEndpointTypeDef * out_ep) { USB_OTG_GlobalTypeDef * usb_otg = GLOBAL_BASE(rhport); usb_fifo_t rx_fifo = FIFO_BASE(rhport, 0); - // Pop control word off FIFO (completed xfers will have 2 control words, - // we only pop one ctl word each interrupt). + // Pop control word off FIFO uint32_t ctl_word = usb_otg->GRXSTSP; uint8_t pktsts = (ctl_word & USB_OTG_GRXSTSP_PKTSTS_Msk) >> USB_OTG_GRXSTSP_PKTSTS_Pos; uint8_t epnum = (ctl_word & USB_OTG_GRXSTSP_EPNUM_Msk) >> USB_OTG_GRXSTSP_EPNUM_Pos; @@ -663,7 +626,13 @@ static void read_rx_fifo(uint8_t rhport, USB_OTG_OUTEndpointTypeDef * out_ep) case 0x02: // Out packet recvd { xfer_ctl_t * xfer = XFER_CTL_BASE(epnum, TUSB_DIR_OUT); - receive_packet(rhport, xfer, bcnt); + + // Use BCNT to calculate correct bytes before data entry popped out from RxFIFO + uint16_t remaining_bytes = ((out_ep[epnum].DOEPTSIZ & USB_OTG_DOEPTSIZ_XFRSIZ_Msk) \ + >> USB_OTG_DOEPTSIZ_XFRSIZ_Pos) + bcnt; + + // Read packet off RxFIFO + read_fifo_packet(rhport, (xfer->buffer + xfer->total_len - remaining_bytes), bcnt); } break; case 0x03: // Out packet done (Interrupt) @@ -698,25 +667,10 @@ static void handle_epout_ints(uint8_t rhport, USB_OTG_DeviceTypeDef * dev, USB_O dcd_event_setup_received(rhport, (uint8_t*) &_setup_packet[0], true); } - // OUT XFER complete (single packet). + // OUT XFER complete if(out_ep[n].DOEPINT & USB_OTG_DOEPINT_XFRC) { out_ep[n].DOEPINT = USB_OTG_DOEPINT_XFRC; - - // TODO: Because of endpoint 0's constrained size, we handle XFRC - // on a packet-basis. The core can internally handle multiple OUT - // packets; it would be more efficient to only trigger XFRC on a - // completed transfer for non-0 endpoints. - - // Transfer complete if short packet or total len is transferred - if(xfer->short_packet || (xfer->queued_len == xfer->total_len)) { - xfer->short_packet = false; - dcd_event_xfer_complete(rhport, n, xfer->queued_len, XFER_RESULT_SUCCESS, true); - } else { - // Schedule another packet to be received. - out_ep[n].DOEPTSIZ |= (1 << USB_OTG_DOEPTSIZ_PKTCNT_Pos) | \ - ((xfer->max_size & USB_OTG_DOEPTSIZ_XFRSIZ_Msk) << USB_OTG_DOEPTSIZ_XFRSIZ_Pos); - out_ep[n].DOEPCTL |= USB_OTG_DOEPCTL_EPENA | USB_OTG_DOEPCTL_CNAK; - } + dcd_event_xfer_complete(rhport, n, xfer->total_len, XFER_RESULT_SUCCESS, true); } } } @@ -760,11 +714,8 @@ static void handle_epin_ints(uint8_t rhport, USB_OTG_DeviceTypeDef * dev, USB_OT break; } - // TODO: queued_len can be removed later - xfer->queued_len = xfer->total_len - remaining_bytes; - // Push packet to Tx-FIFO - write_fifo_packet(rhport, n, (xfer->buffer + xfer->queued_len), packet_size); + write_fifo_packet(rhport, n, (xfer->buffer + xfer->total_len - remaining_bytes), packet_size); } // Turn off TXFE if all bytes are written. @@ -835,12 +786,20 @@ void dcd_int_handler(uint8_t rhport) } #endif - if(int_status & USB_OTG_GINTSTS_RXFLVL) { + // Use while loop to handle more than one fifo data entry + // within a single interrupt call + while(usb_otg->GINTSTS & USB_OTG_GINTSTS_RXFLVL) { // RXFLVL bit is read-only // Mask out RXFLVL while reading data from FIFO usb_otg->GINTMSK &= ~USB_OTG_GINTMSK_RXFLVLM; - read_rx_fifo(rhport, out_ep); + + // Loop until all available packets were handled + do { + handle_rxflvl_ints(rhport, out_ep); + int_status = usb_otg->GINTSTS; + } while(int_status & USB_OTG_GINTSTS_RXFLVL); + usb_otg->GINTMSK |= USB_OTG_GINTMSK_RXFLVLM; } From 0bfa839ac0414632eb284779361ed6a34a98c672 Mon Sep 17 00:00:00 2001 From: hathach Date: Mon, 15 Jun 2020 23:06:17 +0700 Subject: [PATCH 18/48] clean up, update other example config --- .../device/cdc_dual_ports/src/tusb_config.h | 31 +++++++++++++---- examples/device/cdc_msc/src/tusb_config.h | 1 + .../device/cdc_msc_freertos/src/tusb_config.h | 33 +++++++++++++++---- hw/bsp/stm32h743eval/stm32h743eval.c | 10 +++--- 4 files changed, 57 insertions(+), 18 deletions(-) diff --git a/examples/device/cdc_dual_ports/src/tusb_config.h b/examples/device/cdc_dual_ports/src/tusb_config.h index 3536702bb..e3368e72f 100644 --- a/examples/device/cdc_dual_ports/src/tusb_config.h +++ b/examples/device/cdc_dual_ports/src/tusb_config.h @@ -34,18 +34,37 @@ // COMMON CONFIGURATION //-------------------------------------------------------------------- -// defined by compiler flags for flexibility +// defined by board.mk #ifndef CFG_TUSB_MCU #error CFG_TUSB_MCU must be defined #endif -#if CFG_TUSB_MCU == OPT_MCU_LPC18XX || CFG_TUSB_MCU == OPT_MCU_LPC43XX || CFG_TUSB_MCU == OPT_MCU_MIMXRT10XX || \ - CFG_TUSB_MCU == OPT_MCU_NUC505 || CFG_TUSB_MCU == OPT_MCU_CXD56 - #define CFG_TUSB_RHPORT0_MODE (OPT_MODE_DEVICE | OPT_MODE_HIGH_SPEED) -#else - #define CFG_TUSB_RHPORT0_MODE OPT_MODE_DEVICE +// RHPort number used for device can be defined by board.mk, default to port 0 +#ifndef BOARD_DEVICE_RHPORT_NUM + #define BOARD_DEVICE_RHPORT_NUM 0 #endif +// RHPort max operational speed can defined by board.mk +// Default to Highspeed for MCU with internal HighSpeed PHY (can be port specific), otherwise FullSpeed +#ifndef BOARD_DEVICE_RHPORT_SPEED + #if (CFG_TUSB_MCU == OPT_MCU_LPC18XX || CFG_TUSB_MCU == OPT_MCU_LPC43XX || CFG_TUSB_MCU == OPT_MCU_MIMXRT10XX || \ + CFG_TUSB_MCU == OPT_MCU_NUC505 || CFG_TUSB_MCU == OPT_MCU_CXD56) + #define BOARD_DEVICE_RHPORT_SPEED OPT_MODE_HIGH_SPEED + #else + #define BOARD_DEVICE_RHPORT_SPEED OPT_MODE_FULL_SPEED + #endif +#endif + +// Device mode with rhport and speed defined by board.mk +#if BOARD_DEVICE_RHPORT_NUM == 0 + #define CFG_TUSB_RHPORT0_MODE (OPT_MODE_DEVICE | BOARD_DEVICE_RHPORT_SPEED) +#elif BOARD_DEVICE_RHPORT_NUM == 1 + #define CFG_TUSB_RHPORT1_MODE (OPT_MODE_DEVICE | BOARD_DEVICE_RHPORT_SPEED) +#else + #error "Incorrect RHPort configuration" +#endif + +// This example doesn't use an RTOS #define CFG_TUSB_OS OPT_OS_NONE // CFG_TUSB_DEBUG is defined by compiler in DEBUG build diff --git a/examples/device/cdc_msc/src/tusb_config.h b/examples/device/cdc_msc/src/tusb_config.h index b05d219c6..c57c2ead8 100644 --- a/examples/device/cdc_msc/src/tusb_config.h +++ b/examples/device/cdc_msc/src/tusb_config.h @@ -64,6 +64,7 @@ #error "Incorrect RHPort configuration" #endif +// This example doesn't use an RTOS #define CFG_TUSB_OS OPT_OS_NONE // CFG_TUSB_DEBUG is defined by compiler in DEBUG build diff --git a/examples/device/cdc_msc_freertos/src/tusb_config.h b/examples/device/cdc_msc_freertos/src/tusb_config.h index 794e996b6..379fab971 100644 --- a/examples/device/cdc_msc_freertos/src/tusb_config.h +++ b/examples/device/cdc_msc_freertos/src/tusb_config.h @@ -34,19 +34,38 @@ // COMMON CONFIGURATION //-------------------------------------------------------------------- -// defined by compiler flags for flexibility +// defined by board.mk #ifndef CFG_TUSB_MCU #error CFG_TUSB_MCU must be defined #endif -#if CFG_TUSB_MCU == OPT_MCU_LPC18XX || CFG_TUSB_MCU == OPT_MCU_LPC43XX || CFG_TUSB_MCU == OPT_MCU_MIMXRT10XX || \ - CFG_TUSB_MCU == OPT_MCU_NUC505 || CFG_TUSB_MCU == OPT_MCU_CXD56 - #define CFG_TUSB_RHPORT0_MODE (OPT_MODE_DEVICE | OPT_MODE_HIGH_SPEED) -#else - #define CFG_TUSB_RHPORT0_MODE OPT_MODE_DEVICE +// RHPort number used for device can be defined by board.mk, default to port 0 +#ifndef BOARD_DEVICE_RHPORT_NUM + #define BOARD_DEVICE_RHPORT_NUM 0 #endif -#define CFG_TUSB_OS OPT_OS_FREERTOS +// RHPort max operational speed can defined by board.mk +// Default to Highspeed for MCU with internal HighSpeed PHY (can be port specific), otherwise FullSpeed +#ifndef BOARD_DEVICE_RHPORT_SPEED + #if (CFG_TUSB_MCU == OPT_MCU_LPC18XX || CFG_TUSB_MCU == OPT_MCU_LPC43XX || CFG_TUSB_MCU == OPT_MCU_MIMXRT10XX || \ + CFG_TUSB_MCU == OPT_MCU_NUC505 || CFG_TUSB_MCU == OPT_MCU_CXD56) + #define BOARD_DEVICE_RHPORT_SPEED OPT_MODE_HIGH_SPEED + #else + #define BOARD_DEVICE_RHPORT_SPEED OPT_MODE_FULL_SPEED + #endif +#endif + +// Device mode with rhport and speed defined by board.mk +#if BOARD_DEVICE_RHPORT_NUM == 0 + #define CFG_TUSB_RHPORT0_MODE (OPT_MODE_DEVICE | BOARD_DEVICE_RHPORT_SPEED) +#elif BOARD_DEVICE_RHPORT_NUM == 1 + #define CFG_TUSB_RHPORT1_MODE (OPT_MODE_DEVICE | BOARD_DEVICE_RHPORT_SPEED) +#else + #error "Incorrect RHPort configuration" +#endif + +// This examples use FreeRTOS +#define CFG_TUSB_OS OPT_OS_FREERTOS // CFG_TUSB_DEBUG is defined by compiler in DEBUG build // #define CFG_TUSB_DEBUG 0 diff --git a/hw/bsp/stm32h743eval/stm32h743eval.c b/hw/bsp/stm32h743eval/stm32h743eval.c index a28110920..8bafc32cb 100644 --- a/hw/bsp/stm32h743eval/stm32h743eval.c +++ b/hw/bsp/stm32h743eval/stm32h743eval.c @@ -326,14 +326,14 @@ void board_init(void) // No VBUS sense USB_OTG_HS->GCCFG &= ~USB_OTG_GCCFG_VBDEN; + // B-peripheral session valid override enable + USB_OTG_HS->GOTGCTL |= USB_OTG_GOTGCTL_BVALOEN; + USB_OTG_HS->GOTGCTL |= USB_OTG_GOTGCTL_BVALOVAL; + // Force device mode USB_OTG_HS->GUSBCFG &= ~USB_OTG_GUSBCFG_FHMOD; USB_OTG_HS->GUSBCFG |= USB_OTG_GUSBCFG_FDMOD; - // B-peripheral session valid override enabl - USB_OTG_HS->GOTGCTL |= USB_OTG_GOTGCTL_BVALOEN; - USB_OTG_HS->GOTGCTL |= USB_OTG_GOTGCTL_BVALOVAL; - HAL_PWREx_EnableUSBVoltageDetector(); #endif // rhport = 1 @@ -367,7 +367,7 @@ int board_uart_write(void const * buf, int len) } -#if CFG_TUSB_OS == OPT_OS_NONE +#if CFG_TUSB_OS == OPT_OS_NONE volatile uint32_t system_ticks = 0; void SysTick_Handler (void) { From e89fea8237cb6f9d408ccc58710085b2d6790106 Mon Sep 17 00:00:00 2001 From: hathach Date: Mon, 15 Jun 2020 23:09:43 +0700 Subject: [PATCH 19/48] update midi --- examples/device/midi_test/src/tusb_config.h | 33 ++++++++++++++++----- 1 file changed, 26 insertions(+), 7 deletions(-) diff --git a/examples/device/midi_test/src/tusb_config.h b/examples/device/midi_test/src/tusb_config.h index 8dd7ef9fe..fd109ad32 100644 --- a/examples/device/midi_test/src/tusb_config.h +++ b/examples/device/midi_test/src/tusb_config.h @@ -34,19 +34,38 @@ // COMMON CONFIGURATION //-------------------------------------------------------------------- -// defined by compiler flags for flexibility +// defined by board.mk #ifndef CFG_TUSB_MCU #error CFG_TUSB_MCU must be defined #endif -#if CFG_TUSB_MCU == OPT_MCU_LPC18XX || CFG_TUSB_MCU == OPT_MCU_LPC43XX || CFG_TUSB_MCU == OPT_MCU_MIMXRT10XX || \ - CFG_TUSB_MCU == OPT_MCU_NUC505 || CFG_TUSB_MCU == OPT_MCU_CXD56 - #define CFG_TUSB_RHPORT0_MODE (OPT_MODE_DEVICE | OPT_MODE_HIGH_SPEED) -#else - #define CFG_TUSB_RHPORT0_MODE OPT_MODE_DEVICE +// RHPort number used for device can be defined by board.mk, default to port 0 +#ifndef BOARD_DEVICE_RHPORT_NUM + #define BOARD_DEVICE_RHPORT_NUM 0 #endif -#define CFG_TUSB_OS OPT_OS_NONE +// RHPort max operational speed can defined by board.mk +// Default to Highspeed for MCU with internal HighSpeed PHY (can be port specific), otherwise FullSpeed +#ifndef BOARD_DEVICE_RHPORT_SPEED + #if (CFG_TUSB_MCU == OPT_MCU_LPC18XX || CFG_TUSB_MCU == OPT_MCU_LPC43XX || CFG_TUSB_MCU == OPT_MCU_MIMXRT10XX || \ + CFG_TUSB_MCU == OPT_MCU_NUC505 || CFG_TUSB_MCU == OPT_MCU_CXD56) + #define BOARD_DEVICE_RHPORT_SPEED OPT_MODE_HIGH_SPEED + #else + #define BOARD_DEVICE_RHPORT_SPEED OPT_MODE_FULL_SPEED + #endif +#endif + +// Device mode with rhport and speed defined by board.mk +#if BOARD_DEVICE_RHPORT_NUM == 0 + #define CFG_TUSB_RHPORT0_MODE (OPT_MODE_DEVICE | BOARD_DEVICE_RHPORT_SPEED) +#elif BOARD_DEVICE_RHPORT_NUM == 1 + #define CFG_TUSB_RHPORT1_MODE (OPT_MODE_DEVICE | BOARD_DEVICE_RHPORT_SPEED) +#else + #error "Incorrect RHPort configuration" +#endif + +// This example doesn't use an RTOS +#define CFG_TUSB_OS OPT_OS_NONE // CFG_TUSB_DEBUG is defined by compiler in DEBUG build // #define CFG_TUSB_DEBUG 0 From 2dd1be13e5780509cc6ab4e5877dd8c4ffe77e45 Mon Sep 17 00:00:00 2001 From: hathach Date: Mon, 15 Jun 2020 23:17:49 +0700 Subject: [PATCH 20/48] Enhance EP FIFO allocation for both Fullspeed and Highspeed - Update shared RX FIFO calculation with FS/HS - IN FIFO EP - Interrupt -> use EPSize - Bulk/ISO -> use max(EPSize, remaining-fifo / non-opened-EPIN) --- src/portable/st/synopsys/dcd_synopsys.c | 113 ++++++++++++++++-------- 1 file changed, 76 insertions(+), 37 deletions(-) diff --git a/src/portable/st/synopsys/dcd_synopsys.c b/src/portable/st/synopsys/dcd_synopsys.c index 24cfadfe4..030c089aa 100644 --- a/src/portable/st/synopsys/dcd_synopsys.c +++ b/src/portable/st/synopsys/dcd_synopsys.c @@ -116,7 +116,6 @@ enum DCD_FULL_SPEED = 3, // Full speed with internal PHY }; - /*------------------------------------------------------------------*/ /* MACRO TYPEDEF CONSTANT ENUM *------------------------------------------------------------------*/ @@ -138,6 +137,8 @@ typedef volatile uint32_t * usb_fifo_t; xfer_ctl_t xfer_status[EP_MAX][2]; #define XFER_CTL_BASE(_ep, _dir) &xfer_status[_ep][_dir] +// FIFO RAM allocation so far in words +static uint16_t _allocated_fifo_words; // Setup the control endpoint 0. static void bus_reset(uint8_t rhport) @@ -147,6 +148,8 @@ static void bus_reset(uint8_t rhport) USB_OTG_OUTEndpointTypeDef * out_ep = OUT_EP_BASE(rhport); USB_OTG_INEndpointTypeDef * in_ep = IN_EP_BASE(rhport); + tu_memclr(xfer_status, sizeof(xfer_status)); + for(uint8_t n = 0; n < EP_MAX; n++) { out_ep[n].DOEPCTL |= USB_OTG_DOEPCTL_SNAK; } @@ -177,17 +180,36 @@ static void bus_reset(uint8_t rhport) // - Each EP IN needs at least max packet size, 16 words is sufficient for EP0 IN // // - All EP OUT shared a unique OUT FIFO which uses - // * 10 locations in hardware for setup packets + setup control words (up to 3 setup packets). - // * 2 locations for OUT endpoint control words. - // * 16 for largest packet size of 64 bytes. ( TODO Highspeed is 512 bytes) - // * 1 location for global NAK (not required/used here). - // * It is recommended to allocate 2 times the largest packet size, therefore - // Recommended value = 10 + 1 + 2 x (16+2) = 47. To make it scale better with large FIFO size - // and work better with Highspeed. We use 1/5 of total FIFO size - usb_otg->GRXFSIZ = (EP_FIFO_SIZE/4)/5; + // - 13 for setup packets + control words (up to 3 setup packets). + // - 1 for global NAK (not required/used here). + // - Largest-EPsize / 4 + 1. ( FS: 64 bytes, HS: 512 bytes). Recommended is "2 x (Largest-EPsize/4) + 1" + // - 2 for each used OUT endpoint + // + // Therefore GRXFSIZ = 13 + 1 + 1 + 2 x (Largest-EPsize/4) + 2 x EPOUTnum + // - FullSpeed (64 Bytes ): GRXFSIZ = 15 + 2 x 16 + 2 x EP_MAX = 47 + 2 x EP_MAX + // - Highspeed (512 bytes): GRXFSIZ = 15 + 2 x 128 + 2 x EP_MAX = 271 + 2 x EP_MAX + // + // NOTE: Largest-EPsize & EPOUTnum is actual used endpoints in configuration. Since DCD has no knowledge + // of the overall picture yet. We will use the worst scenario: largest possible + EP_MAX + // + // FIXME: for Isochronous, largest EP size can be 1023/1024 for FS/HS respectively. In addition if multiple ISO + // are enabled at least "2 x (Largest-EPsize/4) + 1" are recommended. Maybe provide a macro for application to + // overwrite this. + +#if TUD_OPT_HIGH_SPEED + _allocated_fifo_words = 271 + 2*EP_MAX; +#else + _allocated_fifo_words = 47 + 2*EP_MAX; +#endif + + usb_otg->GRXFSIZ = _allocated_fifo_words; // Control IN uses FIFO 0 with 64 bytes ( 16 32-bit word ) - usb_otg->DIEPTXF0_HNPTXFSIZ = (16 << USB_OTG_TX0FD_Pos) | (usb_otg->GRXFSIZ & 0x0000ffffUL); + usb_otg->DIEPTXF0_HNPTXFSIZ = (16 << USB_OTG_TX0FD_Pos) | _allocated_fifo_words; + + _allocated_fifo_words += 16; + + // TU_LOG2_INT(_allocated_fifo_words); // Fixed control EP0 size to 64 bytes in_ep[0].DIEPCTL &= ~(0x03 << USB_OTG_DIEPCTL_MPSIZ_Pos); @@ -221,7 +243,6 @@ static tusb_speed_t get_speed(USB_OTG_DeviceTypeDef* dev) return (enum_spd == DCD_HIGH_SPEED) ? TUSB_SPEED_HIGH : TUSB_SPEED_FULL; } - /*------------------------------------------------------------------*/ /* Controller API *------------------------------------------------------------------*/ @@ -242,9 +263,11 @@ void dcd_init (uint8_t rhport) usb_otg->GCCFG &= ~USB_OTG_GCCFG_PWRDWN; // On selected MCUs HS port1 can be used with external PHY via ULPI interface - // Select ULPI highspeed PHY with default external VBUS Indicator and Drive - usb_otg->GUSBCFG &= ~(USB_OTG_GUSBCFG_TSDPS | USB_OTG_GUSBCFG_ULPIFSLS | USB_OTG_GUSBCFG_PHYSEL | - USB_OTG_GUSBCFG_ULPIEVBUSD | USB_OTG_GUSBCFG_ULPIEVBUSI); + // Init ULPI Interface + usb_otg->GUSBCFG &= ~(USB_OTG_GUSBCFG_TSDPS | USB_OTG_GUSBCFG_ULPIFSLS | USB_OTG_GUSBCFG_PHYSEL); + + // Select default internal VBUS Indicator and Drive for ULPI + usb_otg->GUSBCFG &= ~(USB_OTG_GUSBCFG_ULPIEVBUSD | USB_OTG_GUSBCFG_ULPIEVBUSI); set_turnaround(usb_otg, TUSB_SPEED_HIGH); } @@ -303,7 +326,6 @@ void dcd_init (uint8_t rhport) USB_OTG_GINTMSK_USBSUSPM | USB_OTG_GINTMSK_WUIM | USB_OTG_GINTMSK_RXFLVLM | (USE_SOF ? USB_OTG_GINTMSK_SOFM : 0); - // Enable global interrupt usb_otg->GAHBCFG |= USB_OTG_GAHBCFG_GINT; } @@ -397,10 +419,40 @@ bool dcd_edpt_open (uint8_t rhport, tusb_desc_endpoint_t const * desc_edpt) // | ( Shared ) | // --------------- 0 // - // Since OUT FIFO = GRXFSIZ, FIFO 0 = 16, for simplicity, we equally allocated for the rest of endpoints - // - Size : (FIFO_SIZE/4 - GRXFSIZ - 16) / (EP_MAX-1) - // - Offset: GRXFSIZ + 16 + Size*(epnum-1) + // In FIFO is allocated by following rules: // - IN EP 1 gets FIFO 1, IN EP "n" gets FIFO "n". + // - Offset: allocated so far + // - Size + // - Interrupt is EPSize + // - Bulk/ISO is max(EPSize, remaining-fifo / non-opened-EPIN) + + uint16_t const fifo_remaining = EP_FIFO_SIZE/4 - _allocated_fifo_words; + uint16_t fifo_size = desc_edpt->wMaxPacketSize.size / 4; + + if ( desc_edpt->bmAttributes.xfer != TUSB_XFER_INTERRUPT ) + { + uint8_t opened = 0; + for(uint8_t i = 0; i < EP_MAX; i++) + { + if ( (i != epnum) && (xfer_status[i][TUSB_DIR_IN].max_size > 0) ) opened++; + } + + // EP Size or equally divided of remaining whichever is larger + fifo_size = tu_max16(fifo_size, fifo_remaining / (EP_MAX - opened)); + } + + + // FIFO overflows, we probably need a better allocating scheme + TU_ASSERT(fifo_size <= fifo_remaining); + + // DIEPTXF starts at FIFO #1. + // Both TXFD and TXSA are in unit of 32-bit words. + usb_otg->DIEPTXF[epnum - 1] = (fifo_size << USB_OTG_DIEPTXF_INEPTXFD_Pos) | _allocated_fifo_words; + + _allocated_fifo_words += fifo_size; + + //TU_LOG2_INT(fifo_size); + //TU_LOG2_INT(_allocated_fifo_words); in_ep[epnum].DIEPCTL |= (1 << USB_OTG_DIEPCTL_USBAEP_Pos) | (epnum << USB_OTG_DIEPCTL_TXFNUM_Pos) | @@ -409,15 +461,6 @@ bool dcd_edpt_open (uint8_t rhport, tusb_desc_endpoint_t const * desc_edpt) (desc_edpt->wMaxPacketSize.size << USB_OTG_DIEPCTL_MPSIZ_Pos); dev->DAINTMSK |= (1 << (USB_OTG_DAINTMSK_IEPM_Pos + epnum)); - - // Both TXFD and TXSA are in unit of 32-bit words. - // IN FIFO 0 was configured during enumeration, hence the "+ 16". - uint16_t const allocated_size = (usb_otg->GRXFSIZ & 0x0000ffff) + 16; - uint16_t const fifo_size = (EP_FIFO_SIZE/4 - allocated_size) / (EP_MAX-1); - uint32_t const fifo_offset = allocated_size + fifo_size*(epnum-1); - - // DIEPTXF starts at FIFO #1. - usb_otg->DIEPTXF[epnum - 1] = (fifo_size << USB_OTG_DIEPTXF_INEPTXFD_Pos) | fifo_offset; } return true; @@ -433,8 +476,8 @@ bool dcd_edpt_xfer (uint8_t rhport, uint8_t ep_addr, uint8_t * buffer, uint16_t uint8_t const dir = tu_edpt_dir(ep_addr); xfer_ctl_t * xfer = XFER_CTL_BASE(epnum, dir); - xfer->buffer = buffer; - xfer->total_len = total_bytes; + xfer->buffer = buffer; + xfer->total_len = total_bytes; uint16_t num_packets = (total_bytes / xfer->max_size); uint8_t short_packet_size = total_bytes % xfer->max_size; @@ -533,20 +576,16 @@ void dcd_edpt_clear_stall (uint8_t rhport, uint8_t ep_addr) if(dir == TUSB_DIR_IN) { in_ep[epnum].DIEPCTL &= ~USB_OTG_DIEPCTL_STALL; - uint8_t eptype = (in_ep[epnum].DIEPCTL & USB_OTG_DIEPCTL_EPTYP_Msk) >> \ - USB_OTG_DIEPCTL_EPTYP_Pos; - // Required by USB spec to reset DATA toggle bit to DATA0 on interrupt - // and bulk endpoints. + uint8_t eptype = (in_ep[epnum].DIEPCTL & USB_OTG_DIEPCTL_EPTYP_Msk) >> USB_OTG_DIEPCTL_EPTYP_Pos; + // Required by USB spec to reset DATA toggle bit to DATA0 on interrupt and bulk endpoints. if(eptype == 2 || eptype == 3) { in_ep[epnum].DIEPCTL |= USB_OTG_DIEPCTL_SD0PID_SEVNFRM; } } else { out_ep[epnum].DOEPCTL &= ~USB_OTG_DOEPCTL_STALL; - uint8_t eptype = (out_ep[epnum].DOEPCTL & USB_OTG_DOEPCTL_EPTYP_Msk) >> \ - USB_OTG_DOEPCTL_EPTYP_Pos; - // Required by USB spec to reset DATA toggle bit to DATA0 on interrupt - // and bulk endpoints. + uint8_t eptype = (out_ep[epnum].DOEPCTL & USB_OTG_DOEPCTL_EPTYP_Msk) >> USB_OTG_DOEPCTL_EPTYP_Pos; + // Required by USB spec to reset DATA toggle bit to DATA0 on interrupt and bulk endpoints. if(eptype == 2 || eptype == 3) { out_ep[epnum].DOEPCTL |= USB_OTG_DOEPCTL_SD0PID_SEVNFRM; } From c67b3a242e8873788e32bbb589836e265e8a9b53 Mon Sep 17 00:00:00 2001 From: hathach Date: Mon, 15 Jun 2020 23:34:09 +0700 Subject: [PATCH 21/48] update example config and descriptor with better Highspeed support --- .../cdc_msc_freertos/src/usb_descriptors.c | 2 +- examples/device/dfu_rt/src/tusb_config.h | 33 ++++++++++++++---- .../dynamic_configuration/src/tusb_config.h | 33 ++++++++++++++---- .../src/usb_descriptors.c | 4 +-- .../device/hid_composite/src/tusb_config.h | 33 ++++++++++++++---- .../hid_composite_freertos/src/tusb_config.h | 32 +++++++++++++---- .../hid_generic_inout/src/tusb_config.h | 33 ++++++++++++++---- .../device/midi_test/src/usb_descriptors.c | 2 +- .../device/msc_dual_lun/src/tusb_config.h | 33 ++++++++++++++---- .../device/msc_dual_lun/src/usb_descriptors.c | 2 +- .../net_lwip_webserver/src/tusb_config.h | 33 ++++++++++++++---- examples/device/usbtmc/src/tusb_config.h | 34 +++++++++++++++---- .../device/webusb_serial/src/tusb_config.h | 33 ++++++++++++++---- test/test/device/msc/test_msc_device.c | 2 +- 14 files changed, 241 insertions(+), 68 deletions(-) diff --git a/examples/device/cdc_msc_freertos/src/usb_descriptors.c b/examples/device/cdc_msc_freertos/src/usb_descriptors.c index 7b22d46a7..62ab4f10f 100644 --- a/examples/device/cdc_msc_freertos/src/usb_descriptors.c +++ b/examples/device/cdc_msc_freertos/src/usb_descriptors.c @@ -123,7 +123,7 @@ uint8_t const desc_configuration[] = TUD_CDC_DESCRIPTOR(ITF_NUM_CDC, 4, EPNUM_CDC_NOTIF, 8, EPNUM_CDC_OUT, EPNUM_CDC_IN, 64), // Interface number, string index, EP Out & EP In address, EP size - TUD_MSC_DESCRIPTOR(ITF_NUM_MSC, 5, EPNUM_MSC_OUT, EPNUM_MSC_IN, (CFG_TUSB_RHPORT0_MODE & OPT_MODE_HIGH_SPEED) ? 512 : 64), + TUD_MSC_DESCRIPTOR(ITF_NUM_MSC, 5, EPNUM_MSC_OUT, EPNUM_MSC_IN, TUD_OPT_HIGH_SPEED ? 512 : 64), }; diff --git a/examples/device/dfu_rt/src/tusb_config.h b/examples/device/dfu_rt/src/tusb_config.h index f6bf79e05..226573263 100644 --- a/examples/device/dfu_rt/src/tusb_config.h +++ b/examples/device/dfu_rt/src/tusb_config.h @@ -16,19 +16,38 @@ // COMMON CONFIGURATION //-------------------------------------------------------------------- -// defined by compiler flags for flexibility +// defined by board.mk #ifndef CFG_TUSB_MCU #error CFG_TUSB_MCU must be defined #endif -#if CFG_TUSB_MCU == OPT_MCU_LPC18XX || CFG_TUSB_MCU == OPT_MCU_LPC43XX || CFG_TUSB_MCU == OPT_MCU_MIMXRT10XX || \ - CFG_TUSB_MCU == OPT_MCU_NUC505 || CFG_TUSB_MCU == OPT_MCU_CXD56 - #define CFG_TUSB_RHPORT0_MODE (OPT_MODE_DEVICE | OPT_MODE_HIGH_SPEED) -#else - #define CFG_TUSB_RHPORT0_MODE OPT_MODE_DEVICE +// RHPort number used for device can be defined by board.mk, default to port 0 +#ifndef BOARD_DEVICE_RHPORT_NUM + #define BOARD_DEVICE_RHPORT_NUM 0 #endif -#define CFG_TUSB_OS OPT_OS_NONE +// RHPort max operational speed can defined by board.mk +// Default to Highspeed for MCU with internal HighSpeed PHY (can be port specific), otherwise FullSpeed +#ifndef BOARD_DEVICE_RHPORT_SPEED + #if (CFG_TUSB_MCU == OPT_MCU_LPC18XX || CFG_TUSB_MCU == OPT_MCU_LPC43XX || CFG_TUSB_MCU == OPT_MCU_MIMXRT10XX || \ + CFG_TUSB_MCU == OPT_MCU_NUC505 || CFG_TUSB_MCU == OPT_MCU_CXD56) + #define BOARD_DEVICE_RHPORT_SPEED OPT_MODE_HIGH_SPEED + #else + #define BOARD_DEVICE_RHPORT_SPEED OPT_MODE_FULL_SPEED + #endif +#endif + +// Device mode with rhport and speed defined by board.mk +#if BOARD_DEVICE_RHPORT_NUM == 0 + #define CFG_TUSB_RHPORT0_MODE (OPT_MODE_DEVICE | BOARD_DEVICE_RHPORT_SPEED) +#elif BOARD_DEVICE_RHPORT_NUM == 1 + #define CFG_TUSB_RHPORT1_MODE (OPT_MODE_DEVICE | BOARD_DEVICE_RHPORT_SPEED) +#else + #error "Incorrect RHPort configuration" +#endif + +// This example doesn't use an RTOS +#define CFG_TUSB_OS OPT_OS_NONE // CFG_TUSB_DEBUG is defined by compiler in DEBUG build // #define CFG_TUSB_DEBUG 0 diff --git a/examples/device/dynamic_configuration/src/tusb_config.h b/examples/device/dynamic_configuration/src/tusb_config.h index 958a446ac..0950305eb 100644 --- a/examples/device/dynamic_configuration/src/tusb_config.h +++ b/examples/device/dynamic_configuration/src/tusb_config.h @@ -34,19 +34,38 @@ // COMMON CONFIGURATION //-------------------------------------------------------------------- -// defined by compiler flags for flexibility +// defined by board.mk #ifndef CFG_TUSB_MCU #error CFG_TUSB_MCU must be defined #endif -#if CFG_TUSB_MCU == OPT_MCU_LPC18XX || CFG_TUSB_MCU == OPT_MCU_LPC43XX || CFG_TUSB_MCU == OPT_MCU_MIMXRT10XX || \ - CFG_TUSB_MCU == OPT_MCU_NUC505 || CFG_TUSB_MCU == OPT_MCU_CXD56 - #define CFG_TUSB_RHPORT0_MODE (OPT_MODE_DEVICE | OPT_MODE_HIGH_SPEED) -#else - #define CFG_TUSB_RHPORT0_MODE OPT_MODE_DEVICE +// RHPort number used for device can be defined by board.mk, default to port 0 +#ifndef BOARD_DEVICE_RHPORT_NUM + #define BOARD_DEVICE_RHPORT_NUM 0 #endif -#define CFG_TUSB_OS OPT_OS_NONE +// RHPort max operational speed can defined by board.mk +// Default to Highspeed for MCU with internal HighSpeed PHY (can be port specific), otherwise FullSpeed +#ifndef BOARD_DEVICE_RHPORT_SPEED + #if (CFG_TUSB_MCU == OPT_MCU_LPC18XX || CFG_TUSB_MCU == OPT_MCU_LPC43XX || CFG_TUSB_MCU == OPT_MCU_MIMXRT10XX || \ + CFG_TUSB_MCU == OPT_MCU_NUC505 || CFG_TUSB_MCU == OPT_MCU_CXD56) + #define BOARD_DEVICE_RHPORT_SPEED OPT_MODE_HIGH_SPEED + #else + #define BOARD_DEVICE_RHPORT_SPEED OPT_MODE_FULL_SPEED + #endif +#endif + +// Device mode with rhport and speed defined by board.mk +#if BOARD_DEVICE_RHPORT_NUM == 0 + #define CFG_TUSB_RHPORT0_MODE (OPT_MODE_DEVICE | BOARD_DEVICE_RHPORT_SPEED) +#elif BOARD_DEVICE_RHPORT_NUM == 1 + #define CFG_TUSB_RHPORT1_MODE (OPT_MODE_DEVICE | BOARD_DEVICE_RHPORT_SPEED) +#else + #error "Incorrect RHPort configuration" +#endif + +// This example doesn't use an RTOS +#define CFG_TUSB_OS OPT_OS_NONE // CFG_TUSB_DEBUG is defined by compiler in DEBUG build // #define CFG_TUSB_DEBUG 0 diff --git a/examples/device/dynamic_configuration/src/usb_descriptors.c b/examples/device/dynamic_configuration/src/usb_descriptors.c index 63468b496..a2017f954 100644 --- a/examples/device/dynamic_configuration/src/usb_descriptors.c +++ b/examples/device/dynamic_configuration/src/usb_descriptors.c @@ -166,7 +166,7 @@ uint8_t const desc_configuration_0[] = TUD_CDC_DESCRIPTOR(ITF_0_NUM_CDC, 0, EPNUM_0_CDC_NOTIF, 8, EPNUM_0_CDC_OUT, EPNUM_0_CDC_IN, 64), // Interface number, string index, EP Out & EP In address, EP size - TUD_MIDI_DESCRIPTOR(ITF_0_NUM_MIDI, 0, EPNUM_0_MIDI_OUT, EPNUM_0_MIDI_IN, (CFG_TUSB_RHPORT0_MODE & OPT_MODE_HIGH_SPEED) ? 512 : 64), + TUD_MIDI_DESCRIPTOR(ITF_0_NUM_MIDI, 0, EPNUM_0_MIDI_OUT, EPNUM_0_MIDI_IN, TUD_OPT_HIGH_SPEED ? 512 : 64), }; @@ -176,7 +176,7 @@ uint8_t const desc_configuraiton_1[] = TUD_CONFIG_DESCRIPTOR(1, ITF_1_NUM_TOTAL, 0, CONFIG_1_TOTAL_LEN, TUSB_DESC_CONFIG_ATT_REMOTE_WAKEUP, 100), // Interface number, string index, EP Out & EP In address, EP size - TUD_MSC_DESCRIPTOR(ITF_1_NUM_MSC, 0, EPNUM_1_MSC_OUT, EPNUM_1_MSC_IN, (CFG_TUSB_RHPORT0_MODE & OPT_MODE_HIGH_SPEED) ? 512 : 64), + TUD_MSC_DESCRIPTOR(ITF_1_NUM_MSC, 0, EPNUM_1_MSC_OUT, EPNUM_1_MSC_IN, TUD_OPT_HIGH_SPEED ? 512 : 64), }; diff --git a/examples/device/hid_composite/src/tusb_config.h b/examples/device/hid_composite/src/tusb_config.h index adc795cc2..abc243436 100644 --- a/examples/device/hid_composite/src/tusb_config.h +++ b/examples/device/hid_composite/src/tusb_config.h @@ -34,19 +34,38 @@ // COMMON CONFIGURATION //-------------------------------------------------------------------- -// defined by compiler flags for flexibility +// defined by board.mk #ifndef CFG_TUSB_MCU #error CFG_TUSB_MCU must be defined #endif -#if CFG_TUSB_MCU == OPT_MCU_LPC18XX || CFG_TUSB_MCU == OPT_MCU_LPC43XX || CFG_TUSB_MCU == OPT_MCU_MIMXRT10XX || \ - CFG_TUSB_MCU == OPT_MCU_NUC505 || CFG_TUSB_MCU == OPT_MCU_CXD56 - #define CFG_TUSB_RHPORT0_MODE (OPT_MODE_DEVICE | OPT_MODE_HIGH_SPEED) -#else - #define CFG_TUSB_RHPORT0_MODE OPT_MODE_DEVICE +// RHPort number used for device can be defined by board.mk, default to port 0 +#ifndef BOARD_DEVICE_RHPORT_NUM + #define BOARD_DEVICE_RHPORT_NUM 0 #endif -#define CFG_TUSB_OS OPT_OS_NONE +// RHPort max operational speed can defined by board.mk +// Default to Highspeed for MCU with internal HighSpeed PHY (can be port specific), otherwise FullSpeed +#ifndef BOARD_DEVICE_RHPORT_SPEED + #if (CFG_TUSB_MCU == OPT_MCU_LPC18XX || CFG_TUSB_MCU == OPT_MCU_LPC43XX || CFG_TUSB_MCU == OPT_MCU_MIMXRT10XX || \ + CFG_TUSB_MCU == OPT_MCU_NUC505 || CFG_TUSB_MCU == OPT_MCU_CXD56) + #define BOARD_DEVICE_RHPORT_SPEED OPT_MODE_HIGH_SPEED + #else + #define BOARD_DEVICE_RHPORT_SPEED OPT_MODE_FULL_SPEED + #endif +#endif + +// Device mode with rhport and speed defined by board.mk +#if BOARD_DEVICE_RHPORT_NUM == 0 + #define CFG_TUSB_RHPORT0_MODE (OPT_MODE_DEVICE | BOARD_DEVICE_RHPORT_SPEED) +#elif BOARD_DEVICE_RHPORT_NUM == 1 + #define CFG_TUSB_RHPORT1_MODE (OPT_MODE_DEVICE | BOARD_DEVICE_RHPORT_SPEED) +#else + #error "Incorrect RHPort configuration" +#endif + +// This example doesn't use an RTOS +#define CFG_TUSB_OS OPT_OS_NONE // CFG_TUSB_DEBUG is defined by compiler in DEBUG build // #define CFG_TUSB_DEBUG 0 diff --git a/examples/device/hid_composite_freertos/src/tusb_config.h b/examples/device/hid_composite_freertos/src/tusb_config.h index e7aea1863..677a9b2c6 100644 --- a/examples/device/hid_composite_freertos/src/tusb_config.h +++ b/examples/device/hid_composite_freertos/src/tusb_config.h @@ -34,18 +34,38 @@ // COMMON CONFIGURATION //-------------------------------------------------------------------- -// defined by compiler flags for flexibility +// defined by board.mk #ifndef CFG_TUSB_MCU #error CFG_TUSB_MCU must be defined #endif -#if CFG_TUSB_MCU == OPT_MCU_LPC43XX || CFG_TUSB_MCU == OPT_MCU_LPC18XX || CFG_TUSB_MCU == OPT_MCU_MIMXRT10XX || CFG_TUSB_MCU == OPT_MCU_NUC505 -#define CFG_TUSB_RHPORT0_MODE (OPT_MODE_DEVICE | OPT_MODE_HIGH_SPEED) -#else -#define CFG_TUSB_RHPORT0_MODE OPT_MODE_DEVICE +// RHPort number used for device can be defined by board.mk, default to port 0 +#ifndef BOARD_DEVICE_RHPORT_NUM + #define BOARD_DEVICE_RHPORT_NUM 0 #endif -#define CFG_TUSB_OS OPT_OS_FREERTOS +// RHPort max operational speed can defined by board.mk +// Default to Highspeed for MCU with internal HighSpeed PHY (can be port specific), otherwise FullSpeed +#ifndef BOARD_DEVICE_RHPORT_SPEED + #if (CFG_TUSB_MCU == OPT_MCU_LPC18XX || CFG_TUSB_MCU == OPT_MCU_LPC43XX || CFG_TUSB_MCU == OPT_MCU_MIMXRT10XX || \ + CFG_TUSB_MCU == OPT_MCU_NUC505 || CFG_TUSB_MCU == OPT_MCU_CXD56) + #define BOARD_DEVICE_RHPORT_SPEED OPT_MODE_HIGH_SPEED + #else + #define BOARD_DEVICE_RHPORT_SPEED OPT_MODE_FULL_SPEED + #endif +#endif + +// Device mode with rhport and speed defined by board.mk +#if BOARD_DEVICE_RHPORT_NUM == 0 + #define CFG_TUSB_RHPORT0_MODE (OPT_MODE_DEVICE | BOARD_DEVICE_RHPORT_SPEED) +#elif BOARD_DEVICE_RHPORT_NUM == 1 + #define CFG_TUSB_RHPORT1_MODE (OPT_MODE_DEVICE | BOARD_DEVICE_RHPORT_SPEED) +#else + #error "Incorrect RHPort configuration" +#endif + +// This examples use FreeRTOS +#define CFG_TUSB_OS OPT_OS_FREERTOS // CFG_TUSB_DEBUG is defined by compiler in DEBUG build // #define CFG_TUSB_DEBUG 0 diff --git a/examples/device/hid_generic_inout/src/tusb_config.h b/examples/device/hid_generic_inout/src/tusb_config.h index 4dc3ecea4..39eebbbeb 100644 --- a/examples/device/hid_generic_inout/src/tusb_config.h +++ b/examples/device/hid_generic_inout/src/tusb_config.h @@ -34,19 +34,38 @@ // COMMON CONFIGURATION //-------------------------------------------------------------------- -// defined by compiler flags for flexibility +// defined by board.mk #ifndef CFG_TUSB_MCU #error CFG_TUSB_MCU must be defined #endif -#if CFG_TUSB_MCU == OPT_MCU_LPC18XX || CFG_TUSB_MCU == OPT_MCU_LPC43XX || CFG_TUSB_MCU == OPT_MCU_MIMXRT10XX || \ - CFG_TUSB_MCU == OPT_MCU_NUC505 || CFG_TUSB_MCU == OPT_MCU_CXD56 - #define CFG_TUSB_RHPORT0_MODE (OPT_MODE_DEVICE | OPT_MODE_HIGH_SPEED) -#else - #define CFG_TUSB_RHPORT0_MODE OPT_MODE_DEVICE +// RHPort number used for device can be defined by board.mk, default to port 0 +#ifndef BOARD_DEVICE_RHPORT_NUM + #define BOARD_DEVICE_RHPORT_NUM 0 #endif -#define CFG_TUSB_OS OPT_OS_NONE +// RHPort max operational speed can defined by board.mk +// Default to Highspeed for MCU with internal HighSpeed PHY (can be port specific), otherwise FullSpeed +#ifndef BOARD_DEVICE_RHPORT_SPEED + #if (CFG_TUSB_MCU == OPT_MCU_LPC18XX || CFG_TUSB_MCU == OPT_MCU_LPC43XX || CFG_TUSB_MCU == OPT_MCU_MIMXRT10XX || \ + CFG_TUSB_MCU == OPT_MCU_NUC505 || CFG_TUSB_MCU == OPT_MCU_CXD56) + #define BOARD_DEVICE_RHPORT_SPEED OPT_MODE_HIGH_SPEED + #else + #define BOARD_DEVICE_RHPORT_SPEED OPT_MODE_FULL_SPEED + #endif +#endif + +// Device mode with rhport and speed defined by board.mk +#if BOARD_DEVICE_RHPORT_NUM == 0 + #define CFG_TUSB_RHPORT0_MODE (OPT_MODE_DEVICE | BOARD_DEVICE_RHPORT_SPEED) +#elif BOARD_DEVICE_RHPORT_NUM == 1 + #define CFG_TUSB_RHPORT1_MODE (OPT_MODE_DEVICE | BOARD_DEVICE_RHPORT_SPEED) +#else + #error "Incorrect RHPort configuration" +#endif + +// This example doesn't use an RTOS +#define CFG_TUSB_OS OPT_OS_NONE // CFG_TUSB_DEBUG is defined by compiler in DEBUG build // #define CFG_TUSB_DEBUG 0 diff --git a/examples/device/midi_test/src/usb_descriptors.c b/examples/device/midi_test/src/usb_descriptors.c index 72ab1416c..2867a205f 100644 --- a/examples/device/midi_test/src/usb_descriptors.c +++ b/examples/device/midi_test/src/usb_descriptors.c @@ -94,7 +94,7 @@ uint8_t const desc_configuration[] = TUD_CONFIG_DESCRIPTOR(1, ITF_NUM_TOTAL, 0, CONFIG_TOTAL_LEN, TUSB_DESC_CONFIG_ATT_REMOTE_WAKEUP, 100), // Interface number, string index, EP Out & EP In address, EP size - TUD_MIDI_DESCRIPTOR(ITF_NUM_MIDI, 0, EPNUM_MIDI, 0x80 | EPNUM_MIDI, (CFG_TUSB_RHPORT0_MODE & OPT_MODE_HIGH_SPEED) ? 512 : 64) + TUD_MIDI_DESCRIPTOR(ITF_NUM_MIDI, 0, EPNUM_MIDI, 0x80 | EPNUM_MIDI, TUD_OPT_HIGH_SPEED ? 512 : 64) }; // Invoked when received GET CONFIGURATION DESCRIPTOR diff --git a/examples/device/msc_dual_lun/src/tusb_config.h b/examples/device/msc_dual_lun/src/tusb_config.h index 841a8aa00..1ee3faec4 100644 --- a/examples/device/msc_dual_lun/src/tusb_config.h +++ b/examples/device/msc_dual_lun/src/tusb_config.h @@ -34,19 +34,38 @@ // COMMON CONFIGURATION //-------------------------------------------------------------------- -// defined by compiler flags for flexibility +// defined by board.mk #ifndef CFG_TUSB_MCU #error CFG_TUSB_MCU must be defined #endif -#if CFG_TUSB_MCU == OPT_MCU_LPC18XX || CFG_TUSB_MCU == OPT_MCU_LPC43XX || CFG_TUSB_MCU == OPT_MCU_MIMXRT10XX || \ - CFG_TUSB_MCU == OPT_MCU_NUC505 || CFG_TUSB_MCU == OPT_MCU_CXD56 - #define CFG_TUSB_RHPORT0_MODE (OPT_MODE_DEVICE | OPT_MODE_HIGH_SPEED) -#else - #define CFG_TUSB_RHPORT0_MODE OPT_MODE_DEVICE +// RHPort number used for device can be defined by board.mk, default to port 0 +#ifndef BOARD_DEVICE_RHPORT_NUM + #define BOARD_DEVICE_RHPORT_NUM 0 #endif -#define CFG_TUSB_OS OPT_OS_NONE +// RHPort max operational speed can defined by board.mk +// Default to Highspeed for MCU with internal HighSpeed PHY (can be port specific), otherwise FullSpeed +#ifndef BOARD_DEVICE_RHPORT_SPEED + #if (CFG_TUSB_MCU == OPT_MCU_LPC18XX || CFG_TUSB_MCU == OPT_MCU_LPC43XX || CFG_TUSB_MCU == OPT_MCU_MIMXRT10XX || \ + CFG_TUSB_MCU == OPT_MCU_NUC505 || CFG_TUSB_MCU == OPT_MCU_CXD56) + #define BOARD_DEVICE_RHPORT_SPEED OPT_MODE_HIGH_SPEED + #else + #define BOARD_DEVICE_RHPORT_SPEED OPT_MODE_FULL_SPEED + #endif +#endif + +// Device mode with rhport and speed defined by board.mk +#if BOARD_DEVICE_RHPORT_NUM == 0 + #define CFG_TUSB_RHPORT0_MODE (OPT_MODE_DEVICE | BOARD_DEVICE_RHPORT_SPEED) +#elif BOARD_DEVICE_RHPORT_NUM == 1 + #define CFG_TUSB_RHPORT1_MODE (OPT_MODE_DEVICE | BOARD_DEVICE_RHPORT_SPEED) +#else + #error "Incorrect RHPort configuration" +#endif + +// This example doesn't use an RTOS +#define CFG_TUSB_OS OPT_OS_NONE // CFG_TUSB_DEBUG is defined by compiler in DEBUG build // #define CFG_TUSB_DEBUG 0 diff --git a/examples/device/msc_dual_lun/src/usb_descriptors.c b/examples/device/msc_dual_lun/src/usb_descriptors.c index 9128c4f75..d0c915b1d 100644 --- a/examples/device/msc_dual_lun/src/usb_descriptors.c +++ b/examples/device/msc_dual_lun/src/usb_descriptors.c @@ -102,7 +102,7 @@ uint8_t const desc_configuration[] = TUD_CONFIG_DESCRIPTOR(1, ITF_NUM_TOTAL, 0, CONFIG_TOTAL_LEN, TUSB_DESC_CONFIG_ATT_REMOTE_WAKEUP, 100), // Interface number, string index, EP Out & EP In address, EP size - TUD_MSC_DESCRIPTOR(ITF_NUM_MSC, 0, EPNUM_MSC_OUT, EPNUM_MSC_IN, (CFG_TUSB_RHPORT0_MODE & OPT_MODE_HIGH_SPEED) ? 512 : 64), + TUD_MSC_DESCRIPTOR(ITF_NUM_MSC, 0, EPNUM_MSC_OUT, EPNUM_MSC_IN, TUD_OPT_HIGH_SPEED ? 512 : 64), }; // Invoked when received GET CONFIGURATION DESCRIPTOR diff --git a/examples/device/net_lwip_webserver/src/tusb_config.h b/examples/device/net_lwip_webserver/src/tusb_config.h index 45c0b8ac1..b6d0e7a86 100644 --- a/examples/device/net_lwip_webserver/src/tusb_config.h +++ b/examples/device/net_lwip_webserver/src/tusb_config.h @@ -34,19 +34,38 @@ // COMMON CONFIGURATION //-------------------------------------------------------------------- -// defined by compiler flags for flexibility +// defined by board.mk #ifndef CFG_TUSB_MCU #error CFG_TUSB_MCU must be defined #endif -#if CFG_TUSB_MCU == OPT_MCU_LPC18XX || CFG_TUSB_MCU == OPT_MCU_LPC43XX || CFG_TUSB_MCU == OPT_MCU_MIMXRT10XX || \ - CFG_TUSB_MCU == OPT_MCU_NUC505 || CFG_TUSB_MCU == OPT_MCU_CXD56 - #define CFG_TUSB_RHPORT0_MODE (OPT_MODE_DEVICE | OPT_MODE_HIGH_SPEED) -#else - #define CFG_TUSB_RHPORT0_MODE OPT_MODE_DEVICE +// RHPort number used for device can be defined by board.mk, default to port 0 +#ifndef BOARD_DEVICE_RHPORT_NUM + #define BOARD_DEVICE_RHPORT_NUM 0 #endif -#define CFG_TUSB_OS OPT_OS_NONE +// RHPort max operational speed can defined by board.mk +// Default to Highspeed for MCU with internal HighSpeed PHY (can be port specific), otherwise FullSpeed +#ifndef BOARD_DEVICE_RHPORT_SPEED + #if (CFG_TUSB_MCU == OPT_MCU_LPC18XX || CFG_TUSB_MCU == OPT_MCU_LPC43XX || CFG_TUSB_MCU == OPT_MCU_MIMXRT10XX || \ + CFG_TUSB_MCU == OPT_MCU_NUC505 || CFG_TUSB_MCU == OPT_MCU_CXD56) + #define BOARD_DEVICE_RHPORT_SPEED OPT_MODE_HIGH_SPEED + #else + #define BOARD_DEVICE_RHPORT_SPEED OPT_MODE_FULL_SPEED + #endif +#endif + +// Device mode with rhport and speed defined by board.mk +#if BOARD_DEVICE_RHPORT_NUM == 0 + #define CFG_TUSB_RHPORT0_MODE (OPT_MODE_DEVICE | BOARD_DEVICE_RHPORT_SPEED) +#elif BOARD_DEVICE_RHPORT_NUM == 1 + #define CFG_TUSB_RHPORT1_MODE (OPT_MODE_DEVICE | BOARD_DEVICE_RHPORT_SPEED) +#else + #error "Incorrect RHPort configuration" +#endif + +// This example doesn't use an RTOS +#define CFG_TUSB_OS OPT_OS_NONE // CFG_TUSB_DEBUG is defined by compiler in DEBUG build // #define CFG_TUSB_DEBUG 0 diff --git a/examples/device/usbtmc/src/tusb_config.h b/examples/device/usbtmc/src/tusb_config.h index 1022125bb..3fab286a9 100644 --- a/examples/device/usbtmc/src/tusb_config.h +++ b/examples/device/usbtmc/src/tusb_config.h @@ -16,18 +16,38 @@ // COMMON CONFIGURATION //-------------------------------------------------------------------- -// defined by compiler flags for flexibility +// defined by board.mk #ifndef CFG_TUSB_MCU #error CFG_TUSB_MCU must be defined #endif -#if CFG_TUSB_MCU == OPT_MCU_LPC18XX || CFG_TUSB_MCU == OPT_MCU_LPC43XX || CFG_TUSB_MCU == OPT_MCU_MIMXRT10XX || \ - CFG_TUSB_MCU == OPT_MCU_NUC505 || CFG_TUSB_MCU == OPT_MCU_CXD56 - #define CFG_TUSB_RHPORT0_MODE (OPT_MODE_DEVICE | OPT_MODE_HIGH_SPEED) -#else - #define CFG_TUSB_RHPORT0_MODE OPT_MODE_DEVICE +// RHPort number used for device can be defined by board.mk, default to port 0 +#ifndef BOARD_DEVICE_RHPORT_NUM + #define BOARD_DEVICE_RHPORT_NUM 0 #endif -#define CFG_TUSB_OS OPT_OS_NONE + +// RHPort max operational speed can defined by board.mk +// Default to Highspeed for MCU with internal HighSpeed PHY (can be port specific), otherwise FullSpeed +#ifndef BOARD_DEVICE_RHPORT_SPEED + #if (CFG_TUSB_MCU == OPT_MCU_LPC18XX || CFG_TUSB_MCU == OPT_MCU_LPC43XX || CFG_TUSB_MCU == OPT_MCU_MIMXRT10XX || \ + CFG_TUSB_MCU == OPT_MCU_NUC505 || CFG_TUSB_MCU == OPT_MCU_CXD56) + #define BOARD_DEVICE_RHPORT_SPEED OPT_MODE_HIGH_SPEED + #else + #define BOARD_DEVICE_RHPORT_SPEED OPT_MODE_FULL_SPEED + #endif +#endif + +// Device mode with rhport and speed defined by board.mk +#if BOARD_DEVICE_RHPORT_NUM == 0 + #define CFG_TUSB_RHPORT0_MODE (OPT_MODE_DEVICE | BOARD_DEVICE_RHPORT_SPEED) +#elif BOARD_DEVICE_RHPORT_NUM == 1 + #define CFG_TUSB_RHPORT1_MODE (OPT_MODE_DEVICE | BOARD_DEVICE_RHPORT_SPEED) +#else + #error "Incorrect RHPort configuration" +#endif + +// This example doesn't use an RTOS +#define CFG_TUSB_OS OPT_OS_NONE // CFG_TUSB_DEBUG is defined by compiler in DEBUG build // #define CFG_TUSB_DEBUG 0 diff --git a/examples/device/webusb_serial/src/tusb_config.h b/examples/device/webusb_serial/src/tusb_config.h index e7e0b81bc..c226eefa6 100644 --- a/examples/device/webusb_serial/src/tusb_config.h +++ b/examples/device/webusb_serial/src/tusb_config.h @@ -34,19 +34,38 @@ // COMMON CONFIGURATION //-------------------------------------------------------------------- -// defined by compiler flags for flexibility +// defined by board.mk #ifndef CFG_TUSB_MCU #error CFG_TUSB_MCU must be defined #endif -#if CFG_TUSB_MCU == OPT_MCU_LPC18XX || CFG_TUSB_MCU == OPT_MCU_LPC43XX || CFG_TUSB_MCU == OPT_MCU_MIMXRT10XX || \ - CFG_TUSB_MCU == OPT_MCU_NUC505 || CFG_TUSB_MCU == OPT_MCU_CXD56 - #define CFG_TUSB_RHPORT0_MODE (OPT_MODE_DEVICE | OPT_MODE_HIGH_SPEED) -#else - #define CFG_TUSB_RHPORT0_MODE OPT_MODE_DEVICE +// RHPort number used for device can be defined by board.mk, default to port 0 +#ifndef BOARD_DEVICE_RHPORT_NUM + #define BOARD_DEVICE_RHPORT_NUM 0 #endif -#define CFG_TUSB_OS OPT_OS_NONE +// RHPort max operational speed can defined by board.mk +// Default to Highspeed for MCU with internal HighSpeed PHY (can be port specific), otherwise FullSpeed +#ifndef BOARD_DEVICE_RHPORT_SPEED + #if (CFG_TUSB_MCU == OPT_MCU_LPC18XX || CFG_TUSB_MCU == OPT_MCU_LPC43XX || CFG_TUSB_MCU == OPT_MCU_MIMXRT10XX || \ + CFG_TUSB_MCU == OPT_MCU_NUC505 || CFG_TUSB_MCU == OPT_MCU_CXD56) + #define BOARD_DEVICE_RHPORT_SPEED OPT_MODE_HIGH_SPEED + #else + #define BOARD_DEVICE_RHPORT_SPEED OPT_MODE_FULL_SPEED + #endif +#endif + +// Device mode with rhport and speed defined by board.mk +#if BOARD_DEVICE_RHPORT_NUM == 0 + #define CFG_TUSB_RHPORT0_MODE (OPT_MODE_DEVICE | BOARD_DEVICE_RHPORT_SPEED) +#elif BOARD_DEVICE_RHPORT_NUM == 1 + #define CFG_TUSB_RHPORT1_MODE (OPT_MODE_DEVICE | BOARD_DEVICE_RHPORT_SPEED) +#else + #error "Incorrect RHPort configuration" +#endif + +// This example doesn't use an RTOS +#define CFG_TUSB_OS OPT_OS_NONE // CFG_TUSB_DEBUG is defined by compiler in DEBUG build // #define CFG_TUSB_DEBUG 0 diff --git a/test/test/device/msc/test_msc_device.c b/test/test/device/msc/test_msc_device.c index 34bd90c7e..0382fb327 100644 --- a/test/test/device/msc/test_msc_device.c +++ b/test/test/device/msc/test_msc_device.c @@ -66,7 +66,7 @@ uint8_t const data_desc_configuration[] = TUD_CONFIG_DESCRIPTOR(1, ITF_NUM_TOTAL, 0, CONFIG_TOTAL_LEN, TUSB_DESC_CONFIG_ATT_REMOTE_WAKEUP, 100), // Interface number, string index, EP Out & EP In address, EP size - TUD_MSC_DESCRIPTOR(ITF_NUM_MSC, 0, EDPT_MSC_OUT, EDPT_MSC_IN, (CFG_TUSB_RHPORT0_MODE & OPT_MODE_HIGH_SPEED) ? 512 : 64), + TUD_MSC_DESCRIPTOR(ITF_NUM_MSC, 0, EDPT_MSC_OUT, EDPT_MSC_IN, TUD_OPT_HIGH_SPEED ? 512 : 64), }; tusb_control_request_t const request_set_configuration = From 667eaa6dd693226d2595e2d19aa3f4798f0a4092 Mon Sep 17 00:00:00 2001 From: hathach Date: Tue, 16 Jun 2020 00:03:52 +0700 Subject: [PATCH 22/48] fix stm32h743 priority with freeRTOS --- hw/bsp/stm32h743eval/stm32h743eval.c | 12 ++++++++---- src/portable/st/synopsys/dcd_synopsys.c | 9 +++++++-- 2 files changed, 15 insertions(+), 6 deletions(-) diff --git a/hw/bsp/stm32h743eval/stm32h743eval.c b/hw/bsp/stm32h743eval/stm32h743eval.c index 8bafc32cb..772edf33c 100644 --- a/hw/bsp/stm32h743eval/stm32h743eval.c +++ b/hw/bsp/stm32h743eval/stm32h743eval.c @@ -185,10 +185,14 @@ void board_init(void) SystemClock_Config(); all_rcc_clk_enable(); - #if CFG_TUSB_OS == OPT_OS_NONE - // 1ms tick timer - SysTick_Config(SystemCoreClock / 1000); - #endif + // 1ms tick timer + SysTick_Config(SystemCoreClock / 1000); + +#if CFG_TUSB_OS == OPT_OS_FREERTOS + // If freeRTOS is used, IRQ priority is limit by max syscall ( smaller is higher ) + NVIC_SetPriority(OTG_FS_IRQn, configLIBRARY_MAX_SYSCALL_INTERRUPT_PRIORITY ); + NVIC_SetPriority(OTG_HS_IRQn, configLIBRARY_MAX_SYSCALL_INTERRUPT_PRIORITY ); +#endif GPIO_InitTypeDef GPIO_InitStruct; diff --git a/src/portable/st/synopsys/dcd_synopsys.c b/src/portable/st/synopsys/dcd_synopsys.c index 030c089aa..d636e581c 100644 --- a/src/portable/st/synopsys/dcd_synopsys.c +++ b/src/portable/st/synopsys/dcd_synopsys.c @@ -48,36 +48,41 @@ (CFG_TUSB_MCU == OPT_MCU_STM32L4 && defined(STM32L4_SYNOPSYS)) \ ) -// TODO Support OTG_HS // EP_MAX : Max number of bi-directional endpoints including EP0 // EP_FIFO_SIZE : Size of dedicated USB SRAM #if CFG_TUSB_MCU == OPT_MCU_STM32F1 #include "stm32f1xx.h" #define EP_MAX 4 #define EP_FIFO_SIZE 1280 + #elif CFG_TUSB_MCU == OPT_MCU_STM32F2 #include "stm32f2xx.h" #define EP_MAX USB_OTG_FS_MAX_IN_ENDPOINTS #define EP_FIFO_SIZE USB_OTG_FS_TOTAL_FIFO_SIZE + #elif CFG_TUSB_MCU == OPT_MCU_STM32F4 #include "stm32f4xx.h" #define EP_MAX USB_OTG_FS_MAX_IN_ENDPOINTS #define EP_FIFO_SIZE USB_OTG_FS_TOTAL_FIFO_SIZE + #elif CFG_TUSB_MCU == OPT_MCU_STM32H7 #include "stm32h7xx.h" #define EP_MAX 9 #define EP_FIFO_SIZE 4096 - // TODO The official name of the USB FS peripheral on H7 is "USB2_OTG_FS". + #elif CFG_TUSB_MCU == OPT_MCU_STM32F7 #include "stm32f7xx.h" #define EP_MAX 6 #define EP_FIFO_SIZE 1280 + #elif CFG_TUSB_MCU == OPT_MCU_STM32L4 #include "stm32l4xx.h" #define EP_MAX 6 #define EP_FIFO_SIZE 1280 + #else #error "Unsupported MCUs" + #endif #include "device/dcd.h" From 2b1c7730b719c6d4abd7d1bfbfdb80b0d64ee892 Mon Sep 17 00:00:00 2001 From: hathach Date: Tue, 16 Jun 2020 00:53:06 +0700 Subject: [PATCH 23/48] fix hs port1 build with net endpoint --- src/class/net/net_device.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/class/net/net_device.h b/src/class/net/net_device.h index 67cd99933..964bc8a00 100644 --- a/src/class/net/net_device.h +++ b/src/class/net/net_device.h @@ -37,7 +37,7 @@ #include "netif/ethernet.h" /* declared here, NOT in usb_descriptors.c, so that the driver can intelligently ZLP as needed */ -#define CFG_TUD_NET_ENDPOINT_SIZE ((CFG_TUSB_RHPORT0_MODE & OPT_MODE_HIGH_SPEED) ? 512 : 64) +#define CFG_TUD_NET_ENDPOINT_SIZE (TUD_OPT_HIGH_SPEED ? 512 : 64) /* Maximum Tranmission Unit (in bytes) of the network, including Ethernet header */ #define CFG_TUD_NET_MTU (1500 + SIZEOF_ETH_HDR) From 4b7f848e1fee86e047cfbe2957701c02f1b5fdf2 Mon Sep 17 00:00:00 2001 From: Uwe Bonnes Date: Sun, 21 Jun 2020 17:55:44 +0200 Subject: [PATCH 24/48] stm32h743nucleo: Enable Log via STLINK-VCP. --- hw/bsp/stm32h743nucleo/board.mk | 4 ++- hw/bsp/stm32h743nucleo/stm32h743nucleo.c | 34 ++++++++++++++++++--- hw/bsp/stm32h743nucleo/stm32h7xx_hal_conf.h | 3 +- 3 files changed, 35 insertions(+), 6 deletions(-) diff --git a/hw/bsp/stm32h743nucleo/board.mk b/hw/bsp/stm32h743nucleo/board.mk index 30e52dfcc..43a4999a4 100644 --- a/hw/bsp/stm32h743nucleo/board.mk +++ b/hw/bsp/stm32h743nucleo/board.mk @@ -9,7 +9,8 @@ CFLAGS += \ -DSTM32H743xx \ -DCFG_TUSB_MCU=OPT_MCU_STM32H7 -# mcu driver cause following warnings +# suppress warning caused by vendor mcu driver +CFLAGS += -Wno-error=maybe-uninitialized -Wno-error=cast-align ST_HAL_DRIVER = hw/mcu/st/st_driver/STM32H7xx_HAL_Driver ST_CMSIS = hw/mcu/st/st_driver/CMSIS/Device/ST/STM32H7xx @@ -24,6 +25,7 @@ SRC_C += \ $(ST_HAL_DRIVER)/Src/stm32h7xx_hal_rcc.c \ $(ST_HAL_DRIVER)/Src/stm32h7xx_hal_rcc_ex.c \ $(ST_HAL_DRIVER)/Src/stm32h7xx_hal_gpio.c \ + $(ST_HAL_DRIVER)/Src/stm32h7xx_hal_uart.c \ $(ST_HAL_DRIVER)/Src/stm32h7xx_hal_pwr_ex.c SRC_S += \ diff --git a/hw/bsp/stm32h743nucleo/stm32h743nucleo.c b/hw/bsp/stm32h743nucleo/stm32h743nucleo.c index bb768eb40..b4a723871 100644 --- a/hw/bsp/stm32h743nucleo/stm32h743nucleo.c +++ b/hw/bsp/stm32h743nucleo/stm32h743nucleo.c @@ -49,14 +49,22 @@ void OTG_FS_IRQHandler(void) #define BUTTON_PIN GPIO_PIN_13 #define BUTTON_STATE_ACTIVE 1 +#define UARTx USART3 +#define UART_GPIO_PORT GPIOD +#define UART_GPIO_AF GPIO_AF7_USART3 +#define UART_TX_PIN GPIO_PIN_8 +#define UART_RX_PIN GPIO_PIN_9 + +UART_HandleTypeDef UartHandle; + // enable all LED, Button, Uart, USB clock static void all_rcc_clk_enable(void) { __HAL_RCC_GPIOA_CLK_ENABLE(); // USB D+, D- __HAL_RCC_GPIOB_CLK_ENABLE(); // LED __HAL_RCC_GPIOC_CLK_ENABLE(); // Button -// __HAL_RCC_GPIOD_CLK_ENABLE(); // Uart tx, rx -// __HAL_RCC_USART3_CLK_ENABLE(); // Uart module + __HAL_RCC_GPIOD_CLK_ENABLE(); // Uart tx, rx + __HAL_RCC_USART3_CLK_ENABLE(); // Uart module } /* PWR, RCC, GPIO (All): AHB4 (D3 domain) @@ -170,6 +178,24 @@ void board_init(void) GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_HIGH; HAL_GPIO_Init(BUTTON_PORT, &GPIO_InitStruct); + // Uart + GPIO_InitStruct.Pin = UART_TX_PIN | UART_RX_PIN; + GPIO_InitStruct.Mode = GPIO_MODE_AF_PP; + GPIO_InitStruct.Pull = GPIO_PULLUP; + GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_VERY_HIGH; + GPIO_InitStruct.Alternate = UART_GPIO_AF; + HAL_GPIO_Init(UART_GPIO_PORT, &GPIO_InitStruct); + + UartHandle.Instance = UARTx; + UartHandle.Init.BaudRate = CFG_BOARD_UART_BAUDRATE; + UartHandle.Init.WordLength = UART_WORDLENGTH_8B; + UartHandle.Init.StopBits = UART_STOPBITS_1; + UartHandle.Init.Parity = UART_PARITY_NONE; + UartHandle.Init.HwFlowCtl = UART_HWCONTROL_NONE; + UartHandle.Init.Mode = UART_MODE_TX_RX; + UartHandle.Init.OverSampling = UART_OVERSAMPLING_16; + HAL_UART_Init(&UartHandle); + // USB Pin Init // PA9- VUSB, PA10- ID, PA11- DM, PA12- DP @@ -226,8 +252,8 @@ int board_uart_read(uint8_t* buf, int len) int board_uart_write(void const * buf, int len) { - (void) buf; (void) len; - return 0; + HAL_UART_Transmit(&UartHandle, (uint8_t*) buf, len, 0xffff); + return len; } diff --git a/hw/bsp/stm32h743nucleo/stm32h7xx_hal_conf.h b/hw/bsp/stm32h743nucleo/stm32h7xx_hal_conf.h index c58fdf75b..8548ca246 100644 --- a/hw/bsp/stm32h743nucleo/stm32h7xx_hal_conf.h +++ b/hw/bsp/stm32h743nucleo/stm32h7xx_hal_conf.h @@ -100,7 +100,7 @@ /* #define HAL_SRAM_MODULE_ENABLED */ /* #define HAL_SWPMI_MODULE_ENABLED */ /* #define HAL_TIM_MODULE_ENABLED */ -/* #define HAL_UART_MODULE_ENABLED */ +#define HAL_UART_MODULE_ENABLED */ /* #define HAL_USART_MODULE_ENABLED */ /* #define HAL_WWDG_MODULE_ENABLED */ @@ -211,6 +211,7 @@ #define USE_HAL_SPI_REGISTER_CALLBACKS 0U /* SPI register callback disabled */ #define USE_HAL_SWPMI_REGISTER_CALLBACKS 0U /* SWPMI register callback disabled */ #define USE_HAL_TIM_REGISTER_CALLBACKS 0U /* TIM register callback disabled */ +#define USE_HAL_UART_REGISTER_CALLBACKS 0U /* USART register callback disabled */ #define USE_HAL_WWDG_REGISTER_CALLBACKS 0U /* WWDG register callback disabled */ /* ########################### Ethernet Configuration ######################### */ From f6660c39a19dda4f4b3c00ce007dfd3e9fd47d7f Mon Sep 17 00:00:00 2001 From: Uwe Bonnes Date: Sun, 21 Jun 2020 20:53:52 +0200 Subject: [PATCH 25/48] Add Stm32F7xxdisco board support files Status with examples/device/cdc_msc: - make BOARD=stm32f723disco => OK - make BOARD=stm32f723disco PORT=1 => No Reaction - make BOARD=stm32f746disco => OK - make BOARD=stm32f746disco PORT=1 => Hangs during enumeration - make BOARD=stm32f769disco => Hangs during enumeration --- examples/readme.md | 4 + hw/bsp/stm32f723disco/STM32F723xE_FLASH.ld | 167 +++++++ hw/bsp/stm32f723disco/board.mk | 59 +++ hw/bsp/stm32f723disco/stm32f723disco.c | 300 ++++++++++++ hw/bsp/stm32f723disco/stm32f7xx_hal_conf.h | 472 +++++++++++++++++++ hw/bsp/stm32f746disco/STM32F746ZGTx_FLASH.ld | 167 +++++++ hw/bsp/stm32f746disco/board.mk | 59 +++ hw/bsp/stm32f746disco/stm32f746disco.c | 353 ++++++++++++++ hw/bsp/stm32f746disco/stm32f7xx_hal_conf.h | 472 +++++++++++++++++++ hw/bsp/stm32f769disco/STM32F769ZITx_FLASH.ld | 167 +++++++ hw/bsp/stm32f769disco/board.mk | 51 ++ hw/bsp/stm32f769disco/stm32f769disco.c | 297 ++++++++++++ hw/bsp/stm32f769disco/stm32f7xx_hal_conf.h | 472 +++++++++++++++++++ 13 files changed, 3040 insertions(+) create mode 100644 hw/bsp/stm32f723disco/STM32F723xE_FLASH.ld create mode 100644 hw/bsp/stm32f723disco/board.mk create mode 100644 hw/bsp/stm32f723disco/stm32f723disco.c create mode 100644 hw/bsp/stm32f723disco/stm32f7xx_hal_conf.h create mode 100644 hw/bsp/stm32f746disco/STM32F746ZGTx_FLASH.ld create mode 100644 hw/bsp/stm32f746disco/board.mk create mode 100644 hw/bsp/stm32f746disco/stm32f746disco.c create mode 100644 hw/bsp/stm32f746disco/stm32f7xx_hal_conf.h create mode 100644 hw/bsp/stm32f769disco/STM32F769ZITx_FLASH.ld create mode 100644 hw/bsp/stm32f769disco/board.mk create mode 100644 hw/bsp/stm32f769disco/stm32f769disco.c create mode 100644 hw/bsp/stm32f769disco/stm32f7xx_hal_conf.h diff --git a/examples/readme.md b/examples/readme.md index ca28d4881..790427cd2 100644 --- a/examples/readme.md +++ b/examples/readme.md @@ -37,6 +37,10 @@ To compile for debugging with debug symbols add DEBUG=1, for example ``` $ make BOARD=feather_nrf52840_express DEBUG=1 all +If a board has several ports, one port is choosen by default in the individual board.mk file. Choose another port with PORT=x. For example to select the HS port of a STM32F746Disco board, use: + +``` +$ make BOARD=stm32f746disco PORT=1 all ``` ### Debug Log diff --git a/hw/bsp/stm32f723disco/STM32F723xE_FLASH.ld b/hw/bsp/stm32f723disco/STM32F723xE_FLASH.ld new file mode 100644 index 000000000..8645ce5c5 --- /dev/null +++ b/hw/bsp/stm32f723disco/STM32F723xE_FLASH.ld @@ -0,0 +1,167 @@ +/* +***************************************************************************** +** + +** File : LinkerScript.ld +** +** Abstract : Linker script for STM32F723xE Device with +** 512KByte FLASH, 256KByte RAM +** +** Set heap size, stack size and stack location according +** to application requirements. +** +** Set memory bank area and size if external memory is used. +** +** Target : STMicroelectronics STM32 +** +** +** Distribution: The file is distributed as is, without any warranty +** of any kind. +** +** (c)Copyright Ac6. +** You may use this file as-is or modify it according to the needs of your +** project. Distribution of this file (unmodified or modified) is not +** permitted. Ac6 permit registered System Workbench for MCU users the +** rights to distribute the assembled, compiled & linked contents of this +** file as part of an application binary file, provided that it is built +** using the System Workbench for MCU toolchain. +** +***************************************************************************** +*/ + +/* Entry Point */ +ENTRY(Reset_Handler) + +/* Highest address of the user mode stack */ +_estack = 0x20040000; /* 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 = 0x460; /* required amount of stack */ + +/* Specify the memory areas */ +MEMORY +{ +RAM (xrw) : ORIGIN = 0x20000000, LENGTH = 256K +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 secion */ + _sbss = .; /* define a global symbol at bss start */ + __bss_start__ = _sbss; + *(.bss) + *(.bss*) + *(COMMON) + + . = ALIGN(4); + _ebss = .; /* define a global symbol at bss end */ + __bss_end__ = _ebss; + } >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/stm32f723disco/board.mk b/hw/bsp/stm32f723disco/board.mk new file mode 100644 index 000000000..2bd3b0756 --- /dev/null +++ b/hw/bsp/stm32f723disco/board.mk @@ -0,0 +1,59 @@ +PORT ?= 0 + +CFLAGS += \ + -flto \ + -mthumb \ + -mabi=aapcs \ + -mcpu=cortex-m7 \ + -mfloat-abi=hard \ + -mfpu=fpv5-d16 \ + -nostdlib -nostartfiles \ + -DSTM32F723xx \ + -DHSE_VALUE=25000000 \ + -DCFG_TUSB_MCU=OPT_MCU_STM32F7 \ + -DBOARD_DEVICE_RHPORT_NUM=$(PORT) + +ifeq ($(PORT), 1) +CFLAGS += -DBOARD_DEVICE_RHPORT_SPEED=OPT_MODE_HIGH_SPEED +$(info "PORT1 HS") +else +$(info "PORT0") +endif + +# mcu driver cause following warnings +CFLAGS += -Wno-error=shadow -Wno-error=cast-align + +ST_HAL_DRIVER = hw/mcu/st/st_driver/STM32F7xx_HAL_Driver +ST_CMSIS = hw/mcu/st/st_driver/CMSIS/Device/ST/STM32F7xx + +# All source paths should be relative to the top level. +LD_FILE = hw/bsp/$(BOARD)/STM32F723xE_FLASH.ld + +SRC_C += \ + $(ST_CMSIS)/Source/Templates/system_stm32f7xx.c \ + $(ST_HAL_DRIVER)/Src/stm32f7xx_hal.c \ + $(ST_HAL_DRIVER)/Src/stm32f7xx_hal_cortex.c \ + $(ST_HAL_DRIVER)/Src/stm32f7xx_hal_rcc.c \ + $(ST_HAL_DRIVER)/Src/stm32f7xx_hal_rcc_ex.c \ + $(ST_HAL_DRIVER)/Src/stm32f7xx_hal_gpio.c \ + $(ST_HAL_DRIVER)/Src/stm32f7xx_hal_uart.c \ + $(ST_HAL_DRIVER)/Src/stm32f7xx_hal_pwr_ex.c + +SRC_S += \ + $(ST_CMSIS)/Source/Templates/gcc/startup_stm32f723xx.s + +INC += \ + $(TOP)/hw/mcu/st/st_driver/CMSIS/Include \ + $(TOP)/$(ST_CMSIS)/Include \ + $(TOP)/$(ST_HAL_DRIVER)/Inc \ + $(TOP)/hw/bsp/$(BOARD) + +# For TinyUSB port source +VENDOR = st +CHIP_FAMILY = synopsys + +# For freeRTOS port source +FREERTOS_PORT = ARM_CM7/r0p1 + +# flash target using on-board stlink +flash: flash-stlink diff --git a/hw/bsp/stm32f723disco/stm32f723disco.c b/hw/bsp/stm32f723disco/stm32f723disco.c new file mode 100644 index 000000000..03057edc7 --- /dev/null +++ b/hw/bsp/stm32f723disco/stm32f723disco.c @@ -0,0 +1,300 @@ +/* + * The MIT License (MIT) + * + * Copyright (c) 2020 Uwe Bonnes (bon@elektron.ikp.physik.tu-darmstadt.de), + * Ha Thach (tinyusb.org) + * + * Permission is hereby granted, free of charge, to any person obtaining a copy + * of this software and associated documentation files (the "Software"), to deal + * in the Software without restriction, including without limitation the rights + * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell + * copies of the Software, and to permit persons to whom the Software is + * furnished to do so, subject to the following conditions: + * + * The above copyright notice and this permission notice shall be included in + * all copies or substantial portions of the Software. + * + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR + * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE + * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER + * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, + * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN + * THE SOFTWARE. + * + * This file is part of the TinyUSB stack. + */ + +#include "../board.h" + +#include "stm32f7xx_hal.h" + +//--------------------------------------------------------------------+ +// Forward USB interrupt events to TinyUSB IRQ Handler +//--------------------------------------------------------------------+ +void OTG_FS_IRQHandler(void) +{ + tud_int_handler(0); +} + +// Despite being call USB2_OTG +// OTG_HS is marked as RHPort1 by TinyUSB to be consistent across stm32 port +void OTG_HS_IRQHandler(void) +{ + tud_int_handler(1); +} + + +//--------------------------------------------------------------------+ +// MACRO TYPEDEF CONSTANT ENUM +//--------------------------------------------------------------------+ + +#define LED_PORT GPIOB +#define LED_PIN GPIO_PIN_1 +#define LED_STATE_ON 1 + +#define BUTTON_PORT GPIOA +#define BUTTON_PIN GPIO_PIN_0 +#define BUTTON_STATE_ACTIVE 1 + +#define UARTx USART6 +#define UART_GPIO_PORT GPIOC +#define UART_GPIO_AF GPIO_AF8_USART6 +#define UART_TX_PIN GPIO_PIN_6 +#define UART_RX_PIN GPIO_PIN_7 + +UART_HandleTypeDef UartHandle; + +// enable all LED, Button, Uart, USB clock +static void all_rcc_clk_enable(void) +{ + __HAL_RCC_GPIOA_CLK_ENABLE(); // USB D+, D- + __HAL_RCC_GPIOB_CLK_ENABLE(); // LED, OTG_HS + __HAL_RCC_GPIOC_CLK_ENABLE(); // Button + __HAL_RCC_GPIOD_CLK_ENABLE(); // Uart tx, rx + __HAL_RCC_USART6_CLK_ENABLE(); // Uart module +} + +/** + * @brief System Clock Configuration + * The system Clock is configured as follow : + * System Clock source = PLL (HSE) + * SYSCLK(Hz) = 216000000 + * HCLK(Hz) = 216000000 + * AHB Prescaler = 1 + * APB1 Prescaler = 4 + * APB2 Prescaler = 2 + * HSE Frequency(Hz) = 25000000 + * PLL_M = HSE_VALUE/1000000 + * PLL_N = 432 + * PLL_P = 2 + * PLL_Q = 9 + * VDD(V) = 3.3 + * Main regulator output voltage = Scale1 mode + * Flash Latency(WS) = 7 + * The USB clock configuration from PLLSAI: + * PLLSAIP = 8 + * PLLSAIN = 384 + * PLLSAIQ = 7 + * @param None + * @retval None + */ +void SystemClock_Config(void) +{ + RCC_ClkInitTypeDef RCC_ClkInitStruct; + RCC_OscInitTypeDef RCC_OscInitStruct; + + /* Enable Power Control clock */ + __HAL_RCC_PWR_CLK_ENABLE(); + + /* The voltage scaling allows optimizing the power consumption when the device is + clocked below the maximum system frequency, to update the voltage scaling value + regarding system frequency refer to product datasheet. */ + __HAL_PWR_VOLTAGESCALING_CONFIG(PWR_REGULATOR_VOLTAGE_SCALE1); + + /* Enable HSE Oscillator and activate PLL with HSE as source */ + RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_HSE; + RCC_OscInitStruct.HSEState = RCC_HSE_ON; + RCC_OscInitStruct.PLL.PLLState = RCC_PLL_ON; + RCC_OscInitStruct.PLL.PLLSource = RCC_PLLSOURCE_HSE; + RCC_OscInitStruct.PLL.PLLM = HSE_VALUE/1000000; + RCC_OscInitStruct.PLL.PLLN = 432; + RCC_OscInitStruct.PLL.PLLP = RCC_PLLP_DIV2; + RCC_OscInitStruct.PLL.PLLQ = 9; + HAL_RCC_OscConfig(&RCC_OscInitStruct); + + /* Activate the OverDrive to reach the 216 MHz Frequency */ + HAL_PWREx_EnableOverDrive(); + + /* Select PLL as system clock source and configure the HCLK, PCLK1 and PCLK2 clocks dividers */ + RCC_ClkInitStruct.ClockType = (RCC_CLOCKTYPE_SYSCLK | RCC_CLOCKTYPE_HCLK | RCC_CLOCKTYPE_PCLK1 | RCC_CLOCKTYPE_PCLK2); + RCC_ClkInitStruct.SYSCLKSource = RCC_SYSCLKSOURCE_PLLCLK; + RCC_ClkInitStruct.AHBCLKDivider = RCC_SYSCLK_DIV1; + RCC_ClkInitStruct.APB1CLKDivider = RCC_HCLK_DIV4; + RCC_ClkInitStruct.APB2CLKDivider = RCC_HCLK_DIV2; + + HAL_RCC_ClockConfig(&RCC_ClkInitStruct, FLASH_LATENCY_7); +} + +void board_init(void) +{ + + + SystemClock_Config(); + all_rcc_clk_enable(); + +#if CFG_TUSB_OS == OPT_OS_NONE + // 1ms tick timer + SysTick_Config(SystemCoreClock / 1000); +#endif + + GPIO_InitTypeDef GPIO_InitStruct; + + // LED + GPIO_InitStruct.Pin = LED_PIN; + GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_PP; + GPIO_InitStruct.Pull = GPIO_PULLUP; + GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_HIGH; + HAL_GPIO_Init(LED_PORT, &GPIO_InitStruct); + + // Button + GPIO_InitStruct.Pin = BUTTON_PIN; + GPIO_InitStruct.Mode = GPIO_MODE_INPUT; + GPIO_InitStruct.Pull = GPIO_NOPULL; + GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_HIGH; + HAL_GPIO_Init(BUTTON_PORT, &GPIO_InitStruct); + + // Uart + GPIO_InitStruct.Pin = UART_TX_PIN | UART_RX_PIN; + GPIO_InitStruct.Mode = GPIO_MODE_AF_PP; + GPIO_InitStruct.Pull = GPIO_PULLUP; + GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_HIGH; + GPIO_InitStruct.Alternate = UART_GPIO_AF; + HAL_GPIO_Init(UART_GPIO_PORT, &GPIO_InitStruct); + + UartHandle.Instance = UARTx; + UartHandle.Init.BaudRate = CFG_BOARD_UART_BAUDRATE; + UartHandle.Init.WordLength = UART_WORDLENGTH_8B; + UartHandle.Init.StopBits = UART_STOPBITS_1; + UartHandle.Init.Parity = UART_PARITY_NONE; + UartHandle.Init.HwFlowCtl = UART_HWCONTROL_NONE; + UartHandle.Init.Mode = UART_MODE_TX_RX; + UartHandle.Init.OverSampling = UART_OVERSAMPLING_16; + HAL_UART_Init(&UartHandle); + +#if BOARD_DEVICE_RHPORT_NUM == 0 + /* Configure USB FS GPIOs */ + /* Configure DM DP Pins */ + GPIO_InitStruct.Pin = (GPIO_PIN_11 | GPIO_PIN_12); + GPIO_InitStruct.Mode = GPIO_MODE_AF_PP; + GPIO_InitStruct.Pull = GPIO_NOPULL; + GPIO_InitStruct.Speed = GPIO_SPEED_HIGH; + GPIO_InitStruct.Alternate = GPIO_AF10_OTG_FS; + HAL_GPIO_Init(GPIOA, &GPIO_InitStruct); + + /* Configure VBUS Pin */ + GPIO_InitStruct.Pin = GPIO_PIN_9; + GPIO_InitStruct.Mode = GPIO_MODE_INPUT; + GPIO_InitStruct.Pull = GPIO_NOPULL; + HAL_GPIO_Init(GPIOA, &GPIO_InitStruct); + + /* Configure OTG-FS ID pin */ + GPIO_InitStruct.Pin = GPIO_PIN_10; + GPIO_InitStruct.Mode = GPIO_MODE_AF_OD; + GPIO_InitStruct.Pull = GPIO_PULLUP; + GPIO_InitStruct.Alternate = GPIO_AF10_OTG_FS; + HAL_GPIO_Init(GPIOA, &GPIO_InitStruct); + + /* Enable USB FS Clocks */ + __HAL_RCC_USB_OTG_FS_CLK_ENABLE(); + + // Enable VBUS sense (B device) via pin PA9 + USB_OTG_FS->GCCFG |= USB_OTG_GCCFG_VBDEN; + +#else + /* Configure USB HS GPIOs */ + /* Configure DM DP Pins */ + GPIO_InitStruct.Pin = (GPIO_PIN_14 | GPIO_PIN_15); + GPIO_InitStruct.Mode = GPIO_MODE_AF_PP; + GPIO_InitStruct.Pull = GPIO_NOPULL; + GPIO_InitStruct.Speed = GPIO_SPEED_VERY_HIGH; + GPIO_InitStruct.Alternate = GPIO_AF10_OTG_HS; + HAL_GPIO_Init(GPIOB, &GPIO_InitStruct); + + // Enable HS VBUS sense (B device) via pin PB13 + USB_OTG_HS->GCCFG |= USB_OTG_GCCFG_VBDEN; + + /* Configure OTG-HS ID pin */ + GPIO_InitStruct.Pin = GPIO_PIN_13; + GPIO_InitStruct.Mode = GPIO_MODE_AF_OD; + GPIO_InitStruct.Pull = GPIO_PULLUP; + GPIO_InitStruct.Alternate = GPIO_AF10_OTG_HS; + HAL_GPIO_Init(GPIOD, &GPIO_InitStruct); + + /* Enable USB HS Clocks */ + __HAL_RCC_USB_OTG_HS_CLK_ENABLE(); + + // Enable VBUS sense (B device) via pin PA9 + USB_OTG_HS->GCCFG &= ~USB_OTG_GCCFG_VBDEN; + + // B-peripheral session valid override enable + USB_OTG_HS->GOTGCTL |= USB_OTG_GOTGCTL_BVALOEN; + USB_OTG_HS->GOTGCTL |= USB_OTG_GOTGCTL_BVALOVAL; + + // Force device mode + USB_OTG_HS->GUSBCFG &= ~USB_OTG_GUSBCFG_FHMOD; + USB_OTG_HS->GUSBCFG |= USB_OTG_GUSBCFG_FDMOD; + +#endif +} + +//--------------------------------------------------------------------+ +// Board porting API +//--------------------------------------------------------------------+ + +void board_led_write(bool state) +{ + HAL_GPIO_WritePin(LED_PORT, LED_PIN, state); +} + +uint32_t board_button_read(void) +{ + return 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) +{ + HAL_UART_Transmit(&UartHandle, (uint8_t*) buf, len, 0xffff); + return len; +} + +#if CFG_TUSB_OS == OPT_OS_NONE +volatile uint32_t system_ticks = 0; +void SysTick_Handler (void) +{ + system_ticks++; +} + +uint32_t board_millis(void) +{ + return system_ticks; +} +#endif + +void HardFault_Handler (void) +{ + asm("bkpt"); +} + +// Required by __libc_init_array in startup code if we are compiling using +// -nostdlib/-nostartfiles. +void _init(void) +{ + +} diff --git a/hw/bsp/stm32f723disco/stm32f7xx_hal_conf.h b/hw/bsp/stm32f723disco/stm32f7xx_hal_conf.h new file mode 100644 index 000000000..03dec8f0d --- /dev/null +++ b/hw/bsp/stm32f723disco/stm32f7xx_hal_conf.h @@ -0,0 +1,472 @@ +/** + ****************************************************************************** + * @file stm32f7xx_hal_conf.h + * @author MCD Application Team + * @brief HAL configuration file. + ****************************************************************************** + * @attention + * + *

© Copyright (c) 2016 STMicroelectronics. + * All rights reserved.

+ * + * This software component is licensed by ST under BSD 3-Clause license, + * the "License"; You may not use this file except in compliance with the + * License. You may obtain a copy of the License at: + * opensource.org/licenses/BSD-3-Clause + * + ****************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __STM32F7xx_HAL_CONF_H +#define __STM32F7xx_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_CAN_MODULE_ENABLED */ +/* #define HAL_CAN_LEGACY_MODULE_ENABLED */ +/* #define HAL_CEC_MODULE_ENABLED */ +/* #define HAL_CRC_MODULE_ENABLED */ +/* #define HAL_CRYP_MODULE_ENABLED */ +/* #define HAL_DAC_MODULE_ENABLED */ +/* #define HAL_DCMI_MODULE_ENABLED */ +#define HAL_DMA_MODULE_ENABLED +/* #define HAL_DMA2D_MODULE_ENABLED */ +/* #define HAL_ETH_MODULE_ENABLED */ +#define HAL_FLASH_MODULE_ENABLED +/* #define HAL_NAND_MODULE_ENABLED */ +/* #define HAL_NOR_MODULE_ENABLED */ +/* #define HAL_SRAM_MODULE_ENABLED */ +/* #define HAL_SDRAM_MODULE_ENABLED */ +/* #define HAL_HASH_MODULE_ENABLED */ +#define HAL_GPIO_MODULE_ENABLED +/* #define HAL_I2C_MODULE_ENABLED */ +/* #define HAL_I2S_MODULE_ENABLED */ +/* #define HAL_IWDG_MODULE_ENABLED */ +/* #define HAL_LPTIM_MODULE_ENABLED */ +/* #define HAL_LTDC_MODULE_ENABLED */ +#define HAL_PWR_MODULE_ENABLED +/* #define HAL_QSPI_MODULE_ENABLED */ +#define HAL_RCC_MODULE_ENABLED +/* #define HAL_RNG_MODULE_ENABLED */ +/* #define HAL_RTC_MODULE_ENABLED */ +/* #define HAL_SAI_MODULE_ENABLED */ +/* #define HAL_SD_MODULE_ENABLED */ +/* #define HAL_SPDIFRX_MODULE_ENABLED */ +/* #define HAL_SPI_MODULE_ENABLED */ +/* #define HAL_TIM_MODULE_ENABLED */ +#define HAL_UART_MODULE_ENABLED +/* #define HAL_USART_MODULE_ENABLED */ +/* #define HAL_IRDA_MODULE_ENABLED */ +/* #define HAL_SMARTCARD_MODULE_ENABLED */ +/* #define HAL_WWDG_MODULE_ENABLED */ +#define HAL_CORTEX_MODULE_ENABLED +/* #define HAL_PCD_MODULE_ENABLED */ +/* #define HAL_HCD_MODULE_ENABLED */ +/* #define HAL_DFSDM_MODULE_ENABLED */ +/* #define HAL_DSI_MODULE_ENABLED */ +/* #define HAL_JPEG_MODULE_ENABLED */ +/* #define HAL_MDIOS_MODULE_ENABLED */ + + +/* ########################## HSE/HSI Values adaptation ##################### */ +/** + * @brief Adjust the value of External High Speed oscillator (HSE) used in your application. + * This value is used by the RCC HAL module to compute the system frequency + * (when HSE is used as system clock source, directly or through the PLL). + */ +#if !defined (HSE_VALUE) + #define HSE_VALUE ((uint32_t)8000000U) /*!< Value of the External oscillator in Hz */ +#endif /* HSE_VALUE */ + +#if !defined (HSE_STARTUP_TIMEOUT) + #define HSE_STARTUP_TIMEOUT ((uint32_t)100U) /*!< Time out for HSE start up, in ms */ +#endif /* HSE_STARTUP_TIMEOUT */ + +/** + * @brief Internal High Speed oscillator (HSI) value. + * This value is used by the RCC HAL module to compute the system frequency + * (when HSI is used as system clock source, directly or through the PLL). + */ +#if !defined (HSI_VALUE) + #define HSI_VALUE ((uint32_t)16000000U) /*!< Value of the Internal oscillator in Hz*/ +#endif /* HSI_VALUE */ + +/** + * @brief Internal Low Speed oscillator (LSI) value. + */ +#if !defined (LSI_VALUE) + #define LSI_VALUE ((uint32_t)32000U) /*!< 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. + */ +#if !defined (LSE_VALUE) + #define LSE_VALUE ((uint32_t)32768U) /*!< Value of the External Low Speed oscillator in Hz */ +#endif /* LSE_VALUE */ + +#if !defined (LSE_STARTUP_TIMEOUT) + #define LSE_STARTUP_TIMEOUT ((uint32_t)5000U) /*!< Time out for LSE start up, in ms */ +#endif /* LSE_STARTUP_TIMEOUT */ + +/** + * @brief External clock source for I2S peripheral + * This value is used by the I2S HAL module to compute the I2S clock source + * frequency, this source is inserted directly through I2S_CKIN pad. + */ +#if !defined (EXTERNAL_CLOCK_VALUE) + #define EXTERNAL_CLOCK_VALUE ((uint32_t)12288000U) /*!< Value of the Internal oscillator in Hz*/ +#endif /* EXTERNAL_CLOCK_VALUE */ + +/* Tip: To avoid modifying this file each time you need to use different HSE, + === you can define the HSE value in your toolchain compiler preprocessor. */ + +/* ########################### System Configuration ######################### */ +/** + * @brief This is the HAL system configuration section + */ +#define VDD_VALUE ((uint32_t)3300U) /*!< Value of VDD in mv */ +#define TICK_INT_PRIORITY ((uint32_t)0x0FU) /*!< tick interrupt priority */ +#define USE_RTOS 0U +#define PREFETCH_ENABLE 1U +#define ART_ACCLERATOR_ENABLE 1U /* To enable instruction cache and prefetch */ + +#define USE_HAL_ADC_REGISTER_CALLBACKS 0U /* ADC register callback disabled */ +#define USE_HAL_CAN_REGISTER_CALLBACKS 0U /* CAN register callback disabled */ +#define USE_HAL_CEC_REGISTER_CALLBACKS 0U /* CEC register callback disabled */ +#define USE_HAL_CRYP_REGISTER_CALLBACKS 0U /* CRYP register callback disabled */ +#define USE_HAL_DAC_REGISTER_CALLBACKS 0U /* DAC register callback disabled */ +#define USE_HAL_DCMI_REGISTER_CALLBACKS 0U /* DCMI register callback disabled */ +#define USE_HAL_DFSDM_REGISTER_CALLBACKS 0U /* DFSDM register callback disabled */ +#define USE_HAL_DMA2D_REGISTER_CALLBACKS 0U /* DMA2D register callback disabled */ +#define USE_HAL_DSI_REGISTER_CALLBACKS 0U /* DSI register callback disabled */ +#define USE_HAL_ETH_REGISTER_CALLBACKS 0U /* ETH register callback disabled */ +#define USE_HAL_HASH_REGISTER_CALLBACKS 0U /* HASH register callback disabled */ +#define USE_HAL_HCD_REGISTER_CALLBACKS 0U /* HCD register callback disabled */ +#define USE_HAL_I2C_REGISTER_CALLBACKS 0U /* I2C register callback disabled */ +#define USE_HAL_I2S_REGISTER_CALLBACKS 0U /* I2S register callback disabled */ +#define USE_HAL_IRDA_REGISTER_CALLBACKS 0U /* IRDA register callback disabled */ +#define USE_HAL_JPEG_REGISTER_CALLBACKS 0U /* JPEG register callback disabled */ +#define USE_HAL_LPTIM_REGISTER_CALLBACKS 0U /* LPTIM register callback disabled */ +#define USE_HAL_LTDC_REGISTER_CALLBACKS 0U /* LTDC register callback disabled */ +#define USE_HAL_MDIOS_REGISTER_CALLBACKS 0U /* MDIOS register callback disabled */ +#define USE_HAL_MMC_REGISTER_CALLBACKS 0U /* MMC register callback disabled */ +#define USE_HAL_NAND_REGISTER_CALLBACKS 0U /* NAND register callback disabled */ +#define USE_HAL_NOR_REGISTER_CALLBACKS 0U /* NOR register callback disabled */ +#define USE_HAL_PCD_REGISTER_CALLBACKS 0U /* PCD register callback disabled */ +#define USE_HAL_QSPI_REGISTER_CALLBACKS 0U /* QSPI register callback disabled */ +#define USE_HAL_RNG_REGISTER_CALLBACKS 0U /* RNG register callback disabled */ +#define USE_HAL_RTC_REGISTER_CALLBACKS 0U /* RTC register callback disabled */ +#define USE_HAL_SAI_REGISTER_CALLBACKS 0U /* SAI register callback disabled */ +#define USE_HAL_SD_REGISTER_CALLBACKS 0U /* SD register callback disabled */ +#define USE_HAL_SMARTCARD_REGISTER_CALLBACKS 0U /* SMARTCARD register callback disabled */ +#define USE_HAL_SDRAM_REGISTER_CALLBACKS 0U /* SDRAM register callback disabled */ +#define USE_HAL_SRAM_REGISTER_CALLBACKS 0U /* SRAM register callback disabled */ +#define USE_HAL_SPDIFRX_REGISTER_CALLBACKS 0U /* SPDIFRX register callback disabled */ +#define USE_HAL_SMBUS_REGISTER_CALLBACKS 0U /* SMBUS register callback disabled */ +#define USE_HAL_SPI_REGISTER_CALLBACKS 0U /* SPI register callback disabled */ +#define USE_HAL_TIM_REGISTER_CALLBACKS 0U /* TIM register callback disabled */ +#define USE_HAL_UART_REGISTER_CALLBACKS 0U /* UART register callback disabled */ +#define USE_HAL_USART_REGISTER_CALLBACKS 0U /* USART register callback disabled */ +#define USE_HAL_WWDG_REGISTER_CALLBACKS 0U /* WWDG register callback disabled */ + +/* ########################## Assert Selection ############################## */ +/** + * @brief Uncomment the line below to expanse the "assert_param" macro in the + * HAL drivers code + */ +/* #define USE_FULL_ASSERT 1 */ + +/* ################## Ethernet peripheral configuration for NUCLEO 144 board ##################### */ + +/* Section 1 : Ethernet peripheral configuration */ + +/* MAC ADDRESS: MAC_ADDR0:MAC_ADDR1:MAC_ADDR2:MAC_ADDR3:MAC_ADDR4:MAC_ADDR5 */ +#define MAC_ADDR0 2U +#define MAC_ADDR1 0U +#define MAC_ADDR2 0U +#define MAC_ADDR3 0U +#define MAC_ADDR4 0U +#define MAC_ADDR5 0U + +/* Definition of the Ethernet driver buffers size and count */ +#define ETH_RX_BUF_SIZE ETH_MAX_PACKET_SIZE /* buffer size for receive */ +#define ETH_TX_BUF_SIZE ETH_MAX_PACKET_SIZE /* buffer size for transmit */ +#define ETH_RXBUFNB ((uint32_t)5) /* 5 Rx buffers of size ETH_RX_BUF_SIZE */ +#define ETH_TXBUFNB ((uint32_t)5) /* 5 Tx buffers of size ETH_TX_BUF_SIZE */ + +/* Section 2: PHY configuration section */ +/* LAN8742A PHY Address*/ +#define LAN8742A_PHY_ADDRESS 0x00 +/* PHY Reset delay these values are based on a 1 ms Systick interrupt*/ +#define PHY_RESET_DELAY ((uint32_t)0x00000FFF) +/* PHY Configuration delay */ +#define PHY_CONFIG_DELAY ((uint32_t)0x00000FFF) + +#define PHY_READ_TO ((uint32_t)0x0000FFFF) +#define PHY_WRITE_TO ((uint32_t)0x0000FFFF) + +/* Section 3: Common PHY Registers */ + +#define PHY_BCR ((uint16_t)0x00) /*!< Transceiver Basic Control Register */ +#define PHY_BSR ((uint16_t)0x01) /*!< Transceiver Basic Status Register */ + +#define PHY_RESET ((uint16_t)0x8000) /*!< PHY Reset */ +#define PHY_LOOPBACK ((uint16_t)0x4000) /*!< Select loop-back mode */ +#define PHY_FULLDUPLEX_100M ((uint16_t)0x2100) /*!< Set the full-duplex mode at 100 Mb/s */ +#define PHY_HALFDUPLEX_100M ((uint16_t)0x2000) /*!< Set the half-duplex mode at 100 Mb/s */ +#define PHY_FULLDUPLEX_10M ((uint16_t)0x0100) /*!< Set the full-duplex mode at 10 Mb/s */ +#define PHY_HALFDUPLEX_10M ((uint16_t)0x0000) /*!< Set the half-duplex mode at 10 Mb/s */ +#define PHY_AUTONEGOTIATION ((uint16_t)0x1000) /*!< Enable auto-negotiation function */ +#define PHY_RESTART_AUTONEGOTIATION ((uint16_t)0x0200) /*!< Restart auto-negotiation function */ +#define PHY_POWERDOWN ((uint16_t)0x0800) /*!< Select the power down mode */ +#define PHY_ISOLATE ((uint16_t)0x0400) /*!< Isolate PHY from MII */ + +#define PHY_AUTONEGO_COMPLETE ((uint16_t)0x0020) /*!< Auto-Negotiation process completed */ +#define PHY_LINKED_STATUS ((uint16_t)0x0004) /*!< Valid link established */ +#define PHY_JABBER_DETECTION ((uint16_t)0x0002) /*!< Jabber condition detected */ + +/* Section 4: Extended PHY Registers */ + +#define PHY_SR ((uint16_t)0x1F) /*!< PHY special control/ status register Offset */ + +#define PHY_SPEED_STATUS ((uint16_t)0x0004) /*!< PHY Speed mask */ +#define PHY_DUPLEX_STATUS ((uint16_t)0x0010) /*!< PHY Duplex mask */ + + +#define PHY_ISFR ((uint16_t)0x1D) /*!< PHY Interrupt Source Flag register Offset */ +#define PHY_ISFR_INT4 ((uint16_t)0x0010) /*!< PHY Link down inturrupt */ + +/* ################## 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 1U + +/* Includes ------------------------------------------------------------------*/ +/** + * @brief Include module's header file + */ + +#ifdef HAL_RCC_MODULE_ENABLED + #include "stm32f7xx_hal_rcc.h" +#endif /* HAL_RCC_MODULE_ENABLED */ + +#ifdef HAL_GPIO_MODULE_ENABLED + #include "stm32f7xx_hal_gpio.h" +#endif /* HAL_GPIO_MODULE_ENABLED */ + +#ifdef HAL_DMA_MODULE_ENABLED + #include "stm32f7xx_hal_dma.h" +#endif /* HAL_DMA_MODULE_ENABLED */ + +#ifdef HAL_CORTEX_MODULE_ENABLED + #include "stm32f7xx_hal_cortex.h" +#endif /* HAL_CORTEX_MODULE_ENABLED */ + +#ifdef HAL_ADC_MODULE_ENABLED + #include "stm32f7xx_hal_adc.h" +#endif /* HAL_ADC_MODULE_ENABLED */ + +#ifdef HAL_CAN_MODULE_ENABLED + #include "stm32f7xx_hal_can.h" +#endif /* HAL_CAN_MODULE_ENABLED */ + +#ifdef HAL_CAN_LEGACY_MODULE_ENABLED + #include "stm32f7xx_hal_can_legacy.h" +#endif /* HAL_CAN_LEGACY_MODULE_ENABLED */ + +#ifdef HAL_CEC_MODULE_ENABLED + #include "stm32f7xx_hal_cec.h" +#endif /* HAL_CEC_MODULE_ENABLED */ + +#ifdef HAL_CRC_MODULE_ENABLED + #include "stm32f7xx_hal_crc.h" +#endif /* HAL_CRC_MODULE_ENABLED */ + +#ifdef HAL_CRYP_MODULE_ENABLED + #include "stm32f7xx_hal_cryp.h" +#endif /* HAL_CRYP_MODULE_ENABLED */ + +#ifdef HAL_DMA2D_MODULE_ENABLED + #include "stm32f7xx_hal_dma2d.h" +#endif /* HAL_DMA2D_MODULE_ENABLED */ + +#ifdef HAL_DAC_MODULE_ENABLED + #include "stm32f7xx_hal_dac.h" +#endif /* HAL_DAC_MODULE_ENABLED */ + +#ifdef HAL_DCMI_MODULE_ENABLED + #include "stm32f7xx_hal_dcmi.h" +#endif /* HAL_DCMI_MODULE_ENABLED */ + +#ifdef HAL_ETH_MODULE_ENABLED + #include "stm32f7xx_hal_eth.h" +#endif /* HAL_ETH_MODULE_ENABLED */ + +#ifdef HAL_FLASH_MODULE_ENABLED + #include "stm32f7xx_hal_flash.h" +#endif /* HAL_FLASH_MODULE_ENABLED */ + +#ifdef HAL_SRAM_MODULE_ENABLED + #include "stm32f7xx_hal_sram.h" +#endif /* HAL_SRAM_MODULE_ENABLED */ + +#ifdef HAL_NOR_MODULE_ENABLED + #include "stm32f7xx_hal_nor.h" +#endif /* HAL_NOR_MODULE_ENABLED */ + +#ifdef HAL_NAND_MODULE_ENABLED + #include "stm32f7xx_hal_nand.h" +#endif /* HAL_NAND_MODULE_ENABLED */ + +#ifdef HAL_SDRAM_MODULE_ENABLED + #include "stm32f7xx_hal_sdram.h" +#endif /* HAL_SDRAM_MODULE_ENABLED */ + +#ifdef HAL_HASH_MODULE_ENABLED + #include "stm32f7xx_hal_hash.h" +#endif /* HAL_HASH_MODULE_ENABLED */ + +#ifdef HAL_I2C_MODULE_ENABLED + #include "stm32f7xx_hal_i2c.h" +#endif /* HAL_I2C_MODULE_ENABLED */ + +#ifdef HAL_I2S_MODULE_ENABLED + #include "stm32f7xx_hal_i2s.h" +#endif /* HAL_I2S_MODULE_ENABLED */ + +#ifdef HAL_IWDG_MODULE_ENABLED + #include "stm32f7xx_hal_iwdg.h" +#endif /* HAL_IWDG_MODULE_ENABLED */ + +#ifdef HAL_LPTIM_MODULE_ENABLED + #include "stm32f7xx_hal_lptim.h" +#endif /* HAL_LPTIM_MODULE_ENABLED */ + +#ifdef HAL_LTDC_MODULE_ENABLED + #include "stm32f7xx_hal_ltdc.h" +#endif /* HAL_LTDC_MODULE_ENABLED */ + +#ifdef HAL_PWR_MODULE_ENABLED + #include "stm32f7xx_hal_pwr.h" +#endif /* HAL_PWR_MODULE_ENABLED */ + +#ifdef HAL_QSPI_MODULE_ENABLED + #include "stm32f7xx_hal_qspi.h" +#endif /* HAL_QSPI_MODULE_ENABLED */ + +#ifdef HAL_RNG_MODULE_ENABLED + #include "stm32f7xx_hal_rng.h" +#endif /* HAL_RNG_MODULE_ENABLED */ + +#ifdef HAL_RTC_MODULE_ENABLED + #include "stm32f7xx_hal_rtc.h" +#endif /* HAL_RTC_MODULE_ENABLED */ + +#ifdef HAL_SAI_MODULE_ENABLED + #include "stm32f7xx_hal_sai.h" +#endif /* HAL_SAI_MODULE_ENABLED */ + +#ifdef HAL_SD_MODULE_ENABLED + #include "stm32f7xx_hal_sd.h" +#endif /* HAL_SD_MODULE_ENABLED */ + +#ifdef HAL_SPDIFRX_MODULE_ENABLED + #include "stm32f7xx_hal_spdifrx.h" +#endif /* HAL_SPDIFRX_MODULE_ENABLED */ + +#ifdef HAL_SPI_MODULE_ENABLED + #include "stm32f7xx_hal_spi.h" +#endif /* HAL_SPI_MODULE_ENABLED */ + +#ifdef HAL_TIM_MODULE_ENABLED + #include "stm32f7xx_hal_tim.h" +#endif /* HAL_TIM_MODULE_ENABLED */ + +#ifdef HAL_UART_MODULE_ENABLED + #include "stm32f7xx_hal_uart.h" +#endif /* HAL_UART_MODULE_ENABLED */ + +#ifdef HAL_USART_MODULE_ENABLED + #include "stm32f7xx_hal_usart.h" +#endif /* HAL_USART_MODULE_ENABLED */ + +#ifdef HAL_IRDA_MODULE_ENABLED + #include "stm32f7xx_hal_irda.h" +#endif /* HAL_IRDA_MODULE_ENABLED */ + +#ifdef HAL_SMARTCARD_MODULE_ENABLED + #include "stm32f7xx_hal_smartcard.h" +#endif /* HAL_SMARTCARD_MODULE_ENABLED */ + +#ifdef HAL_WWDG_MODULE_ENABLED + #include "stm32f7xx_hal_wwdg.h" +#endif /* HAL_WWDG_MODULE_ENABLED */ + +#ifdef HAL_PCD_MODULE_ENABLED + #include "stm32f7xx_hal_pcd.h" +#endif /* HAL_PCD_MODULE_ENABLED */ + +#ifdef HAL_HCD_MODULE_ENABLED + #include "stm32f7xx_hal_hcd.h" +#endif /* HAL_HCD_MODULE_ENABLED */ + +#ifdef HAL_DFSDM_MODULE_ENABLED + #include "stm32f7xx_hal_dfsdm.h" +#endif /* HAL_DFSDM_MODULE_ENABLED */ + +#ifdef HAL_DSI_MODULE_ENABLED + #include "stm32f7xx_hal_dsi.h" +#endif /* HAL_DSI_MODULE_ENABLED */ + +#ifdef HAL_JPEG_MODULE_ENABLED + #include "stm32f7xx_hal_jpeg.h" +#endif /* HAL_JPEG_MODULE_ENABLED */ + +#ifdef HAL_MDIOS_MODULE_ENABLED + #include "stm32f7xx_hal_mdios.h" +#endif /* HAL_MDIOS_MODULE_ENABLED */ + +/* Exported macro ------------------------------------------------------------*/ +#ifdef USE_FULL_ASSERT +/** + * @brief The assert_param macro is used for function's parameters check. + * @param expr: If expr is false, it calls assert_failed function + * which reports the name of the source file and the source + * line number of the call that failed. + * If expr is true, it returns no value. + * @retval None + */ + #define assert_param(expr) ((expr) ? (void)0 : assert_failed((uint8_t *)__FILE__, __LINE__)) +/* Exported functions ------------------------------------------------------- */ + void assert_failed(uint8_t* file, uint32_t line); +#else + #define assert_param(expr) ((void)0U) +#endif /* USE_FULL_ASSERT */ + + +#ifdef __cplusplus +} +#endif + +#endif /* __STM32F7xx_HAL_CONF_H */ + + +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/hw/bsp/stm32f746disco/STM32F746ZGTx_FLASH.ld b/hw/bsp/stm32f746disco/STM32F746ZGTx_FLASH.ld new file mode 100644 index 000000000..045ec76f9 --- /dev/null +++ b/hw/bsp/stm32f746disco/STM32F746ZGTx_FLASH.ld @@ -0,0 +1,167 @@ +/* +***************************************************************************** +** + +** File : LinkerScript.ld +** +** Abstract : Linker script for STM32F746ZGTx Device with +** 1024KByte FLASH, 320KByte RAM +** +** Set heap size, stack size and stack location according +** to application requirements. +** +** Set memory bank area and size if external memory is used. +** +** Target : STMicroelectronics STM32 +** +** +** Distribution: The file is distributed as is, without any warranty +** of any kind. +** +** (c)Copyright Ac6. +** You may use this file as-is or modify it according to the needs of your +** project. Distribution of this file (unmodified or modified) is not +** permitted. Ac6 permit registered System Workbench for MCU users the +** rights to distribute the assembled, compiled & linked contents of this +** file as part of an application binary file, provided that it is built +** using the System Workbench for MCU toolchain. +** +***************************************************************************** +*/ + +/* Entry Point */ +ENTRY(Reset_Handler) + +/* Highest address of the user mode stack */ +_estack = 0x20050000; /* 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 = 0x460; /* required amount of stack */ + +/* Specify the memory areas */ +MEMORY +{ +RAM (xrw) : ORIGIN = 0x20000000, LENGTH = 320K +FLASH (rx) : ORIGIN = 0x8000000, LENGTH = 1024K +} + +/* 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 secion */ + _sbss = .; /* define a global symbol at bss start */ + __bss_start__ = _sbss; + *(.bss) + *(.bss*) + *(COMMON) + + . = ALIGN(4); + _ebss = .; /* define a global symbol at bss end */ + __bss_end__ = _ebss; + } >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/stm32f746disco/board.mk b/hw/bsp/stm32f746disco/board.mk new file mode 100644 index 000000000..76a54cdfd --- /dev/null +++ b/hw/bsp/stm32f746disco/board.mk @@ -0,0 +1,59 @@ +PORT ?= 0 + +CFLAGS += \ + -flto \ + -mthumb \ + -mabi=aapcs \ + -mcpu=cortex-m7 \ + -mfloat-abi=hard \ + -mfpu=fpv5-d16 \ + -nostdlib -nostartfiles \ + -DSTM32F746xx \ + -DHSE_VALUE=25000000 \ + -DCFG_TUSB_MCU=OPT_MCU_STM32F7 \ + -DBOARD_DEVICE_RHPORT_NUM=$(PORT) + +ifeq ($(PORT), 1) +CFLAGS += -DBOARD_DEVICE_RHPORT_SPEED=OPT_MODE_HIGH_SPEED +$(info "PORT1 HS") +else +$(info "PORT0") +endif + +# mcu driver cause following warnings +CFLAGS += -Wno-error=shadow -Wno-error=cast-align + +ST_HAL_DRIVER = hw/mcu/st/st_driver/STM32F7xx_HAL_Driver +ST_CMSIS = hw/mcu/st/st_driver/CMSIS/Device/ST/STM32F7xx + +# All source paths should be relative to the top level. +LD_FILE = hw/bsp/$(BOARD)/STM32F746ZGTx_FLASH.ld + +SRC_C += \ + $(ST_CMSIS)/Source/Templates/system_stm32f7xx.c \ + $(ST_HAL_DRIVER)/Src/stm32f7xx_hal.c \ + $(ST_HAL_DRIVER)/Src/stm32f7xx_hal_cortex.c \ + $(ST_HAL_DRIVER)/Src/stm32f7xx_hal_rcc.c \ + $(ST_HAL_DRIVER)/Src/stm32f7xx_hal_rcc_ex.c \ + $(ST_HAL_DRIVER)/Src/stm32f7xx_hal_gpio.c \ + $(ST_HAL_DRIVER)/Src/stm32f7xx_hal_uart.c \ + $(ST_HAL_DRIVER)/Src/stm32f7xx_hal_pwr_ex.c + +SRC_S += \ + $(ST_CMSIS)/Source/Templates/gcc/startup_stm32f746xx.s + +INC += \ + $(TOP)/hw/mcu/st/st_driver/CMSIS/Include \ + $(TOP)/$(ST_CMSIS)/Include \ + $(TOP)/$(ST_HAL_DRIVER)/Inc \ + $(TOP)/hw/bsp/$(BOARD) + +# For TinyUSB port source +VENDOR = st +CHIP_FAMILY = synopsys + +# For freeRTOS port source +FREERTOS_PORT = ARM_CM7/r0p1 + +# flash target using on-board stlink +flash: flash-stlink diff --git a/hw/bsp/stm32f746disco/stm32f746disco.c b/hw/bsp/stm32f746disco/stm32f746disco.c new file mode 100644 index 000000000..c90182fcf --- /dev/null +++ b/hw/bsp/stm32f746disco/stm32f746disco.c @@ -0,0 +1,353 @@ +/* + * The MIT License (MIT) + * + * Copyright (c) 2020 Uwe Bonnes (bon@elektron.ikp.physik.tu-darmstadt.de), + * Ha Thach (tinyusb.org) + * + * Permission is hereby granted, free of charge, to any person obtaining a copy + * of this software and associated documentation files (the "Software"), to deal + * in the Software without restriction, including without limitation the rights + * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell + * copies of the Software, and to permit persons to whom the Software is + * furnished to do so, subject to the following conditions: + * + * The above copyright notice and this permission notice shall be included in + * all copies or substantial portions of the Software. + * + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR + * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE + * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER + * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, + * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN + * THE SOFTWARE. + * + * This file is part of the TinyUSB stack. + */ + +#include "../board.h" + +#include "stm32f7xx_hal.h" + +//--------------------------------------------------------------------+ +// Forward USB interrupt events to TinyUSB IRQ Handler +//--------------------------------------------------------------------+ + +// Despite being call USB2_OTG +// OTG_FS is marked as RHPort0 by TinyUSB to be consistent across stm32 port +void OTG_FS_IRQHandler(void) +{ + tud_int_handler(0); +} + +// Despite being call USB2_OTG +// OTG_HS is marked as RHPort1 by TinyUSB to be consistent across stm32 port +void OTG_HS_IRQHandler(void) +{ + tud_int_handler(1); +} + + +//--------------------------------------------------------------------+ +// MACRO TYPEDEF CONSTANT ENUM +//--------------------------------------------------------------------+ + +#define LED_PORT GPIOI +#define LED_PIN GPIO_PIN_1 +#define LED_STATE_ON 1 + +#define BUTTON_PORT GPIOI +#define BUTTON_PIN GPIO_PIN_11 +#define BUTTON_STATE_ACTIVE 1 + +#define UARTx USART1 +#define UART_TX_GPIO_PORT GPIOA +#define UART_RX_GPIO_PORT GPIOB +#define UART_TX_GPIO_AF GPIO_AF7_USART1 +#define UART_RX_GPIO_AF GPIO_AF7_USART1 +#define UART_TX_PIN GPIO_PIN_9 +#define UART_RX_PIN GPIO_PIN_7 + +UART_HandleTypeDef UartHandle; + +// enable all LED, Button, Uart, USB clock +static void all_rcc_clk_enable(void) +{ + __HAL_RCC_GPIOA_CLK_ENABLE(); // USB D+, D- + __HAL_RCC_GPIOB_CLK_ENABLE(); // Uart rx + __HAL_RCC_GPIOI_CLK_ENABLE(); // Button + __HAL_RCC_USART1_CLK_ENABLE(); // Uart module +} + +/** + * @brief System Clock Configuration + * The system Clock is configured as follow : + * System Clock source = PLL (HSE) + * SYSCLK(Hz) = 216000000 + * HCLK(Hz) = 216000000 + * AHB Prescaler = 1 + * APB1 Prescaler = 4 + * APB2 Prescaler = 2 + * HSE Frequency(Hz) = 25000000 + * PLL_M = HSE_VALUE/1000000 + * PLL_N = 432 + * PLL_P = 2 + * PLL_Q = 9 + * VDD(V) = 3.3 + * Main regulator output voltage = Scale1 mode + * Flash Latency(WS) = 7 + * The USB clock configuration from PLLSAI: + * PLLSAIP = 8 + * PLLSAIN = 384 + * PLLSAIQ = 7 + * @param None + * @retval None + */ +void SystemClock_Config(void) +{ + RCC_ClkInitTypeDef RCC_ClkInitStruct; + RCC_OscInitTypeDef RCC_OscInitStruct; + + /* Enable Power Control clock */ + __HAL_RCC_PWR_CLK_ENABLE(); + + /* The voltage scaling allows optimizing the power consumption when the device is + clocked below the maximum system frequency, to update the voltage scaling value + regarding system frequency refer to product datasheet. */ + __HAL_PWR_VOLTAGESCALING_CONFIG(PWR_REGULATOR_VOLTAGE_SCALE1); + + /* Enable HSE Oscillator and activate PLL with HSE as source */ + RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_HSE; + RCC_OscInitStruct.HSEState = RCC_HSE_BYPASS; + RCC_OscInitStruct.PLL.PLLState = RCC_PLL_ON; + RCC_OscInitStruct.PLL.PLLSource = RCC_PLLSOURCE_HSE; + RCC_OscInitStruct.PLL.PLLM = HSE_VALUE/1000000; + RCC_OscInitStruct.PLL.PLLN = 432; + RCC_OscInitStruct.PLL.PLLP = RCC_PLLP_DIV2; + RCC_OscInitStruct.PLL.PLLQ = 9; + HAL_RCC_OscConfig(&RCC_OscInitStruct); + + /* Activate the OverDrive to reach the 216 MHz Frequency */ + HAL_PWREx_EnableOverDrive(); + + /* Select PLL as system clock source and configure the HCLK, PCLK1 and PCLK2 clocks dividers */ + RCC_ClkInitStruct.ClockType = (RCC_CLOCKTYPE_SYSCLK | RCC_CLOCKTYPE_HCLK | RCC_CLOCKTYPE_PCLK1 | RCC_CLOCKTYPE_PCLK2); + RCC_ClkInitStruct.SYSCLKSource = RCC_SYSCLKSOURCE_PLLCLK; + RCC_ClkInitStruct.AHBCLKDivider = RCC_SYSCLK_DIV1; + RCC_ClkInitStruct.APB1CLKDivider = RCC_HCLK_DIV4; + RCC_ClkInitStruct.APB2CLKDivider = RCC_HCLK_DIV2; + + HAL_RCC_ClockConfig(&RCC_ClkInitStruct, FLASH_LATENCY_7); +} + +void board_init(void) +{ + + + SystemClock_Config(); + all_rcc_clk_enable(); + +#if CFG_TUSB_OS == OPT_OS_NONE + // 1ms tick timer + SysTick_Config(SystemCoreClock / 1000); +#endif + + GPIO_InitTypeDef GPIO_InitStruct; + + // LED + GPIO_InitStruct.Pin = LED_PIN; + GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_PP; + GPIO_InitStruct.Pull = GPIO_PULLUP; + GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_HIGH; + HAL_GPIO_Init(LED_PORT, &GPIO_InitStruct); + + // Button + GPIO_InitStruct.Pin = BUTTON_PIN; + GPIO_InitStruct.Mode = GPIO_MODE_INPUT; + GPIO_InitStruct.Pull = GPIO_NOPULL; + GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_HIGH; + HAL_GPIO_Init(BUTTON_PORT, &GPIO_InitStruct); + + // Uart TX + GPIO_InitStruct.Pin = UART_TX_PIN ; + GPIO_InitStruct.Mode = GPIO_MODE_AF_PP; + GPIO_InitStruct.Pull = GPIO_PULLUP; + GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_HIGH; + GPIO_InitStruct.Alternate = UART_TX_GPIO_AF; + HAL_GPIO_Init(UART_TX_GPIO_PORT, &GPIO_InitStruct); + + // Uart RX + GPIO_InitStruct.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_RX_GPIO_AF; + HAL_GPIO_Init(UART_RX_GPIO_PORT, &GPIO_InitStruct); + + UartHandle.Instance = UARTx; + UartHandle.Init.BaudRate = CFG_BOARD_UART_BAUDRATE; + UartHandle.Init.WordLength = UART_WORDLENGTH_8B; + UartHandle.Init.StopBits = UART_STOPBITS_1; + UartHandle.Init.Parity = UART_PARITY_NONE; + UartHandle.Init.HwFlowCtl = UART_HWCONTROL_NONE; + UartHandle.Init.Mode = UART_MODE_TX_RX; + UartHandle.Init.OverSampling = UART_OVERSAMPLING_16; + HAL_UART_Init(&UartHandle); + +#if BOARD_DEVICE_RHPORT_NUM == 0 + // Despite being call USB2_OTG + // OTG_FS is marked as RHPort0 by TinyUSB to be consistent across stm32 port + // PA9 VUSB, PA10 ID, PA11 DM, PA12 DP + + /* Configure USB FS GPIOs */ + /* Configure DM DP Pins */ + GPIO_InitStruct.Pin = (GPIO_PIN_11 | GPIO_PIN_12); + GPIO_InitStruct.Mode = GPIO_MODE_AF_PP; + GPIO_InitStruct.Pull = GPIO_NOPULL; + GPIO_InitStruct.Speed = GPIO_SPEED_HIGH; + GPIO_InitStruct.Alternate = GPIO_AF10_OTG_FS; + HAL_GPIO_Init(GPIOA, &GPIO_InitStruct); + + /* Configure VBUS Pin collides with USART TX*/ +// GPIO_InitStruct.Pin = GPIO_PIN_9; +// GPIO_InitStruct.Mode = GPIO_MODE_INPUT; +// GPIO_InitStruct.Pull = GPIO_NOPULL; +// HAL_GPIO_Init(GPIOA, &GPIO_InitStruct); + + /* Configure OTG-FS ID pin */ + GPIO_InitStruct.Pin = GPIO_PIN_10; + GPIO_InitStruct.Mode = GPIO_MODE_AF_OD; + GPIO_InitStruct.Pull = GPIO_PULLUP; + GPIO_InitStruct.Alternate = GPIO_AF10_OTG_FS; + HAL_GPIO_Init(GPIOA, &GPIO_InitStruct); + + /* Enable USB FS Clocks */ + __HAL_RCC_USB_OTG_FS_CLK_ENABLE(); + + // Enable VBUS sense (B device) via pin PA9 +// USB_OTG_FS->GCCFG |= USB_OTG_GCCFG_VBDEN; +#define DEVICE_BASE (USB_OTG_DeviceTypeDef *) (USB_OTG_FS_PERIPH_BASE + USB_OTG_DEVICE_BASE) + USB_OTG_DeviceTypeDef * dev = DEVICE_BASE; + dev->DCTL |= USB_OTG_DCTL_SDIS; + + /* Deactivate VBUS Sensing B */ + USB_OTG_FS->GCCFG &= ~USB_OTG_GCCFG_VBDEN; + + /* B-peripheral session valid override enable */ + USB_OTG_FS->GOTGCTL |= USB_OTG_GOTGCTL_BVALOEN; + USB_OTG_FS->GOTGCTL |= USB_OTG_GOTGCTL_BVALOVAL; +#elif BOARD_DEVICE_RHPORT_NUM == 1 + // Despite being call USB2_OTG + // OTG_HS is marked as RHPort1 by TinyUSB to be consistent across stm32 port + __GPIOA_CLK_ENABLE(); + __GPIOB_CLK_ENABLE(); + __GPIOC_CLK_ENABLE(); + __GPIOH_CLK_ENABLE(); + + /* ULPI CK */ + GPIO_InitStruct.Pin = GPIO_PIN_5; + GPIO_InitStruct.Mode = GPIO_MODE_AF_PP; + GPIO_InitStruct.Pull = GPIO_NOPULL; + GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_HIGH; + GPIO_InitStruct.Alternate = GPIO_AF10_OTG_HS; + HAL_GPIO_Init(GPIOA, &GPIO_InitStruct); + + /* ULPI D0 */ + GPIO_InitStruct.Pin = GPIO_PIN_3; + GPIO_InitStruct.Mode = GPIO_MODE_AF_PP; + GPIO_InitStruct.Pull = GPIO_NOPULL; + GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_HIGH; + GPIO_InitStruct.Alternate = GPIO_AF10_OTG_HS; + HAL_GPIO_Init(GPIOA, &GPIO_InitStruct); + + /* ULPI D1 D2 D3 D4 D5 D6 D7 */ + GPIO_InitStruct.Pin = GPIO_PIN_0 | GPIO_PIN_1 | GPIO_PIN_10 | GPIO_PIN_11 | GPIO_PIN_12 | GPIO_PIN_13 | GPIO_PIN_5; + GPIO_InitStruct.Mode = GPIO_MODE_AF_PP; + GPIO_InitStruct.Pull = GPIO_NOPULL; + GPIO_InitStruct.Alternate = GPIO_AF10_OTG_HS; + HAL_GPIO_Init(GPIOB, &GPIO_InitStruct); + + /* ULPI STP DIR */ + GPIO_InitStruct.Pin = GPIO_PIN_0 | GPIO_PIN_2; + GPIO_InitStruct.Mode = GPIO_MODE_AF_PP; + GPIO_InitStruct.Pull = GPIO_NOPULL; + GPIO_InitStruct.Alternate = GPIO_AF10_OTG_HS; + HAL_GPIO_Init(GPIOC, &GPIO_InitStruct); + + /* NXT */ + GPIO_InitStruct.Pin = GPIO_PIN_4; + GPIO_InitStruct.Mode = GPIO_MODE_AF_PP; + GPIO_InitStruct.Pull = GPIO_NOPULL; + GPIO_InitStruct.Alternate = GPIO_AF10_OTG_HS; + HAL_GPIO_Init(GPIOH, &GPIO_InitStruct); + + // Enable ULPI clock + __HAL_RCC_USB_OTG_HS_ULPI_CLK_ENABLE(); + + /* Enable USB HS Clocks */ + __HAL_RCC_USB_OTG_HS_CLK_ENABLE(); + + // No VBUS sense + USB_OTG_HS->GCCFG &= ~USB_OTG_GCCFG_VBDEN; + + // B-peripheral session valid override enable + USB_OTG_HS->GOTGCTL |= USB_OTG_GOTGCTL_BVALOEN; + USB_OTG_HS->GOTGCTL |= USB_OTG_GOTGCTL_BVALOVAL; + + // Force device mode + USB_OTG_HS->GUSBCFG &= ~USB_OTG_GUSBCFG_FHMOD; + USB_OTG_HS->GUSBCFG |= USB_OTG_GUSBCFG_FDMOD; + +#endif // rhport = 1 +} + +//--------------------------------------------------------------------+ +// Board porting API +//--------------------------------------------------------------------+ + +void board_led_write(bool state) +{ + HAL_GPIO_WritePin(LED_PORT, LED_PIN, state); +} + +uint32_t board_button_read(void) +{ + return 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) +{ + HAL_UART_Transmit(&UartHandle, (uint8_t*) buf, len, 0xffff); + return len; +} + +#if CFG_TUSB_OS == OPT_OS_NONE +volatile uint32_t system_ticks = 0; +void SysTick_Handler (void) +{ + system_ticks++; +} + +uint32_t board_millis(void) +{ + return system_ticks; +} +#endif + +void HardFault_Handler (void) +{ + asm("bkpt"); +} + +// Required by __libc_init_array in startup code if we are compiling using +// -nostdlib/-nostartfiles. +void _init(void) +{ + +} diff --git a/hw/bsp/stm32f746disco/stm32f7xx_hal_conf.h b/hw/bsp/stm32f746disco/stm32f7xx_hal_conf.h new file mode 100644 index 000000000..03dec8f0d --- /dev/null +++ b/hw/bsp/stm32f746disco/stm32f7xx_hal_conf.h @@ -0,0 +1,472 @@ +/** + ****************************************************************************** + * @file stm32f7xx_hal_conf.h + * @author MCD Application Team + * @brief HAL configuration file. + ****************************************************************************** + * @attention + * + *

© Copyright (c) 2016 STMicroelectronics. + * All rights reserved.

+ * + * This software component is licensed by ST under BSD 3-Clause license, + * the "License"; You may not use this file except in compliance with the + * License. You may obtain a copy of the License at: + * opensource.org/licenses/BSD-3-Clause + * + ****************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __STM32F7xx_HAL_CONF_H +#define __STM32F7xx_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_CAN_MODULE_ENABLED */ +/* #define HAL_CAN_LEGACY_MODULE_ENABLED */ +/* #define HAL_CEC_MODULE_ENABLED */ +/* #define HAL_CRC_MODULE_ENABLED */ +/* #define HAL_CRYP_MODULE_ENABLED */ +/* #define HAL_DAC_MODULE_ENABLED */ +/* #define HAL_DCMI_MODULE_ENABLED */ +#define HAL_DMA_MODULE_ENABLED +/* #define HAL_DMA2D_MODULE_ENABLED */ +/* #define HAL_ETH_MODULE_ENABLED */ +#define HAL_FLASH_MODULE_ENABLED +/* #define HAL_NAND_MODULE_ENABLED */ +/* #define HAL_NOR_MODULE_ENABLED */ +/* #define HAL_SRAM_MODULE_ENABLED */ +/* #define HAL_SDRAM_MODULE_ENABLED */ +/* #define HAL_HASH_MODULE_ENABLED */ +#define HAL_GPIO_MODULE_ENABLED +/* #define HAL_I2C_MODULE_ENABLED */ +/* #define HAL_I2S_MODULE_ENABLED */ +/* #define HAL_IWDG_MODULE_ENABLED */ +/* #define HAL_LPTIM_MODULE_ENABLED */ +/* #define HAL_LTDC_MODULE_ENABLED */ +#define HAL_PWR_MODULE_ENABLED +/* #define HAL_QSPI_MODULE_ENABLED */ +#define HAL_RCC_MODULE_ENABLED +/* #define HAL_RNG_MODULE_ENABLED */ +/* #define HAL_RTC_MODULE_ENABLED */ +/* #define HAL_SAI_MODULE_ENABLED */ +/* #define HAL_SD_MODULE_ENABLED */ +/* #define HAL_SPDIFRX_MODULE_ENABLED */ +/* #define HAL_SPI_MODULE_ENABLED */ +/* #define HAL_TIM_MODULE_ENABLED */ +#define HAL_UART_MODULE_ENABLED +/* #define HAL_USART_MODULE_ENABLED */ +/* #define HAL_IRDA_MODULE_ENABLED */ +/* #define HAL_SMARTCARD_MODULE_ENABLED */ +/* #define HAL_WWDG_MODULE_ENABLED */ +#define HAL_CORTEX_MODULE_ENABLED +/* #define HAL_PCD_MODULE_ENABLED */ +/* #define HAL_HCD_MODULE_ENABLED */ +/* #define HAL_DFSDM_MODULE_ENABLED */ +/* #define HAL_DSI_MODULE_ENABLED */ +/* #define HAL_JPEG_MODULE_ENABLED */ +/* #define HAL_MDIOS_MODULE_ENABLED */ + + +/* ########################## HSE/HSI Values adaptation ##################### */ +/** + * @brief Adjust the value of External High Speed oscillator (HSE) used in your application. + * This value is used by the RCC HAL module to compute the system frequency + * (when HSE is used as system clock source, directly or through the PLL). + */ +#if !defined (HSE_VALUE) + #define HSE_VALUE ((uint32_t)8000000U) /*!< Value of the External oscillator in Hz */ +#endif /* HSE_VALUE */ + +#if !defined (HSE_STARTUP_TIMEOUT) + #define HSE_STARTUP_TIMEOUT ((uint32_t)100U) /*!< Time out for HSE start up, in ms */ +#endif /* HSE_STARTUP_TIMEOUT */ + +/** + * @brief Internal High Speed oscillator (HSI) value. + * This value is used by the RCC HAL module to compute the system frequency + * (when HSI is used as system clock source, directly or through the PLL). + */ +#if !defined (HSI_VALUE) + #define HSI_VALUE ((uint32_t)16000000U) /*!< Value of the Internal oscillator in Hz*/ +#endif /* HSI_VALUE */ + +/** + * @brief Internal Low Speed oscillator (LSI) value. + */ +#if !defined (LSI_VALUE) + #define LSI_VALUE ((uint32_t)32000U) /*!< 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. + */ +#if !defined (LSE_VALUE) + #define LSE_VALUE ((uint32_t)32768U) /*!< Value of the External Low Speed oscillator in Hz */ +#endif /* LSE_VALUE */ + +#if !defined (LSE_STARTUP_TIMEOUT) + #define LSE_STARTUP_TIMEOUT ((uint32_t)5000U) /*!< Time out for LSE start up, in ms */ +#endif /* LSE_STARTUP_TIMEOUT */ + +/** + * @brief External clock source for I2S peripheral + * This value is used by the I2S HAL module to compute the I2S clock source + * frequency, this source is inserted directly through I2S_CKIN pad. + */ +#if !defined (EXTERNAL_CLOCK_VALUE) + #define EXTERNAL_CLOCK_VALUE ((uint32_t)12288000U) /*!< Value of the Internal oscillator in Hz*/ +#endif /* EXTERNAL_CLOCK_VALUE */ + +/* Tip: To avoid modifying this file each time you need to use different HSE, + === you can define the HSE value in your toolchain compiler preprocessor. */ + +/* ########################### System Configuration ######################### */ +/** + * @brief This is the HAL system configuration section + */ +#define VDD_VALUE ((uint32_t)3300U) /*!< Value of VDD in mv */ +#define TICK_INT_PRIORITY ((uint32_t)0x0FU) /*!< tick interrupt priority */ +#define USE_RTOS 0U +#define PREFETCH_ENABLE 1U +#define ART_ACCLERATOR_ENABLE 1U /* To enable instruction cache and prefetch */ + +#define USE_HAL_ADC_REGISTER_CALLBACKS 0U /* ADC register callback disabled */ +#define USE_HAL_CAN_REGISTER_CALLBACKS 0U /* CAN register callback disabled */ +#define USE_HAL_CEC_REGISTER_CALLBACKS 0U /* CEC register callback disabled */ +#define USE_HAL_CRYP_REGISTER_CALLBACKS 0U /* CRYP register callback disabled */ +#define USE_HAL_DAC_REGISTER_CALLBACKS 0U /* DAC register callback disabled */ +#define USE_HAL_DCMI_REGISTER_CALLBACKS 0U /* DCMI register callback disabled */ +#define USE_HAL_DFSDM_REGISTER_CALLBACKS 0U /* DFSDM register callback disabled */ +#define USE_HAL_DMA2D_REGISTER_CALLBACKS 0U /* DMA2D register callback disabled */ +#define USE_HAL_DSI_REGISTER_CALLBACKS 0U /* DSI register callback disabled */ +#define USE_HAL_ETH_REGISTER_CALLBACKS 0U /* ETH register callback disabled */ +#define USE_HAL_HASH_REGISTER_CALLBACKS 0U /* HASH register callback disabled */ +#define USE_HAL_HCD_REGISTER_CALLBACKS 0U /* HCD register callback disabled */ +#define USE_HAL_I2C_REGISTER_CALLBACKS 0U /* I2C register callback disabled */ +#define USE_HAL_I2S_REGISTER_CALLBACKS 0U /* I2S register callback disabled */ +#define USE_HAL_IRDA_REGISTER_CALLBACKS 0U /* IRDA register callback disabled */ +#define USE_HAL_JPEG_REGISTER_CALLBACKS 0U /* JPEG register callback disabled */ +#define USE_HAL_LPTIM_REGISTER_CALLBACKS 0U /* LPTIM register callback disabled */ +#define USE_HAL_LTDC_REGISTER_CALLBACKS 0U /* LTDC register callback disabled */ +#define USE_HAL_MDIOS_REGISTER_CALLBACKS 0U /* MDIOS register callback disabled */ +#define USE_HAL_MMC_REGISTER_CALLBACKS 0U /* MMC register callback disabled */ +#define USE_HAL_NAND_REGISTER_CALLBACKS 0U /* NAND register callback disabled */ +#define USE_HAL_NOR_REGISTER_CALLBACKS 0U /* NOR register callback disabled */ +#define USE_HAL_PCD_REGISTER_CALLBACKS 0U /* PCD register callback disabled */ +#define USE_HAL_QSPI_REGISTER_CALLBACKS 0U /* QSPI register callback disabled */ +#define USE_HAL_RNG_REGISTER_CALLBACKS 0U /* RNG register callback disabled */ +#define USE_HAL_RTC_REGISTER_CALLBACKS 0U /* RTC register callback disabled */ +#define USE_HAL_SAI_REGISTER_CALLBACKS 0U /* SAI register callback disabled */ +#define USE_HAL_SD_REGISTER_CALLBACKS 0U /* SD register callback disabled */ +#define USE_HAL_SMARTCARD_REGISTER_CALLBACKS 0U /* SMARTCARD register callback disabled */ +#define USE_HAL_SDRAM_REGISTER_CALLBACKS 0U /* SDRAM register callback disabled */ +#define USE_HAL_SRAM_REGISTER_CALLBACKS 0U /* SRAM register callback disabled */ +#define USE_HAL_SPDIFRX_REGISTER_CALLBACKS 0U /* SPDIFRX register callback disabled */ +#define USE_HAL_SMBUS_REGISTER_CALLBACKS 0U /* SMBUS register callback disabled */ +#define USE_HAL_SPI_REGISTER_CALLBACKS 0U /* SPI register callback disabled */ +#define USE_HAL_TIM_REGISTER_CALLBACKS 0U /* TIM register callback disabled */ +#define USE_HAL_UART_REGISTER_CALLBACKS 0U /* UART register callback disabled */ +#define USE_HAL_USART_REGISTER_CALLBACKS 0U /* USART register callback disabled */ +#define USE_HAL_WWDG_REGISTER_CALLBACKS 0U /* WWDG register callback disabled */ + +/* ########################## Assert Selection ############################## */ +/** + * @brief Uncomment the line below to expanse the "assert_param" macro in the + * HAL drivers code + */ +/* #define USE_FULL_ASSERT 1 */ + +/* ################## Ethernet peripheral configuration for NUCLEO 144 board ##################### */ + +/* Section 1 : Ethernet peripheral configuration */ + +/* MAC ADDRESS: MAC_ADDR0:MAC_ADDR1:MAC_ADDR2:MAC_ADDR3:MAC_ADDR4:MAC_ADDR5 */ +#define MAC_ADDR0 2U +#define MAC_ADDR1 0U +#define MAC_ADDR2 0U +#define MAC_ADDR3 0U +#define MAC_ADDR4 0U +#define MAC_ADDR5 0U + +/* Definition of the Ethernet driver buffers size and count */ +#define ETH_RX_BUF_SIZE ETH_MAX_PACKET_SIZE /* buffer size for receive */ +#define ETH_TX_BUF_SIZE ETH_MAX_PACKET_SIZE /* buffer size for transmit */ +#define ETH_RXBUFNB ((uint32_t)5) /* 5 Rx buffers of size ETH_RX_BUF_SIZE */ +#define ETH_TXBUFNB ((uint32_t)5) /* 5 Tx buffers of size ETH_TX_BUF_SIZE */ + +/* Section 2: PHY configuration section */ +/* LAN8742A PHY Address*/ +#define LAN8742A_PHY_ADDRESS 0x00 +/* PHY Reset delay these values are based on a 1 ms Systick interrupt*/ +#define PHY_RESET_DELAY ((uint32_t)0x00000FFF) +/* PHY Configuration delay */ +#define PHY_CONFIG_DELAY ((uint32_t)0x00000FFF) + +#define PHY_READ_TO ((uint32_t)0x0000FFFF) +#define PHY_WRITE_TO ((uint32_t)0x0000FFFF) + +/* Section 3: Common PHY Registers */ + +#define PHY_BCR ((uint16_t)0x00) /*!< Transceiver Basic Control Register */ +#define PHY_BSR ((uint16_t)0x01) /*!< Transceiver Basic Status Register */ + +#define PHY_RESET ((uint16_t)0x8000) /*!< PHY Reset */ +#define PHY_LOOPBACK ((uint16_t)0x4000) /*!< Select loop-back mode */ +#define PHY_FULLDUPLEX_100M ((uint16_t)0x2100) /*!< Set the full-duplex mode at 100 Mb/s */ +#define PHY_HALFDUPLEX_100M ((uint16_t)0x2000) /*!< Set the half-duplex mode at 100 Mb/s */ +#define PHY_FULLDUPLEX_10M ((uint16_t)0x0100) /*!< Set the full-duplex mode at 10 Mb/s */ +#define PHY_HALFDUPLEX_10M ((uint16_t)0x0000) /*!< Set the half-duplex mode at 10 Mb/s */ +#define PHY_AUTONEGOTIATION ((uint16_t)0x1000) /*!< Enable auto-negotiation function */ +#define PHY_RESTART_AUTONEGOTIATION ((uint16_t)0x0200) /*!< Restart auto-negotiation function */ +#define PHY_POWERDOWN ((uint16_t)0x0800) /*!< Select the power down mode */ +#define PHY_ISOLATE ((uint16_t)0x0400) /*!< Isolate PHY from MII */ + +#define PHY_AUTONEGO_COMPLETE ((uint16_t)0x0020) /*!< Auto-Negotiation process completed */ +#define PHY_LINKED_STATUS ((uint16_t)0x0004) /*!< Valid link established */ +#define PHY_JABBER_DETECTION ((uint16_t)0x0002) /*!< Jabber condition detected */ + +/* Section 4: Extended PHY Registers */ + +#define PHY_SR ((uint16_t)0x1F) /*!< PHY special control/ status register Offset */ + +#define PHY_SPEED_STATUS ((uint16_t)0x0004) /*!< PHY Speed mask */ +#define PHY_DUPLEX_STATUS ((uint16_t)0x0010) /*!< PHY Duplex mask */ + + +#define PHY_ISFR ((uint16_t)0x1D) /*!< PHY Interrupt Source Flag register Offset */ +#define PHY_ISFR_INT4 ((uint16_t)0x0010) /*!< PHY Link down inturrupt */ + +/* ################## 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 1U + +/* Includes ------------------------------------------------------------------*/ +/** + * @brief Include module's header file + */ + +#ifdef HAL_RCC_MODULE_ENABLED + #include "stm32f7xx_hal_rcc.h" +#endif /* HAL_RCC_MODULE_ENABLED */ + +#ifdef HAL_GPIO_MODULE_ENABLED + #include "stm32f7xx_hal_gpio.h" +#endif /* HAL_GPIO_MODULE_ENABLED */ + +#ifdef HAL_DMA_MODULE_ENABLED + #include "stm32f7xx_hal_dma.h" +#endif /* HAL_DMA_MODULE_ENABLED */ + +#ifdef HAL_CORTEX_MODULE_ENABLED + #include "stm32f7xx_hal_cortex.h" +#endif /* HAL_CORTEX_MODULE_ENABLED */ + +#ifdef HAL_ADC_MODULE_ENABLED + #include "stm32f7xx_hal_adc.h" +#endif /* HAL_ADC_MODULE_ENABLED */ + +#ifdef HAL_CAN_MODULE_ENABLED + #include "stm32f7xx_hal_can.h" +#endif /* HAL_CAN_MODULE_ENABLED */ + +#ifdef HAL_CAN_LEGACY_MODULE_ENABLED + #include "stm32f7xx_hal_can_legacy.h" +#endif /* HAL_CAN_LEGACY_MODULE_ENABLED */ + +#ifdef HAL_CEC_MODULE_ENABLED + #include "stm32f7xx_hal_cec.h" +#endif /* HAL_CEC_MODULE_ENABLED */ + +#ifdef HAL_CRC_MODULE_ENABLED + #include "stm32f7xx_hal_crc.h" +#endif /* HAL_CRC_MODULE_ENABLED */ + +#ifdef HAL_CRYP_MODULE_ENABLED + #include "stm32f7xx_hal_cryp.h" +#endif /* HAL_CRYP_MODULE_ENABLED */ + +#ifdef HAL_DMA2D_MODULE_ENABLED + #include "stm32f7xx_hal_dma2d.h" +#endif /* HAL_DMA2D_MODULE_ENABLED */ + +#ifdef HAL_DAC_MODULE_ENABLED + #include "stm32f7xx_hal_dac.h" +#endif /* HAL_DAC_MODULE_ENABLED */ + +#ifdef HAL_DCMI_MODULE_ENABLED + #include "stm32f7xx_hal_dcmi.h" +#endif /* HAL_DCMI_MODULE_ENABLED */ + +#ifdef HAL_ETH_MODULE_ENABLED + #include "stm32f7xx_hal_eth.h" +#endif /* HAL_ETH_MODULE_ENABLED */ + +#ifdef HAL_FLASH_MODULE_ENABLED + #include "stm32f7xx_hal_flash.h" +#endif /* HAL_FLASH_MODULE_ENABLED */ + +#ifdef HAL_SRAM_MODULE_ENABLED + #include "stm32f7xx_hal_sram.h" +#endif /* HAL_SRAM_MODULE_ENABLED */ + +#ifdef HAL_NOR_MODULE_ENABLED + #include "stm32f7xx_hal_nor.h" +#endif /* HAL_NOR_MODULE_ENABLED */ + +#ifdef HAL_NAND_MODULE_ENABLED + #include "stm32f7xx_hal_nand.h" +#endif /* HAL_NAND_MODULE_ENABLED */ + +#ifdef HAL_SDRAM_MODULE_ENABLED + #include "stm32f7xx_hal_sdram.h" +#endif /* HAL_SDRAM_MODULE_ENABLED */ + +#ifdef HAL_HASH_MODULE_ENABLED + #include "stm32f7xx_hal_hash.h" +#endif /* HAL_HASH_MODULE_ENABLED */ + +#ifdef HAL_I2C_MODULE_ENABLED + #include "stm32f7xx_hal_i2c.h" +#endif /* HAL_I2C_MODULE_ENABLED */ + +#ifdef HAL_I2S_MODULE_ENABLED + #include "stm32f7xx_hal_i2s.h" +#endif /* HAL_I2S_MODULE_ENABLED */ + +#ifdef HAL_IWDG_MODULE_ENABLED + #include "stm32f7xx_hal_iwdg.h" +#endif /* HAL_IWDG_MODULE_ENABLED */ + +#ifdef HAL_LPTIM_MODULE_ENABLED + #include "stm32f7xx_hal_lptim.h" +#endif /* HAL_LPTIM_MODULE_ENABLED */ + +#ifdef HAL_LTDC_MODULE_ENABLED + #include "stm32f7xx_hal_ltdc.h" +#endif /* HAL_LTDC_MODULE_ENABLED */ + +#ifdef HAL_PWR_MODULE_ENABLED + #include "stm32f7xx_hal_pwr.h" +#endif /* HAL_PWR_MODULE_ENABLED */ + +#ifdef HAL_QSPI_MODULE_ENABLED + #include "stm32f7xx_hal_qspi.h" +#endif /* HAL_QSPI_MODULE_ENABLED */ + +#ifdef HAL_RNG_MODULE_ENABLED + #include "stm32f7xx_hal_rng.h" +#endif /* HAL_RNG_MODULE_ENABLED */ + +#ifdef HAL_RTC_MODULE_ENABLED + #include "stm32f7xx_hal_rtc.h" +#endif /* HAL_RTC_MODULE_ENABLED */ + +#ifdef HAL_SAI_MODULE_ENABLED + #include "stm32f7xx_hal_sai.h" +#endif /* HAL_SAI_MODULE_ENABLED */ + +#ifdef HAL_SD_MODULE_ENABLED + #include "stm32f7xx_hal_sd.h" +#endif /* HAL_SD_MODULE_ENABLED */ + +#ifdef HAL_SPDIFRX_MODULE_ENABLED + #include "stm32f7xx_hal_spdifrx.h" +#endif /* HAL_SPDIFRX_MODULE_ENABLED */ + +#ifdef HAL_SPI_MODULE_ENABLED + #include "stm32f7xx_hal_spi.h" +#endif /* HAL_SPI_MODULE_ENABLED */ + +#ifdef HAL_TIM_MODULE_ENABLED + #include "stm32f7xx_hal_tim.h" +#endif /* HAL_TIM_MODULE_ENABLED */ + +#ifdef HAL_UART_MODULE_ENABLED + #include "stm32f7xx_hal_uart.h" +#endif /* HAL_UART_MODULE_ENABLED */ + +#ifdef HAL_USART_MODULE_ENABLED + #include "stm32f7xx_hal_usart.h" +#endif /* HAL_USART_MODULE_ENABLED */ + +#ifdef HAL_IRDA_MODULE_ENABLED + #include "stm32f7xx_hal_irda.h" +#endif /* HAL_IRDA_MODULE_ENABLED */ + +#ifdef HAL_SMARTCARD_MODULE_ENABLED + #include "stm32f7xx_hal_smartcard.h" +#endif /* HAL_SMARTCARD_MODULE_ENABLED */ + +#ifdef HAL_WWDG_MODULE_ENABLED + #include "stm32f7xx_hal_wwdg.h" +#endif /* HAL_WWDG_MODULE_ENABLED */ + +#ifdef HAL_PCD_MODULE_ENABLED + #include "stm32f7xx_hal_pcd.h" +#endif /* HAL_PCD_MODULE_ENABLED */ + +#ifdef HAL_HCD_MODULE_ENABLED + #include "stm32f7xx_hal_hcd.h" +#endif /* HAL_HCD_MODULE_ENABLED */ + +#ifdef HAL_DFSDM_MODULE_ENABLED + #include "stm32f7xx_hal_dfsdm.h" +#endif /* HAL_DFSDM_MODULE_ENABLED */ + +#ifdef HAL_DSI_MODULE_ENABLED + #include "stm32f7xx_hal_dsi.h" +#endif /* HAL_DSI_MODULE_ENABLED */ + +#ifdef HAL_JPEG_MODULE_ENABLED + #include "stm32f7xx_hal_jpeg.h" +#endif /* HAL_JPEG_MODULE_ENABLED */ + +#ifdef HAL_MDIOS_MODULE_ENABLED + #include "stm32f7xx_hal_mdios.h" +#endif /* HAL_MDIOS_MODULE_ENABLED */ + +/* Exported macro ------------------------------------------------------------*/ +#ifdef USE_FULL_ASSERT +/** + * @brief The assert_param macro is used for function's parameters check. + * @param expr: If expr is false, it calls assert_failed function + * which reports the name of the source file and the source + * line number of the call that failed. + * If expr is true, it returns no value. + * @retval None + */ + #define assert_param(expr) ((expr) ? (void)0 : assert_failed((uint8_t *)__FILE__, __LINE__)) +/* Exported functions ------------------------------------------------------- */ + void assert_failed(uint8_t* file, uint32_t line); +#else + #define assert_param(expr) ((void)0U) +#endif /* USE_FULL_ASSERT */ + + +#ifdef __cplusplus +} +#endif + +#endif /* __STM32F7xx_HAL_CONF_H */ + + +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/hw/bsp/stm32f769disco/STM32F769ZITx_FLASH.ld b/hw/bsp/stm32f769disco/STM32F769ZITx_FLASH.ld new file mode 100644 index 000000000..378ed80dd --- /dev/null +++ b/hw/bsp/stm32f769disco/STM32F769ZITx_FLASH.ld @@ -0,0 +1,167 @@ +/* +***************************************************************************** +** + +** File : LinkerScript.ld +** +** Abstract : Linker script for STM32F767ZITx Device with +** 2048KByte FLASH, 512KByte RAM +** +** Set heap size, stack size and stack location according +** to application requirements. +** +** Set memory bank area and size if external memory is used. +** +** Target : STMicroelectronics STM32 +** +** +** Distribution: The file is distributed as is, without any warranty +** of any kind. +** +** (c)Copyright Ac6. +** You may use this file as-is or modify it according to the needs of your +** project. Distribution of this file (unmodified or modified) is not +** permitted. Ac6 permit registered System Workbench for MCU users the +** rights to distribute the assembled, compiled & linked contents of this +** file as part of an application binary file, provided that it is built +** using the System Workbench for MCU toolchain. +** +***************************************************************************** +*/ + +/* Entry Point */ +ENTRY(Reset_Handler) + +/* Highest address of the user mode stack */ +_estack = 0x20080000; /* 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 +{ +FLASH (rx) : ORIGIN = 0x08000000, LENGTH = 2048K +RAM (xrw) : ORIGIN = 0x20000000, 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 secion */ + _sbss = .; /* define a global symbol at bss start */ + __bss_start__ = _sbss; + *(.bss) + *(.bss*) + *(COMMON) + + . = ALIGN(4); + _ebss = .; /* define a global symbol at bss end */ + __bss_end__ = _ebss; + } >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/stm32f769disco/board.mk b/hw/bsp/stm32f769disco/board.mk new file mode 100644 index 000000000..62c05cca5 --- /dev/null +++ b/hw/bsp/stm32f769disco/board.mk @@ -0,0 +1,51 @@ +CFLAGS += \ + -flto \ + -mthumb \ + -mabi=aapcs \ + -mcpu=cortex-m7 \ + -mfloat-abi=hard \ + -mfpu=fpv5-d16 \ + -nostdlib -nostartfiles \ + -DSTM32F769xx \ + -DHSE_VALUE=25000000 \ + -DCFG_TUSB_MCU=OPT_MCU_STM32F7 \ + -DBOARD_DEVICE_RHPORT_NUM=1 \ + -DBOARD_DEVICE_RHPORT_SPEED=OPT_MODE_HIGH_SPEED + +# suppress warning caused by vendor mcu driver +CFLAGS += -Wno-error=cast-align -Wno-error=shadow + +ST_HAL_DRIVER = hw/mcu/st/st_driver/STM32F7xx_HAL_Driver +ST_CMSIS = hw/mcu/st/st_driver/CMSIS/Device/ST/STM32F7xx + +# All source paths should be relative to the top level. +LD_FILE = hw/bsp/$(BOARD)/STM32F769ZITx_FLASH.ld + +SRC_C += \ + $(ST_CMSIS)/Source/Templates/system_stm32f7xx.c \ + $(ST_HAL_DRIVER)/Src/stm32f7xx_hal.c \ + $(ST_HAL_DRIVER)/Src/stm32f7xx_hal_cortex.c \ + $(ST_HAL_DRIVER)/Src/stm32f7xx_hal_rcc.c \ + $(ST_HAL_DRIVER)/Src/stm32f7xx_hal_rcc_ex.c \ + $(ST_HAL_DRIVER)/Src/stm32f7xx_hal_gpio.c \ + $(ST_HAL_DRIVER)/Src/stm32f7xx_hal_uart.c \ + $(ST_HAL_DRIVER)/Src/stm32f7xx_hal_pwr_ex.c + +SRC_S += \ + $(ST_CMSIS)/Source/Templates/gcc/startup_stm32f769xx.s + +INC += \ + $(TOP)/hw/mcu/st/st_driver/CMSIS/Include \ + $(TOP)/$(ST_CMSIS)/Include \ + $(TOP)/$(ST_HAL_DRIVER)/Inc \ + $(TOP)/hw/bsp/$(BOARD) + +# For TinyUSB port source +VENDOR = st +CHIP_FAMILY = synopsys + +# For freeRTOS port source +FREERTOS_PORT = ARM_CM7/r0p1 + +# flash target using on-board stlink +flash: flash-stlink diff --git a/hw/bsp/stm32f769disco/stm32f769disco.c b/hw/bsp/stm32f769disco/stm32f769disco.c new file mode 100644 index 000000000..2664fe0e0 --- /dev/null +++ b/hw/bsp/stm32f769disco/stm32f769disco.c @@ -0,0 +1,297 @@ +/* + * The MIT License (MIT) + * + * Copyright (c) 2020 Uwe Bonnes (bon@elektron.ikp.physik.tu-darmstadt.de), + * Ha Thach (tinyusb.org) + * + * Permission is hereby granted, free of charge, to any person obtaining a copy + * of this software and associated documentation files (the "Software"), to deal + * in the Software without restriction, including without limitation the rights + * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell + * copies of the Software, and to permit persons to whom the Software is + * furnished to do so, subject to the following conditions: + * + * The above copyright notice and this permission notice shall be included in + * all copies or substantial portions of the Software. + * + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR + * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE + * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER + * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, + * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN + * THE SOFTWARE. + * + * This file is part of the TinyUSB stack. + */ + +#include "../board.h" + +#include "stm32f7xx_hal.h" + +void OTG_FS_IRQHandler(void) +{ + tud_int_handler(0); +} + +//--------------------------------------------------------------------+ +// Forward USB interrupt events to TinyUSB IRQ Handler +//--------------------------------------------------------------------+ +void OTG_HS_IRQHandler(void) +{ + tud_int_handler(1); +} + +//--------------------------------------------------------------------+ +// MACRO TYPEDEF CONSTANT ENUM +//--------------------------------------------------------------------+ + +#define LED_PORT GPIOJ +#define LED_PIN GPIO_PIN_12 +#define LED_STATE_ON 5 + +#define BUTTON_PORT GPIOA +#define BUTTON_PIN GPIO_PIN_0 +#define BUTTON_STATE_ACTIVE 1 + +#define UARTx USART1 +#define UART_GPIO_PORT GPIOA +#define UART_GPIO_AF GPIO_AF7_USART1 +#define UART_TX_PIN GPIO_PIN_9 +#define UART_RX_PIN GPIO_PIN_10 + +UART_HandleTypeDef UartHandle; + +// enable all LED, Button, Uart, USB clock +static void all_rcc_clk_enable(void) +{ + __HAL_RCC_GPIOA_CLK_ENABLE(); // Button, UART, ULPI CLK|D0 + __HAL_RCC_GPIOB_CLK_ENABLE(); // ULPI D1-7 + __HAL_RCC_GPIOC_CLK_ENABLE(); // ULPI STP + __HAL_RCC_GPIOH_CLK_ENABLE(); // ULPI NXT + __HAL_RCC_GPIOI_CLK_ENABLE(); // ULPI NXT + __HAL_RCC_GPIOJ_CLK_ENABLE(); // LED + __HAL_RCC_USART1_CLK_ENABLE(); // Uart module +} + +/** + * @brief System Clock Configuration + * The system Clock is configured as follow : + * System Clock source = PLL (HSE) + * SYSCLK(Hz) = 216000000 + * HCLK(Hz) = 216000000 + * AHB Prescaler = 1 + * APB1 Prescaler = 4 + * APB2 Prescaler = 2 + * HSE Frequency(Hz) = 25000000 + * PLL_M = HSE_VALUE/1000000 + * PLL_N = 432 + * PLL_P = 2 + * PLL_Q = 9 + * PLL_R = 7 + * VDD(V) = 3.3 + * Main regulator output voltage = Scale1 mode + * Flash Latency(WS) = 7 + * The USB clock configuration from PLLSAI: + * PLLSAIP = 8 + * PLLSAIN = 384 + * PLLSAIQ = 7 + * @param None + * @retval None + */ +void SystemClock_Config(void) +{ + RCC_ClkInitTypeDef RCC_ClkInitStruct; + RCC_OscInitTypeDef RCC_OscInitStruct; + + /* Enable Power Control clock */ + __HAL_RCC_PWR_CLK_ENABLE(); + + /* The voltage scaling allows optimizing the power consumption when the device is + clocked below the maximum system frequency, to update the voltage scaling value + regarding system frequency refer to product datasheet. */ + __HAL_PWR_VOLTAGESCALING_CONFIG(PWR_REGULATOR_VOLTAGE_SCALE1); + + /* Enable HSE Oscillator and activate PLL with HSE as source */ + RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_HSE; + RCC_OscInitStruct.HSEState = RCC_HSE_ON; + RCC_OscInitStruct.PLL.PLLState = RCC_PLL_ON; + RCC_OscInitStruct.PLL.PLLSource = RCC_PLLSOURCE_HSE; + RCC_OscInitStruct.PLL.PLLM = HSE_VALUE/1000000; + RCC_OscInitStruct.PLL.PLLN = 432; + RCC_OscInitStruct.PLL.PLLP = RCC_PLLP_DIV2; + RCC_OscInitStruct.PLL.PLLQ = 9; + RCC_OscInitStruct.PLL.PLLR = 7; + HAL_RCC_OscConfig(&RCC_OscInitStruct); + + /* Activate the OverDrive to reach the 216 MHz Frequency */ + HAL_PWREx_EnableOverDrive(); + + /* Select PLL as system clock source and configure the HCLK, PCLK1 and PCLK2 clocks dividers */ + RCC_ClkInitStruct.ClockType = (RCC_CLOCKTYPE_SYSCLK | RCC_CLOCKTYPE_HCLK | RCC_CLOCKTYPE_PCLK1 | RCC_CLOCKTYPE_PCLK2); + RCC_ClkInitStruct.SYSCLKSource = RCC_SYSCLKSOURCE_PLLCLK; + RCC_ClkInitStruct.AHBCLKDivider = RCC_SYSCLK_DIV1; + RCC_ClkInitStruct.APB1CLKDivider = RCC_HCLK_DIV4; + RCC_ClkInitStruct.APB2CLKDivider = RCC_HCLK_DIV2; + + HAL_RCC_ClockConfig(&RCC_ClkInitStruct, FLASH_LATENCY_7); +} + +void board_init(void) +{ + SystemClock_Config(); + all_rcc_clk_enable(); + +#if CFG_TUSB_OS == OPT_OS_NONE + // 1ms tick timer + SysTick_Config(SystemCoreClock / 1000); +#endif + + GPIO_InitTypeDef GPIO_InitStruct; + + // LED + GPIO_InitStruct.Pin = LED_PIN; + GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_PP; + GPIO_InitStruct.Pull = GPIO_PULLUP; + GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_HIGH; + HAL_GPIO_Init(LED_PORT, &GPIO_InitStruct); + + // Button + GPIO_InitStruct.Pin = BUTTON_PIN; + GPIO_InitStruct.Mode = GPIO_MODE_INPUT; + GPIO_InitStruct.Pull = GPIO_NOPULL; + GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_HIGH; + HAL_GPIO_Init(BUTTON_PORT, &GPIO_InitStruct); + + // Uart + GPIO_InitStruct.Pin = UART_TX_PIN | UART_RX_PIN; + GPIO_InitStruct.Mode = GPIO_MODE_AF_PP; + GPIO_InitStruct.Pull = GPIO_PULLUP; + GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_VERY_HIGH; + GPIO_InitStruct.Alternate = UART_GPIO_AF; + HAL_GPIO_Init(UART_GPIO_PORT, &GPIO_InitStruct); + + UartHandle.Instance = UARTx; + UartHandle.Init.BaudRate = CFG_BOARD_UART_BAUDRATE; + UartHandle.Init.WordLength = UART_WORDLENGTH_8B; + UartHandle.Init.StopBits = UART_STOPBITS_1; + UartHandle.Init.Parity = UART_PARITY_NONE; + UartHandle.Init.HwFlowCtl = UART_HWCONTROL_NONE; + UartHandle.Init.Mode = UART_MODE_TX_RX; + UartHandle.Init.OverSampling = UART_OVERSAMPLING_16; + HAL_UART_Init(&UartHandle); + + /* Configure USB HS GPIOs */ + /* ULPI CLK */ + GPIO_InitStruct.Pin = GPIO_PIN_5; + GPIO_InitStruct.Mode = GPIO_MODE_AF_PP; + GPIO_InitStruct.Pull = GPIO_NOPULL; + GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_HIGH; + GPIO_InitStruct.Alternate = GPIO_AF10_OTG_HS; + HAL_GPIO_Init(GPIOA, &GPIO_InitStruct); + + /* D0 */ + GPIO_InitStruct.Pin = GPIO_PIN_3; + GPIO_InitStruct.Mode = GPIO_MODE_AF_PP; + GPIO_InitStruct.Pull = GPIO_NOPULL; + GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_HIGH; + GPIO_InitStruct.Alternate = GPIO_AF10_OTG_HS; + HAL_GPIO_Init(GPIOA, &GPIO_InitStruct); + + /* D1 D2 D3 D4 D5 D6 D7 */ + GPIO_InitStruct.Pin = GPIO_PIN_0 | GPIO_PIN_1 | GPIO_PIN_10 | GPIO_PIN_11 | GPIO_PIN_12 | GPIO_PIN_13 | GPIO_PIN_5; + GPIO_InitStruct.Mode = GPIO_MODE_AF_PP; + GPIO_InitStruct.Pull = GPIO_NOPULL; + GPIO_InitStruct.Alternate = GPIO_AF10_OTG_HS; + HAL_GPIO_Init(GPIOB, &GPIO_InitStruct); + + /* STP */ + GPIO_InitStruct.Pin = GPIO_PIN_0; + GPIO_InitStruct.Mode = GPIO_MODE_AF_PP; + GPIO_InitStruct.Pull = GPIO_NOPULL; + GPIO_InitStruct.Alternate = GPIO_AF10_OTG_HS; + HAL_GPIO_Init(GPIOC, &GPIO_InitStruct); + + /* NXT */ + GPIO_InitStruct.Pin = GPIO_PIN_4; + GPIO_InitStruct.Mode = GPIO_MODE_AF_PP; + GPIO_InitStruct.Pull = GPIO_NOPULL; + GPIO_InitStruct.Alternate = GPIO_AF10_OTG_HS; + HAL_GPIO_Init(GPIOH, &GPIO_InitStruct); + + /* DIR */ + GPIO_InitStruct.Pin = GPIO_PIN_11; + GPIO_InitStruct.Mode = GPIO_MODE_AF_PP; + GPIO_InitStruct.Pull = GPIO_NOPULL; + GPIO_InitStruct.Alternate = GPIO_AF10_OTG_HS; + HAL_GPIO_Init(GPIOI, &GPIO_InitStruct); + + // Enable ULPI clock + __HAL_RCC_USB_OTG_HS_ULPI_CLK_ENABLE(); + + /* Enable USB HS Clocks */ + __HAL_RCC_USB_OTG_HS_CLK_ENABLE(); + + // No VBUS sense + USB_OTG_HS->GCCFG &= ~USB_OTG_GCCFG_VBDEN; + + // B-peripheral session valid override enable + USB_OTG_HS->GOTGCTL |= USB_OTG_GOTGCTL_BVALOEN; + USB_OTG_HS->GOTGCTL |= USB_OTG_GOTGCTL_BVALOVAL; + + // Force device mode + USB_OTG_HS->GUSBCFG &= ~USB_OTG_GUSBCFG_FHMOD; + USB_OTG_HS->GUSBCFG |= USB_OTG_GUSBCFG_FDMOD; + +} + +//--------------------------------------------------------------------+ +// Board porting API +//--------------------------------------------------------------------+ + +void board_led_write(bool state) +{ + HAL_GPIO_WritePin(LED_PORT, LED_PIN, state); +} + +uint32_t board_button_read(void) +{ + return 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) +{ + HAL_UART_Transmit(&UartHandle, (uint8_t*) buf, len, 0xffff); + return len; +} + +#if CFG_TUSB_OS == OPT_OS_NONE +volatile uint32_t system_ticks = 0; +void SysTick_Handler (void) +{ + system_ticks++; +} + +uint32_t board_millis(void) +{ + return system_ticks; +} +#endif + +void HardFault_Handler (void) +{ + asm("bkpt"); +} + +// Required by __libc_init_array in startup code if we are compiling using +// -nostdlib/-nostartfiles. +void _init(void) +{ + +} diff --git a/hw/bsp/stm32f769disco/stm32f7xx_hal_conf.h b/hw/bsp/stm32f769disco/stm32f7xx_hal_conf.h new file mode 100644 index 000000000..03dec8f0d --- /dev/null +++ b/hw/bsp/stm32f769disco/stm32f7xx_hal_conf.h @@ -0,0 +1,472 @@ +/** + ****************************************************************************** + * @file stm32f7xx_hal_conf.h + * @author MCD Application Team + * @brief HAL configuration file. + ****************************************************************************** + * @attention + * + *

© Copyright (c) 2016 STMicroelectronics. + * All rights reserved.

+ * + * This software component is licensed by ST under BSD 3-Clause license, + * the "License"; You may not use this file except in compliance with the + * License. You may obtain a copy of the License at: + * opensource.org/licenses/BSD-3-Clause + * + ****************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __STM32F7xx_HAL_CONF_H +#define __STM32F7xx_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_CAN_MODULE_ENABLED */ +/* #define HAL_CAN_LEGACY_MODULE_ENABLED */ +/* #define HAL_CEC_MODULE_ENABLED */ +/* #define HAL_CRC_MODULE_ENABLED */ +/* #define HAL_CRYP_MODULE_ENABLED */ +/* #define HAL_DAC_MODULE_ENABLED */ +/* #define HAL_DCMI_MODULE_ENABLED */ +#define HAL_DMA_MODULE_ENABLED +/* #define HAL_DMA2D_MODULE_ENABLED */ +/* #define HAL_ETH_MODULE_ENABLED */ +#define HAL_FLASH_MODULE_ENABLED +/* #define HAL_NAND_MODULE_ENABLED */ +/* #define HAL_NOR_MODULE_ENABLED */ +/* #define HAL_SRAM_MODULE_ENABLED */ +/* #define HAL_SDRAM_MODULE_ENABLED */ +/* #define HAL_HASH_MODULE_ENABLED */ +#define HAL_GPIO_MODULE_ENABLED +/* #define HAL_I2C_MODULE_ENABLED */ +/* #define HAL_I2S_MODULE_ENABLED */ +/* #define HAL_IWDG_MODULE_ENABLED */ +/* #define HAL_LPTIM_MODULE_ENABLED */ +/* #define HAL_LTDC_MODULE_ENABLED */ +#define HAL_PWR_MODULE_ENABLED +/* #define HAL_QSPI_MODULE_ENABLED */ +#define HAL_RCC_MODULE_ENABLED +/* #define HAL_RNG_MODULE_ENABLED */ +/* #define HAL_RTC_MODULE_ENABLED */ +/* #define HAL_SAI_MODULE_ENABLED */ +/* #define HAL_SD_MODULE_ENABLED */ +/* #define HAL_SPDIFRX_MODULE_ENABLED */ +/* #define HAL_SPI_MODULE_ENABLED */ +/* #define HAL_TIM_MODULE_ENABLED */ +#define HAL_UART_MODULE_ENABLED +/* #define HAL_USART_MODULE_ENABLED */ +/* #define HAL_IRDA_MODULE_ENABLED */ +/* #define HAL_SMARTCARD_MODULE_ENABLED */ +/* #define HAL_WWDG_MODULE_ENABLED */ +#define HAL_CORTEX_MODULE_ENABLED +/* #define HAL_PCD_MODULE_ENABLED */ +/* #define HAL_HCD_MODULE_ENABLED */ +/* #define HAL_DFSDM_MODULE_ENABLED */ +/* #define HAL_DSI_MODULE_ENABLED */ +/* #define HAL_JPEG_MODULE_ENABLED */ +/* #define HAL_MDIOS_MODULE_ENABLED */ + + +/* ########################## HSE/HSI Values adaptation ##################### */ +/** + * @brief Adjust the value of External High Speed oscillator (HSE) used in your application. + * This value is used by the RCC HAL module to compute the system frequency + * (when HSE is used as system clock source, directly or through the PLL). + */ +#if !defined (HSE_VALUE) + #define HSE_VALUE ((uint32_t)8000000U) /*!< Value of the External oscillator in Hz */ +#endif /* HSE_VALUE */ + +#if !defined (HSE_STARTUP_TIMEOUT) + #define HSE_STARTUP_TIMEOUT ((uint32_t)100U) /*!< Time out for HSE start up, in ms */ +#endif /* HSE_STARTUP_TIMEOUT */ + +/** + * @brief Internal High Speed oscillator (HSI) value. + * This value is used by the RCC HAL module to compute the system frequency + * (when HSI is used as system clock source, directly or through the PLL). + */ +#if !defined (HSI_VALUE) + #define HSI_VALUE ((uint32_t)16000000U) /*!< Value of the Internal oscillator in Hz*/ +#endif /* HSI_VALUE */ + +/** + * @brief Internal Low Speed oscillator (LSI) value. + */ +#if !defined (LSI_VALUE) + #define LSI_VALUE ((uint32_t)32000U) /*!< 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. + */ +#if !defined (LSE_VALUE) + #define LSE_VALUE ((uint32_t)32768U) /*!< Value of the External Low Speed oscillator in Hz */ +#endif /* LSE_VALUE */ + +#if !defined (LSE_STARTUP_TIMEOUT) + #define LSE_STARTUP_TIMEOUT ((uint32_t)5000U) /*!< Time out for LSE start up, in ms */ +#endif /* LSE_STARTUP_TIMEOUT */ + +/** + * @brief External clock source for I2S peripheral + * This value is used by the I2S HAL module to compute the I2S clock source + * frequency, this source is inserted directly through I2S_CKIN pad. + */ +#if !defined (EXTERNAL_CLOCK_VALUE) + #define EXTERNAL_CLOCK_VALUE ((uint32_t)12288000U) /*!< Value of the Internal oscillator in Hz*/ +#endif /* EXTERNAL_CLOCK_VALUE */ + +/* Tip: To avoid modifying this file each time you need to use different HSE, + === you can define the HSE value in your toolchain compiler preprocessor. */ + +/* ########################### System Configuration ######################### */ +/** + * @brief This is the HAL system configuration section + */ +#define VDD_VALUE ((uint32_t)3300U) /*!< Value of VDD in mv */ +#define TICK_INT_PRIORITY ((uint32_t)0x0FU) /*!< tick interrupt priority */ +#define USE_RTOS 0U +#define PREFETCH_ENABLE 1U +#define ART_ACCLERATOR_ENABLE 1U /* To enable instruction cache and prefetch */ + +#define USE_HAL_ADC_REGISTER_CALLBACKS 0U /* ADC register callback disabled */ +#define USE_HAL_CAN_REGISTER_CALLBACKS 0U /* CAN register callback disabled */ +#define USE_HAL_CEC_REGISTER_CALLBACKS 0U /* CEC register callback disabled */ +#define USE_HAL_CRYP_REGISTER_CALLBACKS 0U /* CRYP register callback disabled */ +#define USE_HAL_DAC_REGISTER_CALLBACKS 0U /* DAC register callback disabled */ +#define USE_HAL_DCMI_REGISTER_CALLBACKS 0U /* DCMI register callback disabled */ +#define USE_HAL_DFSDM_REGISTER_CALLBACKS 0U /* DFSDM register callback disabled */ +#define USE_HAL_DMA2D_REGISTER_CALLBACKS 0U /* DMA2D register callback disabled */ +#define USE_HAL_DSI_REGISTER_CALLBACKS 0U /* DSI register callback disabled */ +#define USE_HAL_ETH_REGISTER_CALLBACKS 0U /* ETH register callback disabled */ +#define USE_HAL_HASH_REGISTER_CALLBACKS 0U /* HASH register callback disabled */ +#define USE_HAL_HCD_REGISTER_CALLBACKS 0U /* HCD register callback disabled */ +#define USE_HAL_I2C_REGISTER_CALLBACKS 0U /* I2C register callback disabled */ +#define USE_HAL_I2S_REGISTER_CALLBACKS 0U /* I2S register callback disabled */ +#define USE_HAL_IRDA_REGISTER_CALLBACKS 0U /* IRDA register callback disabled */ +#define USE_HAL_JPEG_REGISTER_CALLBACKS 0U /* JPEG register callback disabled */ +#define USE_HAL_LPTIM_REGISTER_CALLBACKS 0U /* LPTIM register callback disabled */ +#define USE_HAL_LTDC_REGISTER_CALLBACKS 0U /* LTDC register callback disabled */ +#define USE_HAL_MDIOS_REGISTER_CALLBACKS 0U /* MDIOS register callback disabled */ +#define USE_HAL_MMC_REGISTER_CALLBACKS 0U /* MMC register callback disabled */ +#define USE_HAL_NAND_REGISTER_CALLBACKS 0U /* NAND register callback disabled */ +#define USE_HAL_NOR_REGISTER_CALLBACKS 0U /* NOR register callback disabled */ +#define USE_HAL_PCD_REGISTER_CALLBACKS 0U /* PCD register callback disabled */ +#define USE_HAL_QSPI_REGISTER_CALLBACKS 0U /* QSPI register callback disabled */ +#define USE_HAL_RNG_REGISTER_CALLBACKS 0U /* RNG register callback disabled */ +#define USE_HAL_RTC_REGISTER_CALLBACKS 0U /* RTC register callback disabled */ +#define USE_HAL_SAI_REGISTER_CALLBACKS 0U /* SAI register callback disabled */ +#define USE_HAL_SD_REGISTER_CALLBACKS 0U /* SD register callback disabled */ +#define USE_HAL_SMARTCARD_REGISTER_CALLBACKS 0U /* SMARTCARD register callback disabled */ +#define USE_HAL_SDRAM_REGISTER_CALLBACKS 0U /* SDRAM register callback disabled */ +#define USE_HAL_SRAM_REGISTER_CALLBACKS 0U /* SRAM register callback disabled */ +#define USE_HAL_SPDIFRX_REGISTER_CALLBACKS 0U /* SPDIFRX register callback disabled */ +#define USE_HAL_SMBUS_REGISTER_CALLBACKS 0U /* SMBUS register callback disabled */ +#define USE_HAL_SPI_REGISTER_CALLBACKS 0U /* SPI register callback disabled */ +#define USE_HAL_TIM_REGISTER_CALLBACKS 0U /* TIM register callback disabled */ +#define USE_HAL_UART_REGISTER_CALLBACKS 0U /* UART register callback disabled */ +#define USE_HAL_USART_REGISTER_CALLBACKS 0U /* USART register callback disabled */ +#define USE_HAL_WWDG_REGISTER_CALLBACKS 0U /* WWDG register callback disabled */ + +/* ########################## Assert Selection ############################## */ +/** + * @brief Uncomment the line below to expanse the "assert_param" macro in the + * HAL drivers code + */ +/* #define USE_FULL_ASSERT 1 */ + +/* ################## Ethernet peripheral configuration for NUCLEO 144 board ##################### */ + +/* Section 1 : Ethernet peripheral configuration */ + +/* MAC ADDRESS: MAC_ADDR0:MAC_ADDR1:MAC_ADDR2:MAC_ADDR3:MAC_ADDR4:MAC_ADDR5 */ +#define MAC_ADDR0 2U +#define MAC_ADDR1 0U +#define MAC_ADDR2 0U +#define MAC_ADDR3 0U +#define MAC_ADDR4 0U +#define MAC_ADDR5 0U + +/* Definition of the Ethernet driver buffers size and count */ +#define ETH_RX_BUF_SIZE ETH_MAX_PACKET_SIZE /* buffer size for receive */ +#define ETH_TX_BUF_SIZE ETH_MAX_PACKET_SIZE /* buffer size for transmit */ +#define ETH_RXBUFNB ((uint32_t)5) /* 5 Rx buffers of size ETH_RX_BUF_SIZE */ +#define ETH_TXBUFNB ((uint32_t)5) /* 5 Tx buffers of size ETH_TX_BUF_SIZE */ + +/* Section 2: PHY configuration section */ +/* LAN8742A PHY Address*/ +#define LAN8742A_PHY_ADDRESS 0x00 +/* PHY Reset delay these values are based on a 1 ms Systick interrupt*/ +#define PHY_RESET_DELAY ((uint32_t)0x00000FFF) +/* PHY Configuration delay */ +#define PHY_CONFIG_DELAY ((uint32_t)0x00000FFF) + +#define PHY_READ_TO ((uint32_t)0x0000FFFF) +#define PHY_WRITE_TO ((uint32_t)0x0000FFFF) + +/* Section 3: Common PHY Registers */ + +#define PHY_BCR ((uint16_t)0x00) /*!< Transceiver Basic Control Register */ +#define PHY_BSR ((uint16_t)0x01) /*!< Transceiver Basic Status Register */ + +#define PHY_RESET ((uint16_t)0x8000) /*!< PHY Reset */ +#define PHY_LOOPBACK ((uint16_t)0x4000) /*!< Select loop-back mode */ +#define PHY_FULLDUPLEX_100M ((uint16_t)0x2100) /*!< Set the full-duplex mode at 100 Mb/s */ +#define PHY_HALFDUPLEX_100M ((uint16_t)0x2000) /*!< Set the half-duplex mode at 100 Mb/s */ +#define PHY_FULLDUPLEX_10M ((uint16_t)0x0100) /*!< Set the full-duplex mode at 10 Mb/s */ +#define PHY_HALFDUPLEX_10M ((uint16_t)0x0000) /*!< Set the half-duplex mode at 10 Mb/s */ +#define PHY_AUTONEGOTIATION ((uint16_t)0x1000) /*!< Enable auto-negotiation function */ +#define PHY_RESTART_AUTONEGOTIATION ((uint16_t)0x0200) /*!< Restart auto-negotiation function */ +#define PHY_POWERDOWN ((uint16_t)0x0800) /*!< Select the power down mode */ +#define PHY_ISOLATE ((uint16_t)0x0400) /*!< Isolate PHY from MII */ + +#define PHY_AUTONEGO_COMPLETE ((uint16_t)0x0020) /*!< Auto-Negotiation process completed */ +#define PHY_LINKED_STATUS ((uint16_t)0x0004) /*!< Valid link established */ +#define PHY_JABBER_DETECTION ((uint16_t)0x0002) /*!< Jabber condition detected */ + +/* Section 4: Extended PHY Registers */ + +#define PHY_SR ((uint16_t)0x1F) /*!< PHY special control/ status register Offset */ + +#define PHY_SPEED_STATUS ((uint16_t)0x0004) /*!< PHY Speed mask */ +#define PHY_DUPLEX_STATUS ((uint16_t)0x0010) /*!< PHY Duplex mask */ + + +#define PHY_ISFR ((uint16_t)0x1D) /*!< PHY Interrupt Source Flag register Offset */ +#define PHY_ISFR_INT4 ((uint16_t)0x0010) /*!< PHY Link down inturrupt */ + +/* ################## 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 1U + +/* Includes ------------------------------------------------------------------*/ +/** + * @brief Include module's header file + */ + +#ifdef HAL_RCC_MODULE_ENABLED + #include "stm32f7xx_hal_rcc.h" +#endif /* HAL_RCC_MODULE_ENABLED */ + +#ifdef HAL_GPIO_MODULE_ENABLED + #include "stm32f7xx_hal_gpio.h" +#endif /* HAL_GPIO_MODULE_ENABLED */ + +#ifdef HAL_DMA_MODULE_ENABLED + #include "stm32f7xx_hal_dma.h" +#endif /* HAL_DMA_MODULE_ENABLED */ + +#ifdef HAL_CORTEX_MODULE_ENABLED + #include "stm32f7xx_hal_cortex.h" +#endif /* HAL_CORTEX_MODULE_ENABLED */ + +#ifdef HAL_ADC_MODULE_ENABLED + #include "stm32f7xx_hal_adc.h" +#endif /* HAL_ADC_MODULE_ENABLED */ + +#ifdef HAL_CAN_MODULE_ENABLED + #include "stm32f7xx_hal_can.h" +#endif /* HAL_CAN_MODULE_ENABLED */ + +#ifdef HAL_CAN_LEGACY_MODULE_ENABLED + #include "stm32f7xx_hal_can_legacy.h" +#endif /* HAL_CAN_LEGACY_MODULE_ENABLED */ + +#ifdef HAL_CEC_MODULE_ENABLED + #include "stm32f7xx_hal_cec.h" +#endif /* HAL_CEC_MODULE_ENABLED */ + +#ifdef HAL_CRC_MODULE_ENABLED + #include "stm32f7xx_hal_crc.h" +#endif /* HAL_CRC_MODULE_ENABLED */ + +#ifdef HAL_CRYP_MODULE_ENABLED + #include "stm32f7xx_hal_cryp.h" +#endif /* HAL_CRYP_MODULE_ENABLED */ + +#ifdef HAL_DMA2D_MODULE_ENABLED + #include "stm32f7xx_hal_dma2d.h" +#endif /* HAL_DMA2D_MODULE_ENABLED */ + +#ifdef HAL_DAC_MODULE_ENABLED + #include "stm32f7xx_hal_dac.h" +#endif /* HAL_DAC_MODULE_ENABLED */ + +#ifdef HAL_DCMI_MODULE_ENABLED + #include "stm32f7xx_hal_dcmi.h" +#endif /* HAL_DCMI_MODULE_ENABLED */ + +#ifdef HAL_ETH_MODULE_ENABLED + #include "stm32f7xx_hal_eth.h" +#endif /* HAL_ETH_MODULE_ENABLED */ + +#ifdef HAL_FLASH_MODULE_ENABLED + #include "stm32f7xx_hal_flash.h" +#endif /* HAL_FLASH_MODULE_ENABLED */ + +#ifdef HAL_SRAM_MODULE_ENABLED + #include "stm32f7xx_hal_sram.h" +#endif /* HAL_SRAM_MODULE_ENABLED */ + +#ifdef HAL_NOR_MODULE_ENABLED + #include "stm32f7xx_hal_nor.h" +#endif /* HAL_NOR_MODULE_ENABLED */ + +#ifdef HAL_NAND_MODULE_ENABLED + #include "stm32f7xx_hal_nand.h" +#endif /* HAL_NAND_MODULE_ENABLED */ + +#ifdef HAL_SDRAM_MODULE_ENABLED + #include "stm32f7xx_hal_sdram.h" +#endif /* HAL_SDRAM_MODULE_ENABLED */ + +#ifdef HAL_HASH_MODULE_ENABLED + #include "stm32f7xx_hal_hash.h" +#endif /* HAL_HASH_MODULE_ENABLED */ + +#ifdef HAL_I2C_MODULE_ENABLED + #include "stm32f7xx_hal_i2c.h" +#endif /* HAL_I2C_MODULE_ENABLED */ + +#ifdef HAL_I2S_MODULE_ENABLED + #include "stm32f7xx_hal_i2s.h" +#endif /* HAL_I2S_MODULE_ENABLED */ + +#ifdef HAL_IWDG_MODULE_ENABLED + #include "stm32f7xx_hal_iwdg.h" +#endif /* HAL_IWDG_MODULE_ENABLED */ + +#ifdef HAL_LPTIM_MODULE_ENABLED + #include "stm32f7xx_hal_lptim.h" +#endif /* HAL_LPTIM_MODULE_ENABLED */ + +#ifdef HAL_LTDC_MODULE_ENABLED + #include "stm32f7xx_hal_ltdc.h" +#endif /* HAL_LTDC_MODULE_ENABLED */ + +#ifdef HAL_PWR_MODULE_ENABLED + #include "stm32f7xx_hal_pwr.h" +#endif /* HAL_PWR_MODULE_ENABLED */ + +#ifdef HAL_QSPI_MODULE_ENABLED + #include "stm32f7xx_hal_qspi.h" +#endif /* HAL_QSPI_MODULE_ENABLED */ + +#ifdef HAL_RNG_MODULE_ENABLED + #include "stm32f7xx_hal_rng.h" +#endif /* HAL_RNG_MODULE_ENABLED */ + +#ifdef HAL_RTC_MODULE_ENABLED + #include "stm32f7xx_hal_rtc.h" +#endif /* HAL_RTC_MODULE_ENABLED */ + +#ifdef HAL_SAI_MODULE_ENABLED + #include "stm32f7xx_hal_sai.h" +#endif /* HAL_SAI_MODULE_ENABLED */ + +#ifdef HAL_SD_MODULE_ENABLED + #include "stm32f7xx_hal_sd.h" +#endif /* HAL_SD_MODULE_ENABLED */ + +#ifdef HAL_SPDIFRX_MODULE_ENABLED + #include "stm32f7xx_hal_spdifrx.h" +#endif /* HAL_SPDIFRX_MODULE_ENABLED */ + +#ifdef HAL_SPI_MODULE_ENABLED + #include "stm32f7xx_hal_spi.h" +#endif /* HAL_SPI_MODULE_ENABLED */ + +#ifdef HAL_TIM_MODULE_ENABLED + #include "stm32f7xx_hal_tim.h" +#endif /* HAL_TIM_MODULE_ENABLED */ + +#ifdef HAL_UART_MODULE_ENABLED + #include "stm32f7xx_hal_uart.h" +#endif /* HAL_UART_MODULE_ENABLED */ + +#ifdef HAL_USART_MODULE_ENABLED + #include "stm32f7xx_hal_usart.h" +#endif /* HAL_USART_MODULE_ENABLED */ + +#ifdef HAL_IRDA_MODULE_ENABLED + #include "stm32f7xx_hal_irda.h" +#endif /* HAL_IRDA_MODULE_ENABLED */ + +#ifdef HAL_SMARTCARD_MODULE_ENABLED + #include "stm32f7xx_hal_smartcard.h" +#endif /* HAL_SMARTCARD_MODULE_ENABLED */ + +#ifdef HAL_WWDG_MODULE_ENABLED + #include "stm32f7xx_hal_wwdg.h" +#endif /* HAL_WWDG_MODULE_ENABLED */ + +#ifdef HAL_PCD_MODULE_ENABLED + #include "stm32f7xx_hal_pcd.h" +#endif /* HAL_PCD_MODULE_ENABLED */ + +#ifdef HAL_HCD_MODULE_ENABLED + #include "stm32f7xx_hal_hcd.h" +#endif /* HAL_HCD_MODULE_ENABLED */ + +#ifdef HAL_DFSDM_MODULE_ENABLED + #include "stm32f7xx_hal_dfsdm.h" +#endif /* HAL_DFSDM_MODULE_ENABLED */ + +#ifdef HAL_DSI_MODULE_ENABLED + #include "stm32f7xx_hal_dsi.h" +#endif /* HAL_DSI_MODULE_ENABLED */ + +#ifdef HAL_JPEG_MODULE_ENABLED + #include "stm32f7xx_hal_jpeg.h" +#endif /* HAL_JPEG_MODULE_ENABLED */ + +#ifdef HAL_MDIOS_MODULE_ENABLED + #include "stm32f7xx_hal_mdios.h" +#endif /* HAL_MDIOS_MODULE_ENABLED */ + +/* Exported macro ------------------------------------------------------------*/ +#ifdef USE_FULL_ASSERT +/** + * @brief The assert_param macro is used for function's parameters check. + * @param expr: If expr is false, it calls assert_failed function + * which reports the name of the source file and the source + * line number of the call that failed. + * If expr is true, it returns no value. + * @retval None + */ + #define assert_param(expr) ((expr) ? (void)0 : assert_failed((uint8_t *)__FILE__, __LINE__)) +/* Exported functions ------------------------------------------------------- */ + void assert_failed(uint8_t* file, uint32_t line); +#else + #define assert_param(expr) ((void)0U) +#endif /* USE_FULL_ASSERT */ + + +#ifdef __cplusplus +} +#endif + +#endif /* __STM32F7xx_HAL_CONF_H */ + + +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ From 05bfd9ac4a804f6f8053bdbc8ee83813ad623fa0 Mon Sep 17 00:00:00 2001 From: Uwe Bonnes Date: Tue, 23 Jun 2020 13:07:33 +0200 Subject: [PATCH 26/48] dcd_synopsys: Handle HS and FS IP in one device FIXME: Allow run-time selection to allow to handle both HS and FS with one file F746 HS port enumerates with error config 1 interface 2 altsetting 0 bulk endpoint 0x3 has invalid maxpacket 64 --- src/portable/st/synopsys/dcd_synopsys.c | 44 ++++++++++++++++--------- 1 file changed, 29 insertions(+), 15 deletions(-) diff --git a/src/portable/st/synopsys/dcd_synopsys.c b/src/portable/st/synopsys/dcd_synopsys.c index 845aecf1e..6e26fd09a 100644 --- a/src/portable/st/synopsys/dcd_synopsys.c +++ b/src/portable/st/synopsys/dcd_synopsys.c @@ -53,33 +53,39 @@ // EP_FIFO_SIZE : Size of dedicated USB SRAM #if CFG_TUSB_MCU == OPT_MCU_STM32F1 #include "stm32f1xx.h" - #define EP_MAX 4 - #define EP_FIFO_SIZE 1280 + #define EP_MAX_FS 4 + #define EP_FIFO_SIZE_FS 1280 #elif CFG_TUSB_MCU == OPT_MCU_STM32F2 #include "stm32f2xx.h" - #define EP_MAX USB_OTG_FS_MAX_IN_ENDPOINTS - #define EP_FIFO_SIZE USB_OTG_FS_TOTAL_FIFO_SIZE + #define EP_MAX_FS USB_OTG_FS_MAX_IN_ENDPOINTS + #define EP_FIFO_SIZE_FS USB_OTG_FS_TOTAL_FIFO_SIZE #elif CFG_TUSB_MCU == OPT_MCU_STM32F4 #include "stm32f4xx.h" - #define EP_MAX USB_OTG_FS_MAX_IN_ENDPOINTS - #define EP_FIFO_SIZE USB_OTG_FS_TOTAL_FIFO_SIZE + #define EP_MAX_FS USB_OTG_FS_MAX_IN_ENDPOINTS + #define EP_FIFO_SIZE_FS USB_OTG_FS_TOTAL_FIFO_SIZE + #define EP_MAX_HS USB_OTG_HS_MAX_IN_ENDPOINTS + #define EP_FIFO_SIZE_HS USB_OTG_HS_TOTAL_FIFO_SIZE #elif CFG_TUSB_MCU == OPT_MCU_STM32H7 #include "stm32h7xx.h" - #define EP_MAX 9 - #define EP_FIFO_SIZE 4096 + #define EP_MAX_FS 9 + #define EP_FIFO_SIZE_FS 4096 + #define EP_MAX_HS 9 + #define EP_FIFO_SIZE_HS 4096 #elif CFG_TUSB_MCU == OPT_MCU_STM32F7 #include "stm32f7xx.h" - #define EP_MAX 6 - #define EP_FIFO_SIZE 1280 + #define EP_MAX_FS 6 + #define EP_FIFO_SIZE_FS 1280 + #define EP_MAX_HS 9 + #define EP_FIFO_SIZE_HS 4096 #elif CFG_TUSB_MCU == OPT_MCU_STM32L4 #include "stm32l4xx.h" - #define EP_MAX 6 - #define EP_FIFO_SIZE 1280 + #define EP_MAX_FS 6 + #define EP_FIFO_SIZE_FS 1280 #else #error "Unsupported MCUs" @@ -140,7 +146,15 @@ typedef struct { typedef volatile uint32_t * usb_fifo_t; -xfer_ctl_t xfer_status[EP_MAX][2]; +#if TUD_OPT_RHPORT == 1 +xfer_ctl_t xfer_status[EP_MAX_HS][2]; +# define EP_MAX EP_MAX_HS +# define EP_FIFO_SIZE EP_FIFO_SIZE_HS +#else +xfer_ctl_t xfer_status[EP_MAX_FS][2]; +# define EP_MAX EP_MAX_FS +# define EP_FIFO_SIZE EP_FIFO_SIZE_FS +#endif #define XFER_CTL_BASE(_ep, _dir) &xfer_status[_ep][_dir] // EP0 transfers are limited to 1 packet - larger sizes has to be split @@ -206,9 +220,9 @@ static void bus_reset(uint8_t rhport) // overwrite this. #if TUD_OPT_HIGH_SPEED - _allocated_fifo_words = 271 + 2*EP_MAX; + _allocated_fifo_words = 271 + 2*EP_MAX_HS; #else - _allocated_fifo_words = 47 + 2*EP_MAX; + _allocated_fifo_words = 47 + 2*EP_MAX_FS; #endif usb_otg->GRXFSIZ = _allocated_fifo_words; From 62239bb576c37e8e240879e5783d4f181f42877e Mon Sep 17 00:00:00 2001 From: Uwe Bonnes Date: Tue, 23 Jun 2020 13:55:07 +0200 Subject: [PATCH 27/48] cdc-acm: Use 512 bytes when in HS mode. Removes error: config 1 interface 2 altsetting 0 bulk endpoint 0x3 has invalid maxpacket 64 while enumerationg. --- examples/device/cdc_msc/src/tusb_config.h | 4 ++-- examples/device/cdc_msc/src/usb_descriptors.c | 2 +- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/examples/device/cdc_msc/src/tusb_config.h b/examples/device/cdc_msc/src/tusb_config.h index c57c2ead8..13021d5d3 100644 --- a/examples/device/cdc_msc/src/tusb_config.h +++ b/examples/device/cdc_msc/src/tusb_config.h @@ -102,8 +102,8 @@ #define CFG_TUD_VENDOR 0 // CDC FIFO size of TX and RX -#define CFG_TUD_CDC_RX_BUFSIZE 64 -#define CFG_TUD_CDC_TX_BUFSIZE 64 +#define CFG_TUD_CDC_RX_BUFSIZE (TUD_OPT_HIGH_SPEED ? 512 : 64) +#define CFG_TUD_CDC_TX_BUFSIZE (TUD_OPT_HIGH_SPEED ? 512 : 64) // MSC Buffer size of Device Mass storage #define CFG_TUD_MSC_BUFSIZE 512 diff --git a/examples/device/cdc_msc/src/usb_descriptors.c b/examples/device/cdc_msc/src/usb_descriptors.c index 62ab4f10f..9a4d71f24 100644 --- a/examples/device/cdc_msc/src/usb_descriptors.c +++ b/examples/device/cdc_msc/src/usb_descriptors.c @@ -120,7 +120,7 @@ uint8_t const desc_configuration[] = TUD_CONFIG_DESCRIPTOR(1, ITF_NUM_TOTAL, 0, CONFIG_TOTAL_LEN, TUSB_DESC_CONFIG_ATT_REMOTE_WAKEUP, 100), // Interface number, string index, EP notification address and size, EP data address (out, in) and size. - TUD_CDC_DESCRIPTOR(ITF_NUM_CDC, 4, EPNUM_CDC_NOTIF, 8, EPNUM_CDC_OUT, EPNUM_CDC_IN, 64), + TUD_CDC_DESCRIPTOR(ITF_NUM_CDC, 4, EPNUM_CDC_NOTIF, 8, EPNUM_CDC_OUT, EPNUM_CDC_IN, TUD_OPT_HIGH_SPEED ? 512 : 64), // Interface number, string index, EP Out & EP In address, EP size TUD_MSC_DESCRIPTOR(ITF_NUM_MSC, 5, EPNUM_MSC_OUT, EPNUM_MSC_IN, TUD_OPT_HIGH_SPEED ? 512 : 64), From 30a18e260562194b0541584600a0cfc88b1ef178 Mon Sep 17 00:00:00 2001 From: Uwe Bonnes Date: Wed, 24 Jun 2020 16:25:23 +0200 Subject: [PATCH 28/48] stm32f723disco: USB HS enumerates. --- hw/bsp/stm32f723disco/stm32f723disco.c | 6 +- src/portable/st/synopsys/dcd_synopsys.c | 87 +++++++++++++++++++++++-- 2 files changed, 85 insertions(+), 8 deletions(-) diff --git a/hw/bsp/stm32f723disco/stm32f723disco.c b/hw/bsp/stm32f723disco/stm32f723disco.c index 03057edc7..eeedd2a66 100644 --- a/hw/bsp/stm32f723disco/stm32f723disco.c +++ b/hw/bsp/stm32f723disco/stm32f723disco.c @@ -217,7 +217,7 @@ void board_init(void) GPIO_InitStruct.Pin = (GPIO_PIN_14 | GPIO_PIN_15); GPIO_InitStruct.Mode = GPIO_MODE_AF_PP; GPIO_InitStruct.Pull = GPIO_NOPULL; - GPIO_InitStruct.Speed = GPIO_SPEED_VERY_HIGH; + GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_HIGH; GPIO_InitStruct.Alternate = GPIO_AF10_OTG_HS; HAL_GPIO_Init(GPIOB, &GPIO_InitStruct); @@ -231,8 +231,12 @@ void board_init(void) GPIO_InitStruct.Alternate = GPIO_AF10_OTG_HS; HAL_GPIO_Init(GPIOD, &GPIO_InitStruct); + /* Enable PHYC Clocks */ + __HAL_RCC_OTGPHYC_CLK_ENABLE(); + /* Enable USB HS Clocks */ __HAL_RCC_USB_OTG_HS_CLK_ENABLE(); + __HAL_RCC_USB_OTG_HS_ULPI_CLK_ENABLE(); // Enable VBUS sense (B device) via pin PA9 USB_OTG_HS->GCCFG &= ~USB_OTG_GCCFG_VBDEN; diff --git a/src/portable/st/synopsys/dcd_synopsys.c b/src/portable/st/synopsys/dcd_synopsys.c index 6e26fd09a..ba3cc3460 100644 --- a/src/portable/st/synopsys/dcd_synopsys.c +++ b/src/portable/st/synopsys/dcd_synopsys.c @@ -27,6 +27,7 @@ */ #include "tusb_option.h" +#include "../../../../hw/bsp//board.h" #if defined (STM32F105x8) || defined (STM32F105xB) || defined (STM32F105xC) || \ defined (STM32F107xB) || defined (STM32F107xC) @@ -147,14 +148,13 @@ typedef struct { typedef volatile uint32_t * usb_fifo_t; #if TUD_OPT_RHPORT == 1 -xfer_ctl_t xfer_status[EP_MAX_HS][2]; # define EP_MAX EP_MAX_HS # define EP_FIFO_SIZE EP_FIFO_SIZE_HS #else -xfer_ctl_t xfer_status[EP_MAX_FS][2]; # define EP_MAX EP_MAX_FS # define EP_FIFO_SIZE EP_FIFO_SIZE_FS #endif +xfer_ctl_t xfer_status[EP_MAX][2]; #define XFER_CTL_BASE(_ep, _dir) &xfer_status[_ep][_dir] // EP0 transfers are limited to 1 packet - larger sizes has to be split @@ -220,9 +220,9 @@ static void bus_reset(uint8_t rhport) // overwrite this. #if TUD_OPT_HIGH_SPEED - _allocated_fifo_words = 271 + 2*EP_MAX_HS; + _allocated_fifo_words = 271 + 2*EP_MAX; #else - _allocated_fifo_words = 47 + 2*EP_MAX_FS; + _allocated_fifo_words = 47 + 2*EP_MAX; #endif usb_otg->GRXFSIZ = _allocated_fifo_words; @@ -301,6 +301,59 @@ static void edpt_schedule_packets(uint8_t rhport, uint8_t const epnum, uint8_t c } +# if defined(USB_HS_PHYC) && TUD_OPT_HIGH_SPEED +static bool USB_HS_PHYCInit(void) +{ + USB_HS_PHYC_GlobalTypeDef *usb_hs_phyc = (USB_HS_PHYC_GlobalTypeDef *)USB_HS_PHYC_CONTROLLER_BASE; + // Enable LDO + usb_hs_phyc->USB_HS_PHYC_LDO |= USB_HS_PHYC_LDO_ENABLE; + int32_t count = 2000000; + while(1) { + if (usb_hs_phyc->USB_HS_PHYC_LDO & USB_HS_PHYC_LDO_STATUS) + break; + TU_ASSERT(count > 0); + } + uint32_t phyc_pll = 0; + switch (HSE_VALUE) { + case 12000000: + phyc_pll = USB_HS_PHYC_PLL1_PLLSEL_12MHZ; + break; + case 12500000: + phyc_pll = USB_HS_PHYC_PLL1_PLLSEL_12_5MHZ; + break; + case 16000000: + phyc_pll = USB_HS_PHYC_PLL1_PLLSEL_16MHZ; + break; + case 24000000: + phyc_pll = USB_HS_PHYC_PLL1_PLLSEL_24MHZ; + break; + case 25000000: + phyc_pll = USB_HS_PHYC_PLL1_PLLSEL_25MHZ; + break; + case 32000000: + // Value not defined in header + phyc_pll = USB_HS_PHYC_PLL1_PLLSEL_Msk; + break; + default: + TU_ASSERT(0); + } + usb_hs_phyc->USB_HS_PHYC_PLL = phyc_pll; + + // Use magic value as in stm32f7xx_ll_usb. +# if !defined (USB_HS_PHYC_TUNE_VALUE) +# define USB_HS_PHYC_TUNE_VALUE 0x00000F13U /*!< Value of USB HS PHY Tune */ +# endif /* USB_HS_PHYC_TUNE_VALUE */ + // Control the tuning interface of the High Speed PHY */ + usb_hs_phyc->USB_HS_PHYC_TUNE |= USB_HS_PHYC_TUNE_VALUE; + + // Enable PLL internal PHY + usb_hs_phyc->USB_HS_PHYC_PLL = phyc_pll | USB_HS_PHYC_PLL_PLLEN; + + board_delay(2); + return true; +} +# endif + /*------------------------------------------------------------------*/ /* Controller API *------------------------------------------------------------------*/ @@ -315,12 +368,31 @@ void dcd_init (uint8_t rhport) #if TUD_OPT_HIGH_SPEED // TODO may pass parameter instead of using macro for HighSpeed if ( rhport == 1 ) { - // Highspeed with external ULPI PHY - // deactivate internal PHY usb_otg->GCCFG &= ~USB_OTG_GCCFG_PWRDWN; - // On selected MCUs HS port1 can be used with external PHY via ULPI interface + // TODO may pass parameter instead of using macro for HighSpeed +#if defined(USB_HS_PHYC) + // Highspeed with embedded UTMI PHYC + // Init The UTMI Interface + usb_otg->GUSBCFG &= ~(USB_OTG_GUSBCFG_TSDPS | USB_OTG_GUSBCFG_ULPIFSLS | USB_OTG_GUSBCFG_PHYSEL); + + // Select vbus source + usb_otg->GUSBCFG &= ~(USB_OTG_GUSBCFG_ULPIEVBUSD | USB_OTG_GUSBCFG_ULPIEVBUSI); + + // Select UTMI Interace + usb_otg->GUSBCFG &= ~USB_OTG_GUSBCFG_ULPI_UTMI_SEL; + usb_otg->GCCFG |= USB_OTG_GCCFG_PHYHSEN; + + //Enables control of a High Speed USB PHY + USB_HS_PHYCInit(); + + // Disable external VBUS detection + usb_otg->GUSBCFG &= ~USB_OTG_GUSBCFG_ULPIEVBUSD; + +# else// On selected MCUs HS port1 can be used with external PHY via ULPI interface + // Highspeed with external ULPI PHY + // Init ULPI Interface usb_otg->GUSBCFG &= ~(USB_OTG_GUSBCFG_TSDPS | USB_OTG_GUSBCFG_ULPIFSLS | USB_OTG_GUSBCFG_PHYSEL); @@ -328,6 +400,7 @@ void dcd_init (uint8_t rhport) usb_otg->GUSBCFG &= ~(USB_OTG_GUSBCFG_ULPIEVBUSD | USB_OTG_GUSBCFG_ULPIEVBUSI); set_turnaround(usb_otg, TUSB_SPEED_HIGH); +# endif } else #endif From f3a88477dc39a5eccc8d4de61d8943ace2b74e44 Mon Sep 17 00:00:00 2001 From: hathach Date: Tue, 30 Jun 2020 16:18:43 +0700 Subject: [PATCH 29/48] revert rhport config in nxp mcus --- hw/bsp/ea4357/ea4357.c | 8 ++++---- hw/bsp/mcb1800/mcb1800.c | 8 ++++---- hw/bsp/mimxrt1050_evkb/mimxrt1050_evkb.c | 4 ++-- hw/bsp/mimxrt1060_evk/mimxrt1060_evk.c | 4 ++-- hw/bsp/mimxrt1064_evk/mimxrt1064_evk.c | 4 ++-- hw/bsp/ngx4330/ngx4330.c | 8 ++++---- hw/bsp/teensy_40/teensy40.c | 4 ++-- 7 files changed, 20 insertions(+), 20 deletions(-) diff --git a/hw/bsp/ea4357/ea4357.c b/hw/bsp/ea4357/ea4357.c index 04c4e60a6..b7e7f7a5c 100644 --- a/hw/bsp/ea4357/ea4357.c +++ b/hw/bsp/ea4357/ea4357.c @@ -149,7 +149,7 @@ void board_init(void) * status feedback from the distribution switch. GPIO54 is used for VBUS sensing. 15Kohm pull-down * resistors are always active */ -#if CFG_TUSB_RHPORT0_MODE & (OPT_MODE_DEVICE | OPT_MODE_HOST) +#if CFG_TUSB_RHPORT0_MODE Chip_USB0_Init(); // // Reset controller @@ -185,7 +185,7 @@ void board_init(void) * of VBUS can be read via U31. * JP16 shall not be inserted. */ -#if CFG_TUSB_RHPORT0_MODE & ((OPT_MODE_DEVICE | OPT_MODE_HOST) << 8) +#if CFG_TUSB_RHPORT1_MODE Chip_USB1_Init(); // // Reset controller @@ -232,11 +232,11 @@ void USB0_IRQHandler(void) void USB1_IRQHandler(void) { - #if CFG_TUSB_RHPORT0_MODE & (OPT_MODE_HOST << 8) + #if CFG_TUSB_RHPORT1_MODE & OPT_MODE_HOST tuh_isr(1); #endif - #if CFG_TUSB_RHPORT0_MODE & (OPT_MODE_DEVICE << 8) + #if CFG_TUSB_RHPORT1_MODE & OPT_MODE_DEVICE tud_int_handler(1); #endif } diff --git a/hw/bsp/mcb1800/mcb1800.c b/hw/bsp/mcb1800/mcb1800.c index 6387f983e..ae9f1b62f 100644 --- a/hw/bsp/mcb1800/mcb1800.c +++ b/hw/bsp/mcb1800/mcb1800.c @@ -43,11 +43,11 @@ void USB0_IRQHandler(void) void USB1_IRQHandler(void) { - #if CFG_TUSB_RHPORT0_MODE & (OPT_MODE_HOST << 8) + #if CFG_TUSB_RHPORT1_MODE & OPT_MODE_HOST tuh_isr(1); #endif - #if CFG_TUSB_RHPORT0_MODE & (OPT_MODE_DEVICE << 8) + #if CFG_TUSB_RHPORT1_MODE & OPT_MODE_DEVICE tud_int_handler(1); #endif } @@ -163,7 +163,7 @@ void board_init(void) }; // USB0 -#if CFG_TUSB_RHPORT0_MODE & (OPT_MODE_DEVICE | OPT_MODE_HOST) +#if CFG_TUSB_RHPORT0_MODE Chip_USB0_Init(); // // Reset controller @@ -180,7 +180,7 @@ void board_init(void) #endif // USB1 -#if CFG_TUSB_RHPORT0_MODE & ((OPT_MODE_DEVICE | OPT_MODE_HOST) << 8) +#if CFG_TUSB_RHPORT1_MODE Chip_USB1_Init(); // // Reset controller diff --git a/hw/bsp/mimxrt1050_evkb/mimxrt1050_evkb.c b/hw/bsp/mimxrt1050_evkb/mimxrt1050_evkb.c index 8dae7a0c2..be0ae3ea8 100644 --- a/hw/bsp/mimxrt1050_evkb/mimxrt1050_evkb.c +++ b/hw/bsp/mimxrt1050_evkb/mimxrt1050_evkb.c @@ -134,11 +134,11 @@ void USB_OTG1_IRQHandler(void) void USB_OTG2_IRQHandler(void) { - #if CFG_TUSB_RHPORT0_MODE & (OPT_MODE_HOST << 8) + #if CFG_TUSB_RHPORT1_MODE & OPT_MODE_HOST tuh_isr(1); #endif - #if CFG_TUSB_RHPORT0_MODE & (OPT_MODE_DEVICE << 8) + #if CFG_TUSB_RHPORT1_MODE & OPT_MODE_DEVICE tud_int_handler(1); #endif } diff --git a/hw/bsp/mimxrt1060_evk/mimxrt1060_evk.c b/hw/bsp/mimxrt1060_evk/mimxrt1060_evk.c index 8dae7a0c2..0f55c2b00 100644 --- a/hw/bsp/mimxrt1060_evk/mimxrt1060_evk.c +++ b/hw/bsp/mimxrt1060_evk/mimxrt1060_evk.c @@ -134,11 +134,11 @@ void USB_OTG1_IRQHandler(void) void USB_OTG2_IRQHandler(void) { - #if CFG_TUSB_RHPORT0_MODE & (OPT_MODE_HOST << 8) + #if CFG_TUSB_RHPORT0_MODE & OPT_MODE_HOST tuh_isr(1); #endif - #if CFG_TUSB_RHPORT0_MODE & (OPT_MODE_DEVICE << 8) + #if CFG_TUSB_RHPORT1_MODE & OPT_MODE_DEVICE tud_int_handler(1); #endif } diff --git a/hw/bsp/mimxrt1064_evk/mimxrt1064_evk.c b/hw/bsp/mimxrt1064_evk/mimxrt1064_evk.c index 8dae7a0c2..be0ae3ea8 100644 --- a/hw/bsp/mimxrt1064_evk/mimxrt1064_evk.c +++ b/hw/bsp/mimxrt1064_evk/mimxrt1064_evk.c @@ -134,11 +134,11 @@ void USB_OTG1_IRQHandler(void) void USB_OTG2_IRQHandler(void) { - #if CFG_TUSB_RHPORT0_MODE & (OPT_MODE_HOST << 8) + #if CFG_TUSB_RHPORT1_MODE & OPT_MODE_HOST tuh_isr(1); #endif - #if CFG_TUSB_RHPORT0_MODE & (OPT_MODE_DEVICE << 8) + #if CFG_TUSB_RHPORT1_MODE & OPT_MODE_DEVICE tud_int_handler(1); #endif } diff --git a/hw/bsp/ngx4330/ngx4330.c b/hw/bsp/ngx4330/ngx4330.c index 85d11d6ad..5296ddcb3 100644 --- a/hw/bsp/ngx4330/ngx4330.c +++ b/hw/bsp/ngx4330/ngx4330.c @@ -161,7 +161,7 @@ void board_init(void) * status feedback from the distribution switch. GPIO54 is used for VBUS sensing. 15Kohm pull-down * resistors are always active */ -#if CFG_TUSB_RHPORT0_MODE & (OPT_MODE_DEVICE | OPT_MODE_HOST) +#if CFG_TUSB_RHPORT0_MODE Chip_USB0_Init(); // // Reset controller @@ -197,7 +197,7 @@ void board_init(void) * of VBUS can be read via U31. * JP16 shall not be inserted. */ -#if CFG_TUSB_RHPORT0_MODE & ((OPT_MODE_DEVICE | OPT_MODE_HOST) << 8) +#if CFG_TUSB_RHPORT1_MODE Chip_USB1_Init(); // // Reset controller @@ -235,11 +235,11 @@ void USB0_IRQHandler(void) void USB1_IRQHandler(void) { - #if CFG_TUSB_RHPORT0_MODE & (OPT_MODE_HOST << 8) + #if CFG_TUSB_RHPORT1_MODE & OPT_MODE_HOST tuh_isr(1); #endif - #if CFG_TUSB_RHPORT0_MODE & (OPT_MODE_DEVICE << 8) + #if CFG_TUSB_RHPORT1_MODE & OPT_MODE_DEVICE tud_int_handler(1); #endif } diff --git a/hw/bsp/teensy_40/teensy40.c b/hw/bsp/teensy_40/teensy40.c index 0ca86f602..f45a98ef3 100644 --- a/hw/bsp/teensy_40/teensy40.c +++ b/hw/bsp/teensy_40/teensy40.c @@ -135,11 +135,11 @@ void USB_OTG1_IRQHandler(void) void USB_OTG2_IRQHandler(void) { - #if CFG_TUSB_RHPORT0_MODE & (OPT_MODE_HOST << 8) + #if CFG_TUSB_RHPORT1_MODE & OPT_MODE_HOST tuh_isr(1); #endif - #if CFG_TUSB_RHPORT0_MODE & (OPT_MODE_DEVICE << 8) + #if CFG_TUSB_RHPORT1_MODE & OPT_MODE_DEVICE tud_int_handler(1); #endif } From 0477446224c1c193f5ae8a0cbed7c33e13e7ce6c Mon Sep 17 00:00:00 2001 From: hathach Date: Tue, 30 Jun 2020 16:31:59 +0700 Subject: [PATCH 30/48] more clean up --- CONTRIBUTORS.md | 7 +++---- hw/bsp/mimxrt1060_evk/mimxrt1060_evk.c | 2 +- 2 files changed, 4 insertions(+), 5 deletions(-) diff --git a/CONTRIBUTORS.md b/CONTRIBUTORS.md index ef691c98a..f7d77afe3 100644 --- a/CONTRIBUTORS.md +++ b/CONTRIBUTORS.md @@ -12,6 +12,9 @@ * Author and maintainer * Most features development +* **[Jan Dümpelmann](https://github.com/duempel)** + * Improvements to Synopsys device controller driver (DCD) for STM32 MCUs + * **[Jeff Epler](https://github.com/jepler)** * Improvement to MIDI device driver @@ -57,8 +60,4 @@ * TI MSP430 device driver port * Board support for STM32F407 Discovery, STM32H743 Nucleo, pyboard v1.1, msp_exp430f5529lp etc ... -* **[Jan Dümpelmann](https://github.com/duempel)** - * Improvements to Synopsys device controller driver (DCD) for STM32 MCUs - - **[Full contributors list](https://github.com/hathach/tinyusb/contributors).** diff --git a/hw/bsp/mimxrt1060_evk/mimxrt1060_evk.c b/hw/bsp/mimxrt1060_evk/mimxrt1060_evk.c index 0f55c2b00..be0ae3ea8 100644 --- a/hw/bsp/mimxrt1060_evk/mimxrt1060_evk.c +++ b/hw/bsp/mimxrt1060_evk/mimxrt1060_evk.c @@ -134,7 +134,7 @@ void USB_OTG1_IRQHandler(void) void USB_OTG2_IRQHandler(void) { - #if CFG_TUSB_RHPORT0_MODE & OPT_MODE_HOST + #if CFG_TUSB_RHPORT1_MODE & OPT_MODE_HOST tuh_isr(1); #endif From ed1b670c55053c1fdb6b5ec0c543fe81d95989e4 Mon Sep 17 00:00:00 2001 From: hathach Date: Wed, 1 Jul 2020 17:57:37 +0700 Subject: [PATCH 31/48] clean up code --- src/portable/st/synopsys/dcd_synopsys.c | 64 +++++++++++-------------- 1 file changed, 27 insertions(+), 37 deletions(-) diff --git a/src/portable/st/synopsys/dcd_synopsys.c b/src/portable/st/synopsys/dcd_synopsys.c index ba3cc3460..f6d064228 100644 --- a/src/portable/st/synopsys/dcd_synopsys.c +++ b/src/portable/st/synopsys/dcd_synopsys.c @@ -243,7 +243,7 @@ static void bus_reset(uint8_t rhport) usb_otg->GINTMSK |= USB_OTG_GINTMSK_OEPINT | USB_OTG_GINTMSK_IEPINT; } -// speed is native DCD speed +// Set turn-around timeout according to link speed static void set_turnaround(USB_OTG_GlobalTypeDef * usb_otg, tusb_speed_t speed) { usb_otg->GUSBCFG &= ~USB_OTG_GUSBCFG_TRDT; @@ -368,47 +368,40 @@ void dcd_init (uint8_t rhport) #if TUD_OPT_HIGH_SPEED // TODO may pass parameter instead of using macro for HighSpeed if ( rhport == 1 ) { + // On selected MCUs HS port1 can be used with external PHY via ULPI interface + // deactivate internal PHY usb_otg->GCCFG &= ~USB_OTG_GCCFG_PWRDWN; - // TODO may pass parameter instead of using macro for HighSpeed -#if defined(USB_HS_PHYC) - // Highspeed with embedded UTMI PHYC // Init The UTMI Interface usb_otg->GUSBCFG &= ~(USB_OTG_GUSBCFG_TSDPS | USB_OTG_GUSBCFG_ULPIFSLS | USB_OTG_GUSBCFG_PHYSEL); - // Select vbus source - usb_otg->GUSBCFG &= ~(USB_OTG_GUSBCFG_ULPIEVBUSD | USB_OTG_GUSBCFG_ULPIEVBUSI); - - // Select UTMI Interace - usb_otg->GUSBCFG &= ~USB_OTG_GUSBCFG_ULPI_UTMI_SEL; - usb_otg->GCCFG |= USB_OTG_GCCFG_PHYHSEN; - - //Enables control of a High Speed USB PHY - USB_HS_PHYCInit(); - - // Disable external VBUS detection - usb_otg->GUSBCFG &= ~USB_OTG_GUSBCFG_ULPIEVBUSD; - -# else// On selected MCUs HS port1 can be used with external PHY via ULPI interface - // Highspeed with external ULPI PHY - - // Init ULPI Interface - usb_otg->GUSBCFG &= ~(USB_OTG_GUSBCFG_TSDPS | USB_OTG_GUSBCFG_ULPIFSLS | USB_OTG_GUSBCFG_PHYSEL); - // Select default internal VBUS Indicator and Drive for ULPI usb_otg->GUSBCFG &= ~(USB_OTG_GUSBCFG_ULPIEVBUSD | USB_OTG_GUSBCFG_ULPIEVBUSI); +#if defined(USB_HS_PHYC) + // Highspeed with embedded UTMI PHYC + + // Select UTMI Interface + usb_otg->GUSBCFG &= ~USB_OTG_GUSBCFG_ULPI_UTMI_SEL; + usb_otg->GCCFG |= USB_OTG_GCCFG_PHYHSEN; + + // Enables control of a High Speed USB PHY + USB_HS_PHYCInit(); + + // Disable external VBUS detection + usb_otg->GUSBCFG &= ~USB_OTG_GUSBCFG_ULPIEVBUSD; +#endif + + // Highspeed with external ULPI PHY set_turnaround(usb_otg, TUSB_SPEED_HIGH); -# endif - } - else + } else #endif { - set_turnaround(usb_otg, TUSB_SPEED_FULL); - // Enable internal PHY usb_otg->GUSBCFG |= USB_OTG_GUSBCFG_PHYSEL; + + set_turnaround(usb_otg, TUSB_SPEED_FULL); } // Reset core after selecting PHY @@ -434,20 +427,17 @@ void dcd_init (uint8_t rhport) // (non zero-length packet), send STALL back and discard. dev->DCFG |= USB_OTG_DCFG_NZLSOHSK; -#if TUD_OPT_HIGH_SPEED + // Clear speed bits + dev->DCFG &= ~(3 << USB_OTG_DCFG_DSPD_Pos); + if ( rhport == 1 ) { - // high speed = 0x00 - dev->DCFG &= ~(3 << USB_OTG_DCFG_DSPD_Pos); - - // Transceiver delay, necessary for some ULPI PHYs - //dev->DCFG |= (1 << 14); + if ( !TUD_OPT_HIGH_SPEED ) dev->DCFG |= ((TUD_OPT_HIGH_SPEED ? DCD_HIGH_SPEED : DCD_FULL_SPEED_USE_HS) << USB_OTG_DCFG_DSPD_Pos); } else -#endif { - // full speed with internal PHY - dev->DCFG |= (3 << USB_OTG_DCFG_DSPD_Pos); + // full speed = 0x03 + dev->DCFG |= (DCD_FULL_SPEED << USB_OTG_DCFG_DSPD_Pos); // Enable internal USB transceiver. usb_otg->GCCFG |= USB_OTG_GCCFG_PWRDWN; From 77315ba7ce65291b7f77b6258c4546c7dfde0246 Mon Sep 17 00:00:00 2001 From: hathach Date: Wed, 1 Jul 2020 18:27:48 +0700 Subject: [PATCH 32/48] added uart for h743 --- hw/bsp/stm32h743eval/stm32h743eval.c | 22 ++++++++++------------ 1 file changed, 10 insertions(+), 12 deletions(-) diff --git a/hw/bsp/stm32h743eval/stm32h743eval.c b/hw/bsp/stm32h743eval/stm32h743eval.c index 772edf33c..6a51d8884 100644 --- a/hw/bsp/stm32h743eval/stm32h743eval.c +++ b/hw/bsp/stm32h743eval/stm32h743eval.c @@ -61,6 +61,7 @@ void OTG_HS_IRQHandler(void) #define BUTTON_PIN GPIO_PIN_13 #define BUTTON_STATE_ACTIVE 0 +// Need to change jumper setting J7 and J8 from RS-232 to STLink #define UARTx USART1 #define UART_GPIO_PORT GPIOB #define UART_GPIO_AF GPIO_AF4_USART1 @@ -74,8 +75,8 @@ static void all_rcc_clk_enable(void) { __HAL_RCC_GPIOA_CLK_ENABLE(); // LED __HAL_RCC_GPIOC_CLK_ENABLE(); // Button -// __HAL_RCC_GPIOB_CLK_ENABLE(); // Uart tx, rx -// __HAL_RCC_USART1_CLK_ENABLE(); // Uart module + __HAL_RCC_GPIOB_CLK_ENABLE(); // Uart tx, rx + __HAL_RCC_USART1_CLK_ENABLE(); // Uart module } /* PWR, RCC, GPIO (All): AHB4 (D3 domain) @@ -197,20 +198,19 @@ void board_init(void) GPIO_InitTypeDef GPIO_InitStruct; // LED - GPIO_InitStruct.Pin = LED_PIN; - GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_PP; - GPIO_InitStruct.Pull = GPIO_PULLUP; + 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); // Button - GPIO_InitStruct.Pin = BUTTON_PIN; - GPIO_InitStruct.Mode = GPIO_MODE_INPUT; - GPIO_InitStruct.Pull = GPIO_NOPULL; + GPIO_InitStruct.Pin = BUTTON_PIN; + GPIO_InitStruct.Mode = GPIO_MODE_INPUT; + GPIO_InitStruct.Pull = GPIO_NOPULL; GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_HIGH; HAL_GPIO_Init(BUTTON_PORT, &GPIO_InitStruct); -#if 0 // Uart GPIO_InitStruct.Pin = UART_TX_PIN | UART_RX_PIN; GPIO_InitStruct.Mode = GPIO_MODE_AF_PP; @@ -228,7 +228,6 @@ void board_init(void) UartHandle.Init.Mode = UART_MODE_TX_RX; UartHandle.Init.OverSampling = UART_OVERSAMPLING_16; HAL_UART_Init(&UartHandle); -#endif #if BOARD_DEVICE_RHPORT_NUM == 0 // Despite being call USB2_OTG @@ -365,8 +364,7 @@ int board_uart_read(uint8_t* buf, int len) int board_uart_write(void const * buf, int len) { - (void) buf; (void) len; -// HAL_UART_Transmit(&UartHandle, (uint8_t*) buf, len, 0xffff); + HAL_UART_Transmit(&UartHandle, (uint8_t*) buf, len, 0xffff); return len; } From e3974d6869fb091609ccffc342031dc779a37f7e Mon Sep 17 00:00:00 2001 From: hathach Date: Wed, 1 Jul 2020 18:44:52 +0700 Subject: [PATCH 33/48] correctly set turn around according to cpu clock help to run with low speed mcu --- src/portable/st/synopsys/dcd_synopsys.c | 27 ++++++++++++++++++++++++- 1 file changed, 26 insertions(+), 1 deletion(-) diff --git a/src/portable/st/synopsys/dcd_synopsys.c b/src/portable/st/synopsys/dcd_synopsys.c index 7ba6b2378..ee8cab5c4 100644 --- a/src/portable/st/synopsys/dcd_synopsys.c +++ b/src/portable/st/synopsys/dcd_synopsys.c @@ -255,8 +255,33 @@ static void set_turnaround(USB_OTG_GlobalTypeDef * usb_otg, tusb_speed_t speed) } else { + // Turnaround timeout depends on the MCU clock + extern uint32_t SystemCoreClock; + uint32_t turnaround; + + if ( SystemCoreClock >= 32000000U ) + turnaround = 0x6U; + else if ( SystemCoreClock >= 27500000U ) + turnaround = 0x7U; + else if ( SystemCoreClock >= 24000000U ) + turnaround = 0x8U; + else if ( SystemCoreClock >= 21800000U ) + turnaround = 0x9U; + else if ( SystemCoreClock >= 20000000U ) + turnaround = 0xAU; + else if ( SystemCoreClock >= 18500000U ) + turnaround = 0xBU; + else if ( SystemCoreClock >= 17200000U ) + turnaround = 0xCU; + else if ( SystemCoreClock >= 16000000U ) + turnaround = 0xDU; + else if ( SystemCoreClock >= 15000000U ) + turnaround = 0xEU; + else + turnaround = 0xFU; + // Fullspeed depends on MCU clocks, but we will use 0x06 for 32+ Mhz - usb_otg->GUSBCFG |= (0x06 << USB_OTG_GUSBCFG_TRDT_Pos); + usb_otg->GUSBCFG |= (turnaround << USB_OTG_GUSBCFG_TRDT_Pos); } } From d2450abaafee659cd30ba2fbd14ff9bdb06f6725 Mon Sep 17 00:00:00 2001 From: hathach Date: Wed, 1 Jul 2020 18:49:58 +0700 Subject: [PATCH 34/48] only set turnaround in reset complete --- src/portable/st/synopsys/dcd_synopsys.c | 7 +------ 1 file changed, 1 insertion(+), 6 deletions(-) diff --git a/src/portable/st/synopsys/dcd_synopsys.c b/src/portable/st/synopsys/dcd_synopsys.c index ee8cab5c4..2adaa762e 100644 --- a/src/portable/st/synopsys/dcd_synopsys.c +++ b/src/portable/st/synopsys/dcd_synopsys.c @@ -417,16 +417,11 @@ void dcd_init (uint8_t rhport) // Disable external VBUS detection usb_otg->GUSBCFG &= ~USB_OTG_GUSBCFG_ULPIEVBUSD; #endif - - // Highspeed with external ULPI PHY - set_turnaround(usb_otg, TUSB_SPEED_HIGH); } else #endif { // Enable internal PHY usb_otg->GUSBCFG |= USB_OTG_GUSBCFG_PHYSEL; - - set_turnaround(usb_otg, TUSB_SPEED_FULL); } // Reset core after selecting PHY @@ -457,7 +452,7 @@ void dcd_init (uint8_t rhport) if ( rhport == 1 ) { - if ( !TUD_OPT_HIGH_SPEED ) dev->DCFG |= ((TUD_OPT_HIGH_SPEED ? DCD_HIGH_SPEED : DCD_FULL_SPEED_USE_HS) << USB_OTG_DCFG_DSPD_Pos); + dev->DCFG |= ((TUD_OPT_HIGH_SPEED ? DCD_HIGH_SPEED : DCD_FULL_SPEED_USE_HS) << USB_OTG_DCFG_DSPD_Pos); } else { From 196bdbc7024fcfd3f94e4609cee6580df5bab70b Mon Sep 17 00:00:00 2001 From: Uwe Bonnes Date: Wed, 1 Jul 2020 14:45:07 +0200 Subject: [PATCH 35/48] st/synopsys/dcd_synopsys.c: Remove USBC PHY PLL stabilization delay for now While the ST code has a 2 ms stabilization delay for the USBC PHY PLL, running without this delay showed no problem for at leat 10 USB un/replug cycles. Observe for problems! --- src/portable/st/synopsys/dcd_synopsys.c | 8 ++++++-- 1 file changed, 6 insertions(+), 2 deletions(-) diff --git a/src/portable/st/synopsys/dcd_synopsys.c b/src/portable/st/synopsys/dcd_synopsys.c index ba3cc3460..4a372348a 100644 --- a/src/portable/st/synopsys/dcd_synopsys.c +++ b/src/portable/st/synopsys/dcd_synopsys.c @@ -27,7 +27,6 @@ */ #include "tusb_option.h" -#include "../../../../hw/bsp//board.h" #if defined (STM32F105x8) || defined (STM32F105xB) || defined (STM32F105xC) || \ defined (STM32F107xB) || defined (STM32F107xC) @@ -349,7 +348,12 @@ static bool USB_HS_PHYCInit(void) // Enable PLL internal PHY usb_hs_phyc->USB_HS_PHYC_PLL = phyc_pll | USB_HS_PHYC_PLL_PLLEN; - board_delay(2); + /* Original ST code has 2 ms delay for PLL stabilization. + * Primitive test shows that more than 10 USB un/replug cycle + * showed no error with enumeration + * //#include "../../../../hw/bsp//board.h" + * //board_delay(2); + */ return true; } # endif From 5b3a67a1e208296d927da31c3df1aefa562ec2ac Mon Sep 17 00:00:00 2001 From: Uwe Bonnes Date: Wed, 1 Jul 2020 14:52:49 +0200 Subject: [PATCH 36/48] Add bsp for stlinkv3mini. --- hw/bsp/stlinkv3mini/STM32F723xE_FLASH.ld | 167 ++++++++ hw/bsp/stlinkv3mini/board.mk | 59 +++ hw/bsp/stlinkv3mini/stlinkv3mini.c | 298 ++++++++++++++ hw/bsp/stlinkv3mini/stm32f7xx_hal_conf.h | 472 +++++++++++++++++++++++ 4 files changed, 996 insertions(+) create mode 100644 hw/bsp/stlinkv3mini/STM32F723xE_FLASH.ld create mode 100644 hw/bsp/stlinkv3mini/board.mk create mode 100644 hw/bsp/stlinkv3mini/stlinkv3mini.c create mode 100644 hw/bsp/stlinkv3mini/stm32f7xx_hal_conf.h diff --git a/hw/bsp/stlinkv3mini/STM32F723xE_FLASH.ld b/hw/bsp/stlinkv3mini/STM32F723xE_FLASH.ld new file mode 100644 index 000000000..8645ce5c5 --- /dev/null +++ b/hw/bsp/stlinkv3mini/STM32F723xE_FLASH.ld @@ -0,0 +1,167 @@ +/* +***************************************************************************** +** + +** File : LinkerScript.ld +** +** Abstract : Linker script for STM32F723xE Device with +** 512KByte FLASH, 256KByte RAM +** +** Set heap size, stack size and stack location according +** to application requirements. +** +** Set memory bank area and size if external memory is used. +** +** Target : STMicroelectronics STM32 +** +** +** Distribution: The file is distributed as is, without any warranty +** of any kind. +** +** (c)Copyright Ac6. +** You may use this file as-is or modify it according to the needs of your +** project. Distribution of this file (unmodified or modified) is not +** permitted. Ac6 permit registered System Workbench for MCU users the +** rights to distribute the assembled, compiled & linked contents of this +** file as part of an application binary file, provided that it is built +** using the System Workbench for MCU toolchain. +** +***************************************************************************** +*/ + +/* Entry Point */ +ENTRY(Reset_Handler) + +/* Highest address of the user mode stack */ +_estack = 0x20040000; /* 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 = 0x460; /* required amount of stack */ + +/* Specify the memory areas */ +MEMORY +{ +RAM (xrw) : ORIGIN = 0x20000000, LENGTH = 256K +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 secion */ + _sbss = .; /* define a global symbol at bss start */ + __bss_start__ = _sbss; + *(.bss) + *(.bss*) + *(COMMON) + + . = ALIGN(4); + _ebss = .; /* define a global symbol at bss end */ + __bss_end__ = _ebss; + } >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/stlinkv3mini/board.mk b/hw/bsp/stlinkv3mini/board.mk new file mode 100644 index 000000000..8576eeaa8 --- /dev/null +++ b/hw/bsp/stlinkv3mini/board.mk @@ -0,0 +1,59 @@ +PORT ?= 1 + +CFLAGS += \ + -flto \ + -mthumb \ + -mabi=aapcs \ + -mcpu=cortex-m7 \ + -mfloat-abi=hard \ + -mfpu=fpv5-d16 \ + -nostdlib -nostartfiles \ + -DSTM32F723xx \ + -DHSE_VALUE=25000000 \ + -DCFG_TUSB_MCU=OPT_MCU_STM32F7 \ + -DBOARD_DEVICE_RHPORT_NUM=$(PORT) + +ifeq ($(PORT), 1) +CFLAGS += -DBOARD_DEVICE_RHPORT_SPEED=OPT_MODE_HIGH_SPEED +$(info "PORT1 HS") +else +$(info "PORT0") +endif + +# mcu driver cause following warnings +CFLAGS += -Wno-error=shadow -Wno-error=cast-align + +ST_HAL_DRIVER = hw/mcu/st/st_driver/STM32F7xx_HAL_Driver +ST_CMSIS = hw/mcu/st/st_driver/CMSIS/Device/ST/STM32F7xx + +# All source paths should be relative to the top level. +LD_FILE = hw/bsp/$(BOARD)/STM32F723xE_FLASH.ld + +SRC_C += \ + $(ST_CMSIS)/Source/Templates/system_stm32f7xx.c \ + $(ST_HAL_DRIVER)/Src/stm32f7xx_hal.c \ + $(ST_HAL_DRIVER)/Src/stm32f7xx_hal_cortex.c \ + $(ST_HAL_DRIVER)/Src/stm32f7xx_hal_rcc.c \ + $(ST_HAL_DRIVER)/Src/stm32f7xx_hal_rcc_ex.c \ + $(ST_HAL_DRIVER)/Src/stm32f7xx_hal_gpio.c \ + $(ST_HAL_DRIVER)/Src/stm32f7xx_hal_uart.c \ + $(ST_HAL_DRIVER)/Src/stm32f7xx_hal_pwr_ex.c + +SRC_S += \ + $(ST_CMSIS)/Source/Templates/gcc/startup_stm32f723xx.s + +INC += \ + $(TOP)/hw/mcu/st/st_driver/CMSIS/Include \ + $(TOP)/$(ST_CMSIS)/Include \ + $(TOP)/$(ST_HAL_DRIVER)/Inc \ + $(TOP)/hw/bsp/$(BOARD) + +# For TinyUSB port source +VENDOR = st +CHIP_FAMILY = synopsys + +# For freeRTOS port source +FREERTOS_PORT = ARM_CM7/r0p1 + +# flash target using on-board stlink +flash: flash-stlink diff --git a/hw/bsp/stlinkv3mini/stlinkv3mini.c b/hw/bsp/stlinkv3mini/stlinkv3mini.c new file mode 100644 index 000000000..03babcfa9 --- /dev/null +++ b/hw/bsp/stlinkv3mini/stlinkv3mini.c @@ -0,0 +1,298 @@ +/* + * The MIT License (MIT) + * + * Copyright (c) 2020 Uwe Bonnes (bon@elektron.ikp.physik.tu-darmstadt.de), + * Ha Thach (tinyusb.org) + * + * Permission is hereby granted, free of charge, to any person obtaining a copy + * of this software and associated documentation files (the "Software"), to deal + * in the Software without restriction, including without limitation the rights + * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell + * copies of the Software, and to permit persons to whom the Software is + * furnished to do so, subject to the following conditions: + * + * The above copyright notice and this permission notice shall be included in + * all copies or substantial portions of the Software. + * + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR + * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE + * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER + * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, + * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN + * THE SOFTWARE. + * + * This file is part of the TinyUSB stack. + */ + +#include "../board.h" + +#include "stm32f7xx_hal.h" + +//--------------------------------------------------------------------+ +// Forward USB interrupt events to TinyUSB IRQ Handler +//--------------------------------------------------------------------+ +void OTG_FS_IRQHandler(void) +{ + tud_int_handler(0); +} + +// Despite being call USB2_OTG +// OTG_HS is marked as RHPort1 by TinyUSB to be consistent across stm32 port +void OTG_HS_IRQHandler(void) +{ + tud_int_handler(1); +} + +// Pin configuartion with help from +// RadioOperator/CMSIS-DAP_for_STLINK-V3MINI.git +// CMSIS-DAP_for_STLINK-V3MINI/STLINK-V3MINI/Sch/STLINK-V3MINI_GPIOs.JPG + +//--------------------------------------------------------------------+ +// MACRO TYPEDEF CONSTANT ENUM +//--------------------------------------------------------------------+ + +#define LED_PORT GPIOA +#define LED_PIN GPIO_PIN_10 +#define LED_STATE_ON 1 + +/* No Buttom */ + +#define UARTx USART6 +#define UART_GPIO_PORT GPIOG +#define UART_GPIO_AF GPIO_AF8_USART6 +#define UART_TX_PIN GPIO_PIN_9 +#define UART_RX_PIN GPIO_PIN_14 + +UART_HandleTypeDef UartHandle; + +// enable all LED, Button, Uart, USB clock +static void all_rcc_clk_enable(void) +{ + __HAL_RCC_GPIOA_CLK_ENABLE(); // USB D+, D-, LED + __HAL_RCC_GPIOB_CLK_ENABLE(); // OTG_HS + __HAL_RCC_GPIOD_CLK_ENABLE(); // OTG_HS ID + __HAL_RCC_GPIOG_CLK_ENABLE(); // Uart TX, RX + __HAL_RCC_USART6_CLK_ENABLE(); // Uart module +} + +/** + * @brief System Clock Configuration + * The system Clock is configured as follow : + * System Clock source = PLL (HSE) + * SYSCLK(Hz) = 216000000 + * HCLK(Hz) = 216000000 + * AHB Prescaler = 1 + * APB1 Prescaler = 4 + * APB2 Prescaler = 2 + * HSE Frequency(Hz) = 25000000 + * PLL_M = HSE_VALUE/1000000 + * PLL_N = 432 + * PLL_P = 2 + * PLL_Q = 9 + * VDD(V) = 3.3 + * Main regulator output voltage = Scale1 mode + * Flash Latency(WS) = 7 + * The USB clock configuration from PLLSAI: + * PLLSAIP = 8 + * PLLSAIN = 384 + * PLLSAIQ = 7 + * @param None + * @retval None + */ +void SystemClock_Config(void) +{ + RCC_ClkInitTypeDef RCC_ClkInitStruct; + RCC_OscInitTypeDef RCC_OscInitStruct; + + /* Enable Power Control clock */ + __HAL_RCC_PWR_CLK_ENABLE(); + + /* The voltage scaling allows optimizing the power consumption when the device is + clocked below the maximum system frequency, to update the voltage scaling value + regarding system frequency refer to product datasheet. */ + __HAL_PWR_VOLTAGESCALING_CONFIG(PWR_REGULATOR_VOLTAGE_SCALE1); + + /* Enable HSE Oscillator and activate PLL with HSE as source */ + RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_HSE; + RCC_OscInitStruct.HSEState = RCC_HSE_BYPASS; + RCC_OscInitStruct.PLL.PLLState = RCC_PLL_ON; + RCC_OscInitStruct.PLL.PLLSource = RCC_PLLSOURCE_HSE; + RCC_OscInitStruct.PLL.PLLM = HSE_VALUE/1000000; + RCC_OscInitStruct.PLL.PLLN = 432; + RCC_OscInitStruct.PLL.PLLP = RCC_PLLP_DIV2; + RCC_OscInitStruct.PLL.PLLQ = 9; + HAL_RCC_OscConfig(&RCC_OscInitStruct); + + /* Activate the OverDrive to reach the 216 MHz Frequency */ + HAL_PWREx_EnableOverDrive(); + + /* Select PLL as system clock source and configure the HCLK, PCLK1 and PCLK2 clocks dividers */ + RCC_ClkInitStruct.ClockType = (RCC_CLOCKTYPE_SYSCLK | RCC_CLOCKTYPE_HCLK | RCC_CLOCKTYPE_PCLK1 | RCC_CLOCKTYPE_PCLK2); + RCC_ClkInitStruct.SYSCLKSource = RCC_SYSCLKSOURCE_PLLCLK; + RCC_ClkInitStruct.AHBCLKDivider = RCC_SYSCLK_DIV1; + RCC_ClkInitStruct.APB1CLKDivider = RCC_HCLK_DIV4; + RCC_ClkInitStruct.APB2CLKDivider = RCC_HCLK_DIV2; + + HAL_RCC_ClockConfig(&RCC_ClkInitStruct, FLASH_LATENCY_7); +} + +void board_init(void) +{ + + + SystemClock_Config(); + all_rcc_clk_enable(); + +#if CFG_TUSB_OS == OPT_OS_NONE + // 1ms tick timer + SysTick_Config(SystemCoreClock / 1000); +#endif + + GPIO_InitTypeDef GPIO_InitStruct; + + // LED + GPIO_InitStruct.Pin = LED_PIN; + GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_PP; + GPIO_InitStruct.Pull = GPIO_PULLUP; + GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_HIGH; + HAL_GPIO_Init(LED_PORT, &GPIO_InitStruct); + + // Uart + GPIO_InitStruct.Pin = UART_TX_PIN | UART_RX_PIN; + GPIO_InitStruct.Mode = GPIO_MODE_AF_PP; + GPIO_InitStruct.Pull = GPIO_PULLUP; + GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_HIGH; + GPIO_InitStruct.Alternate = UART_GPIO_AF; + HAL_GPIO_Init(UART_GPIO_PORT, &GPIO_InitStruct); + + UartHandle.Instance = UARTx; + UartHandle.Init.BaudRate = CFG_BOARD_UART_BAUDRATE; + UartHandle.Init.WordLength = UART_WORDLENGTH_8B; + UartHandle.Init.StopBits = UART_STOPBITS_1; + UartHandle.Init.Parity = UART_PARITY_NONE; + UartHandle.Init.HwFlowCtl = UART_HWCONTROL_NONE; + UartHandle.Init.Mode = UART_MODE_TX_RX; + UartHandle.Init.OverSampling = UART_OVERSAMPLING_16; + HAL_UART_Init(&UartHandle); + +#if BOARD_DEVICE_RHPORT_NUM == 0 + /* Configure USB FS GPIOs */ + /* Configure DM DP Pins */ + GPIO_InitStruct.Pin = (GPIO_PIN_11 | GPIO_PIN_12); + GPIO_InitStruct.Mode = GPIO_MODE_AF_PP; + GPIO_InitStruct.Pull = GPIO_NOPULL; + GPIO_InitStruct.Speed = GPIO_SPEED_HIGH; + GPIO_InitStruct.Alternate = GPIO_AF10_OTG_FS; + HAL_GPIO_Init(GPIOA, &GPIO_InitStruct); + + /* Configure VBUS Pin */ + GPIO_InitStruct.Pin = GPIO_PIN_9; + GPIO_InitStruct.Mode = GPIO_MODE_INPUT; + GPIO_InitStruct.Pull = GPIO_NOPULL; + HAL_GPIO_Init(GPIOA, &GPIO_InitStruct); + + /* Configure OTG-FS ID pin */ + GPIO_InitStruct.Pin = GPIO_PIN_10; + GPIO_InitStruct.Mode = GPIO_MODE_AF_OD; + GPIO_InitStruct.Pull = GPIO_PULLUP; + GPIO_InitStruct.Alternate = GPIO_AF10_OTG_FS; + HAL_GPIO_Init(GPIOA, &GPIO_InitStruct); + + /* Enable USB FS Clocks */ + __HAL_RCC_USB_OTG_FS_CLK_ENABLE(); + + // Enable VBUS sense (B device) via pin PA9 + USB_OTG_FS->GCCFG |= USB_OTG_GCCFG_VBDEN; + +#else + /* Configure USB HS GPIOs */ + /* Configure DM DP Pins */ + GPIO_InitStruct.Pin = (GPIO_PIN_14 | GPIO_PIN_15); + GPIO_InitStruct.Mode = GPIO_MODE_AF_PP; + GPIO_InitStruct.Pull = GPIO_NOPULL; + GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_HIGH; + GPIO_InitStruct.Alternate = GPIO_AF10_OTG_HS; + HAL_GPIO_Init(GPIOB, &GPIO_InitStruct); + + // Enable HS VBUS sense (B device) via pin PB13 + USB_OTG_HS->GCCFG |= USB_OTG_GCCFG_VBDEN; + + /* Configure OTG-HS ID pin */ + GPIO_InitStruct.Pin = GPIO_PIN_13; + GPIO_InitStruct.Mode = GPIO_MODE_AF_OD; + GPIO_InitStruct.Pull = GPIO_PULLUP; + GPIO_InitStruct.Alternate = GPIO_AF10_OTG_HS; + HAL_GPIO_Init(GPIOD, &GPIO_InitStruct); + + /* Enable PHYC Clocks */ + __HAL_RCC_OTGPHYC_CLK_ENABLE(); + + /* Enable USB HS Clocks */ + __HAL_RCC_USB_OTG_HS_CLK_ENABLE(); + __HAL_RCC_USB_OTG_HS_ULPI_CLK_ENABLE(); + + // Enable VBUS sense (B device) via pin PA9 + USB_OTG_HS->GCCFG &= ~USB_OTG_GCCFG_VBDEN; + + // B-peripheral session valid override enable + USB_OTG_HS->GOTGCTL |= USB_OTG_GOTGCTL_BVALOEN; + USB_OTG_HS->GOTGCTL |= USB_OTG_GOTGCTL_BVALOVAL; + + // Force device mode + USB_OTG_HS->GUSBCFG &= ~USB_OTG_GUSBCFG_FHMOD; + USB_OTG_HS->GUSBCFG |= USB_OTG_GUSBCFG_FDMOD; + +#endif +} + +//--------------------------------------------------------------------+ +// Board porting API +//--------------------------------------------------------------------+ + +void board_led_write(bool state) +{ + HAL_GPIO_WritePin(LED_PORT, LED_PIN, state); +} + +uint32_t board_button_read(void) +{ + return 0; +} + +int board_uart_read(uint8_t* buf, int len) +{ + (void) buf; (void) len; + return 0; +} + +int board_uart_write(void const * buf, int len) +{ + HAL_UART_Transmit(&UartHandle, (uint8_t*) buf, len, 0xffff); + return len; +} + +#if CFG_TUSB_OS == OPT_OS_NONE +volatile uint32_t system_ticks = 0; +void SysTick_Handler (void) +{ + system_ticks++; +} + +uint32_t board_millis(void) +{ + return system_ticks; +} +#endif + +void HardFault_Handler (void) +{ + asm("bkpt"); +} + +// Required by __libc_init_array in startup code if we are compiling using +// -nostdlib/-nostartfiles. +void _init(void) +{ + +} diff --git a/hw/bsp/stlinkv3mini/stm32f7xx_hal_conf.h b/hw/bsp/stlinkv3mini/stm32f7xx_hal_conf.h new file mode 100644 index 000000000..03dec8f0d --- /dev/null +++ b/hw/bsp/stlinkv3mini/stm32f7xx_hal_conf.h @@ -0,0 +1,472 @@ +/** + ****************************************************************************** + * @file stm32f7xx_hal_conf.h + * @author MCD Application Team + * @brief HAL configuration file. + ****************************************************************************** + * @attention + * + *

© Copyright (c) 2016 STMicroelectronics. + * All rights reserved.

+ * + * This software component is licensed by ST under BSD 3-Clause license, + * the "License"; You may not use this file except in compliance with the + * License. You may obtain a copy of the License at: + * opensource.org/licenses/BSD-3-Clause + * + ****************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __STM32F7xx_HAL_CONF_H +#define __STM32F7xx_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_CAN_MODULE_ENABLED */ +/* #define HAL_CAN_LEGACY_MODULE_ENABLED */ +/* #define HAL_CEC_MODULE_ENABLED */ +/* #define HAL_CRC_MODULE_ENABLED */ +/* #define HAL_CRYP_MODULE_ENABLED */ +/* #define HAL_DAC_MODULE_ENABLED */ +/* #define HAL_DCMI_MODULE_ENABLED */ +#define HAL_DMA_MODULE_ENABLED +/* #define HAL_DMA2D_MODULE_ENABLED */ +/* #define HAL_ETH_MODULE_ENABLED */ +#define HAL_FLASH_MODULE_ENABLED +/* #define HAL_NAND_MODULE_ENABLED */ +/* #define HAL_NOR_MODULE_ENABLED */ +/* #define HAL_SRAM_MODULE_ENABLED */ +/* #define HAL_SDRAM_MODULE_ENABLED */ +/* #define HAL_HASH_MODULE_ENABLED */ +#define HAL_GPIO_MODULE_ENABLED +/* #define HAL_I2C_MODULE_ENABLED */ +/* #define HAL_I2S_MODULE_ENABLED */ +/* #define HAL_IWDG_MODULE_ENABLED */ +/* #define HAL_LPTIM_MODULE_ENABLED */ +/* #define HAL_LTDC_MODULE_ENABLED */ +#define HAL_PWR_MODULE_ENABLED +/* #define HAL_QSPI_MODULE_ENABLED */ +#define HAL_RCC_MODULE_ENABLED +/* #define HAL_RNG_MODULE_ENABLED */ +/* #define HAL_RTC_MODULE_ENABLED */ +/* #define HAL_SAI_MODULE_ENABLED */ +/* #define HAL_SD_MODULE_ENABLED */ +/* #define HAL_SPDIFRX_MODULE_ENABLED */ +/* #define HAL_SPI_MODULE_ENABLED */ +/* #define HAL_TIM_MODULE_ENABLED */ +#define HAL_UART_MODULE_ENABLED +/* #define HAL_USART_MODULE_ENABLED */ +/* #define HAL_IRDA_MODULE_ENABLED */ +/* #define HAL_SMARTCARD_MODULE_ENABLED */ +/* #define HAL_WWDG_MODULE_ENABLED */ +#define HAL_CORTEX_MODULE_ENABLED +/* #define HAL_PCD_MODULE_ENABLED */ +/* #define HAL_HCD_MODULE_ENABLED */ +/* #define HAL_DFSDM_MODULE_ENABLED */ +/* #define HAL_DSI_MODULE_ENABLED */ +/* #define HAL_JPEG_MODULE_ENABLED */ +/* #define HAL_MDIOS_MODULE_ENABLED */ + + +/* ########################## HSE/HSI Values adaptation ##################### */ +/** + * @brief Adjust the value of External High Speed oscillator (HSE) used in your application. + * This value is used by the RCC HAL module to compute the system frequency + * (when HSE is used as system clock source, directly or through the PLL). + */ +#if !defined (HSE_VALUE) + #define HSE_VALUE ((uint32_t)8000000U) /*!< Value of the External oscillator in Hz */ +#endif /* HSE_VALUE */ + +#if !defined (HSE_STARTUP_TIMEOUT) + #define HSE_STARTUP_TIMEOUT ((uint32_t)100U) /*!< Time out for HSE start up, in ms */ +#endif /* HSE_STARTUP_TIMEOUT */ + +/** + * @brief Internal High Speed oscillator (HSI) value. + * This value is used by the RCC HAL module to compute the system frequency + * (when HSI is used as system clock source, directly or through the PLL). + */ +#if !defined (HSI_VALUE) + #define HSI_VALUE ((uint32_t)16000000U) /*!< Value of the Internal oscillator in Hz*/ +#endif /* HSI_VALUE */ + +/** + * @brief Internal Low Speed oscillator (LSI) value. + */ +#if !defined (LSI_VALUE) + #define LSI_VALUE ((uint32_t)32000U) /*!< 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. + */ +#if !defined (LSE_VALUE) + #define LSE_VALUE ((uint32_t)32768U) /*!< Value of the External Low Speed oscillator in Hz */ +#endif /* LSE_VALUE */ + +#if !defined (LSE_STARTUP_TIMEOUT) + #define LSE_STARTUP_TIMEOUT ((uint32_t)5000U) /*!< Time out for LSE start up, in ms */ +#endif /* LSE_STARTUP_TIMEOUT */ + +/** + * @brief External clock source for I2S peripheral + * This value is used by the I2S HAL module to compute the I2S clock source + * frequency, this source is inserted directly through I2S_CKIN pad. + */ +#if !defined (EXTERNAL_CLOCK_VALUE) + #define EXTERNAL_CLOCK_VALUE ((uint32_t)12288000U) /*!< Value of the Internal oscillator in Hz*/ +#endif /* EXTERNAL_CLOCK_VALUE */ + +/* Tip: To avoid modifying this file each time you need to use different HSE, + === you can define the HSE value in your toolchain compiler preprocessor. */ + +/* ########################### System Configuration ######################### */ +/** + * @brief This is the HAL system configuration section + */ +#define VDD_VALUE ((uint32_t)3300U) /*!< Value of VDD in mv */ +#define TICK_INT_PRIORITY ((uint32_t)0x0FU) /*!< tick interrupt priority */ +#define USE_RTOS 0U +#define PREFETCH_ENABLE 1U +#define ART_ACCLERATOR_ENABLE 1U /* To enable instruction cache and prefetch */ + +#define USE_HAL_ADC_REGISTER_CALLBACKS 0U /* ADC register callback disabled */ +#define USE_HAL_CAN_REGISTER_CALLBACKS 0U /* CAN register callback disabled */ +#define USE_HAL_CEC_REGISTER_CALLBACKS 0U /* CEC register callback disabled */ +#define USE_HAL_CRYP_REGISTER_CALLBACKS 0U /* CRYP register callback disabled */ +#define USE_HAL_DAC_REGISTER_CALLBACKS 0U /* DAC register callback disabled */ +#define USE_HAL_DCMI_REGISTER_CALLBACKS 0U /* DCMI register callback disabled */ +#define USE_HAL_DFSDM_REGISTER_CALLBACKS 0U /* DFSDM register callback disabled */ +#define USE_HAL_DMA2D_REGISTER_CALLBACKS 0U /* DMA2D register callback disabled */ +#define USE_HAL_DSI_REGISTER_CALLBACKS 0U /* DSI register callback disabled */ +#define USE_HAL_ETH_REGISTER_CALLBACKS 0U /* ETH register callback disabled */ +#define USE_HAL_HASH_REGISTER_CALLBACKS 0U /* HASH register callback disabled */ +#define USE_HAL_HCD_REGISTER_CALLBACKS 0U /* HCD register callback disabled */ +#define USE_HAL_I2C_REGISTER_CALLBACKS 0U /* I2C register callback disabled */ +#define USE_HAL_I2S_REGISTER_CALLBACKS 0U /* I2S register callback disabled */ +#define USE_HAL_IRDA_REGISTER_CALLBACKS 0U /* IRDA register callback disabled */ +#define USE_HAL_JPEG_REGISTER_CALLBACKS 0U /* JPEG register callback disabled */ +#define USE_HAL_LPTIM_REGISTER_CALLBACKS 0U /* LPTIM register callback disabled */ +#define USE_HAL_LTDC_REGISTER_CALLBACKS 0U /* LTDC register callback disabled */ +#define USE_HAL_MDIOS_REGISTER_CALLBACKS 0U /* MDIOS register callback disabled */ +#define USE_HAL_MMC_REGISTER_CALLBACKS 0U /* MMC register callback disabled */ +#define USE_HAL_NAND_REGISTER_CALLBACKS 0U /* NAND register callback disabled */ +#define USE_HAL_NOR_REGISTER_CALLBACKS 0U /* NOR register callback disabled */ +#define USE_HAL_PCD_REGISTER_CALLBACKS 0U /* PCD register callback disabled */ +#define USE_HAL_QSPI_REGISTER_CALLBACKS 0U /* QSPI register callback disabled */ +#define USE_HAL_RNG_REGISTER_CALLBACKS 0U /* RNG register callback disabled */ +#define USE_HAL_RTC_REGISTER_CALLBACKS 0U /* RTC register callback disabled */ +#define USE_HAL_SAI_REGISTER_CALLBACKS 0U /* SAI register callback disabled */ +#define USE_HAL_SD_REGISTER_CALLBACKS 0U /* SD register callback disabled */ +#define USE_HAL_SMARTCARD_REGISTER_CALLBACKS 0U /* SMARTCARD register callback disabled */ +#define USE_HAL_SDRAM_REGISTER_CALLBACKS 0U /* SDRAM register callback disabled */ +#define USE_HAL_SRAM_REGISTER_CALLBACKS 0U /* SRAM register callback disabled */ +#define USE_HAL_SPDIFRX_REGISTER_CALLBACKS 0U /* SPDIFRX register callback disabled */ +#define USE_HAL_SMBUS_REGISTER_CALLBACKS 0U /* SMBUS register callback disabled */ +#define USE_HAL_SPI_REGISTER_CALLBACKS 0U /* SPI register callback disabled */ +#define USE_HAL_TIM_REGISTER_CALLBACKS 0U /* TIM register callback disabled */ +#define USE_HAL_UART_REGISTER_CALLBACKS 0U /* UART register callback disabled */ +#define USE_HAL_USART_REGISTER_CALLBACKS 0U /* USART register callback disabled */ +#define USE_HAL_WWDG_REGISTER_CALLBACKS 0U /* WWDG register callback disabled */ + +/* ########################## Assert Selection ############################## */ +/** + * @brief Uncomment the line below to expanse the "assert_param" macro in the + * HAL drivers code + */ +/* #define USE_FULL_ASSERT 1 */ + +/* ################## Ethernet peripheral configuration for NUCLEO 144 board ##################### */ + +/* Section 1 : Ethernet peripheral configuration */ + +/* MAC ADDRESS: MAC_ADDR0:MAC_ADDR1:MAC_ADDR2:MAC_ADDR3:MAC_ADDR4:MAC_ADDR5 */ +#define MAC_ADDR0 2U +#define MAC_ADDR1 0U +#define MAC_ADDR2 0U +#define MAC_ADDR3 0U +#define MAC_ADDR4 0U +#define MAC_ADDR5 0U + +/* Definition of the Ethernet driver buffers size and count */ +#define ETH_RX_BUF_SIZE ETH_MAX_PACKET_SIZE /* buffer size for receive */ +#define ETH_TX_BUF_SIZE ETH_MAX_PACKET_SIZE /* buffer size for transmit */ +#define ETH_RXBUFNB ((uint32_t)5) /* 5 Rx buffers of size ETH_RX_BUF_SIZE */ +#define ETH_TXBUFNB ((uint32_t)5) /* 5 Tx buffers of size ETH_TX_BUF_SIZE */ + +/* Section 2: PHY configuration section */ +/* LAN8742A PHY Address*/ +#define LAN8742A_PHY_ADDRESS 0x00 +/* PHY Reset delay these values are based on a 1 ms Systick interrupt*/ +#define PHY_RESET_DELAY ((uint32_t)0x00000FFF) +/* PHY Configuration delay */ +#define PHY_CONFIG_DELAY ((uint32_t)0x00000FFF) + +#define PHY_READ_TO ((uint32_t)0x0000FFFF) +#define PHY_WRITE_TO ((uint32_t)0x0000FFFF) + +/* Section 3: Common PHY Registers */ + +#define PHY_BCR ((uint16_t)0x00) /*!< Transceiver Basic Control Register */ +#define PHY_BSR ((uint16_t)0x01) /*!< Transceiver Basic Status Register */ + +#define PHY_RESET ((uint16_t)0x8000) /*!< PHY Reset */ +#define PHY_LOOPBACK ((uint16_t)0x4000) /*!< Select loop-back mode */ +#define PHY_FULLDUPLEX_100M ((uint16_t)0x2100) /*!< Set the full-duplex mode at 100 Mb/s */ +#define PHY_HALFDUPLEX_100M ((uint16_t)0x2000) /*!< Set the half-duplex mode at 100 Mb/s */ +#define PHY_FULLDUPLEX_10M ((uint16_t)0x0100) /*!< Set the full-duplex mode at 10 Mb/s */ +#define PHY_HALFDUPLEX_10M ((uint16_t)0x0000) /*!< Set the half-duplex mode at 10 Mb/s */ +#define PHY_AUTONEGOTIATION ((uint16_t)0x1000) /*!< Enable auto-negotiation function */ +#define PHY_RESTART_AUTONEGOTIATION ((uint16_t)0x0200) /*!< Restart auto-negotiation function */ +#define PHY_POWERDOWN ((uint16_t)0x0800) /*!< Select the power down mode */ +#define PHY_ISOLATE ((uint16_t)0x0400) /*!< Isolate PHY from MII */ + +#define PHY_AUTONEGO_COMPLETE ((uint16_t)0x0020) /*!< Auto-Negotiation process completed */ +#define PHY_LINKED_STATUS ((uint16_t)0x0004) /*!< Valid link established */ +#define PHY_JABBER_DETECTION ((uint16_t)0x0002) /*!< Jabber condition detected */ + +/* Section 4: Extended PHY Registers */ + +#define PHY_SR ((uint16_t)0x1F) /*!< PHY special control/ status register Offset */ + +#define PHY_SPEED_STATUS ((uint16_t)0x0004) /*!< PHY Speed mask */ +#define PHY_DUPLEX_STATUS ((uint16_t)0x0010) /*!< PHY Duplex mask */ + + +#define PHY_ISFR ((uint16_t)0x1D) /*!< PHY Interrupt Source Flag register Offset */ +#define PHY_ISFR_INT4 ((uint16_t)0x0010) /*!< PHY Link down inturrupt */ + +/* ################## 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 1U + +/* Includes ------------------------------------------------------------------*/ +/** + * @brief Include module's header file + */ + +#ifdef HAL_RCC_MODULE_ENABLED + #include "stm32f7xx_hal_rcc.h" +#endif /* HAL_RCC_MODULE_ENABLED */ + +#ifdef HAL_GPIO_MODULE_ENABLED + #include "stm32f7xx_hal_gpio.h" +#endif /* HAL_GPIO_MODULE_ENABLED */ + +#ifdef HAL_DMA_MODULE_ENABLED + #include "stm32f7xx_hal_dma.h" +#endif /* HAL_DMA_MODULE_ENABLED */ + +#ifdef HAL_CORTEX_MODULE_ENABLED + #include "stm32f7xx_hal_cortex.h" +#endif /* HAL_CORTEX_MODULE_ENABLED */ + +#ifdef HAL_ADC_MODULE_ENABLED + #include "stm32f7xx_hal_adc.h" +#endif /* HAL_ADC_MODULE_ENABLED */ + +#ifdef HAL_CAN_MODULE_ENABLED + #include "stm32f7xx_hal_can.h" +#endif /* HAL_CAN_MODULE_ENABLED */ + +#ifdef HAL_CAN_LEGACY_MODULE_ENABLED + #include "stm32f7xx_hal_can_legacy.h" +#endif /* HAL_CAN_LEGACY_MODULE_ENABLED */ + +#ifdef HAL_CEC_MODULE_ENABLED + #include "stm32f7xx_hal_cec.h" +#endif /* HAL_CEC_MODULE_ENABLED */ + +#ifdef HAL_CRC_MODULE_ENABLED + #include "stm32f7xx_hal_crc.h" +#endif /* HAL_CRC_MODULE_ENABLED */ + +#ifdef HAL_CRYP_MODULE_ENABLED + #include "stm32f7xx_hal_cryp.h" +#endif /* HAL_CRYP_MODULE_ENABLED */ + +#ifdef HAL_DMA2D_MODULE_ENABLED + #include "stm32f7xx_hal_dma2d.h" +#endif /* HAL_DMA2D_MODULE_ENABLED */ + +#ifdef HAL_DAC_MODULE_ENABLED + #include "stm32f7xx_hal_dac.h" +#endif /* HAL_DAC_MODULE_ENABLED */ + +#ifdef HAL_DCMI_MODULE_ENABLED + #include "stm32f7xx_hal_dcmi.h" +#endif /* HAL_DCMI_MODULE_ENABLED */ + +#ifdef HAL_ETH_MODULE_ENABLED + #include "stm32f7xx_hal_eth.h" +#endif /* HAL_ETH_MODULE_ENABLED */ + +#ifdef HAL_FLASH_MODULE_ENABLED + #include "stm32f7xx_hal_flash.h" +#endif /* HAL_FLASH_MODULE_ENABLED */ + +#ifdef HAL_SRAM_MODULE_ENABLED + #include "stm32f7xx_hal_sram.h" +#endif /* HAL_SRAM_MODULE_ENABLED */ + +#ifdef HAL_NOR_MODULE_ENABLED + #include "stm32f7xx_hal_nor.h" +#endif /* HAL_NOR_MODULE_ENABLED */ + +#ifdef HAL_NAND_MODULE_ENABLED + #include "stm32f7xx_hal_nand.h" +#endif /* HAL_NAND_MODULE_ENABLED */ + +#ifdef HAL_SDRAM_MODULE_ENABLED + #include "stm32f7xx_hal_sdram.h" +#endif /* HAL_SDRAM_MODULE_ENABLED */ + +#ifdef HAL_HASH_MODULE_ENABLED + #include "stm32f7xx_hal_hash.h" +#endif /* HAL_HASH_MODULE_ENABLED */ + +#ifdef HAL_I2C_MODULE_ENABLED + #include "stm32f7xx_hal_i2c.h" +#endif /* HAL_I2C_MODULE_ENABLED */ + +#ifdef HAL_I2S_MODULE_ENABLED + #include "stm32f7xx_hal_i2s.h" +#endif /* HAL_I2S_MODULE_ENABLED */ + +#ifdef HAL_IWDG_MODULE_ENABLED + #include "stm32f7xx_hal_iwdg.h" +#endif /* HAL_IWDG_MODULE_ENABLED */ + +#ifdef HAL_LPTIM_MODULE_ENABLED + #include "stm32f7xx_hal_lptim.h" +#endif /* HAL_LPTIM_MODULE_ENABLED */ + +#ifdef HAL_LTDC_MODULE_ENABLED + #include "stm32f7xx_hal_ltdc.h" +#endif /* HAL_LTDC_MODULE_ENABLED */ + +#ifdef HAL_PWR_MODULE_ENABLED + #include "stm32f7xx_hal_pwr.h" +#endif /* HAL_PWR_MODULE_ENABLED */ + +#ifdef HAL_QSPI_MODULE_ENABLED + #include "stm32f7xx_hal_qspi.h" +#endif /* HAL_QSPI_MODULE_ENABLED */ + +#ifdef HAL_RNG_MODULE_ENABLED + #include "stm32f7xx_hal_rng.h" +#endif /* HAL_RNG_MODULE_ENABLED */ + +#ifdef HAL_RTC_MODULE_ENABLED + #include "stm32f7xx_hal_rtc.h" +#endif /* HAL_RTC_MODULE_ENABLED */ + +#ifdef HAL_SAI_MODULE_ENABLED + #include "stm32f7xx_hal_sai.h" +#endif /* HAL_SAI_MODULE_ENABLED */ + +#ifdef HAL_SD_MODULE_ENABLED + #include "stm32f7xx_hal_sd.h" +#endif /* HAL_SD_MODULE_ENABLED */ + +#ifdef HAL_SPDIFRX_MODULE_ENABLED + #include "stm32f7xx_hal_spdifrx.h" +#endif /* HAL_SPDIFRX_MODULE_ENABLED */ + +#ifdef HAL_SPI_MODULE_ENABLED + #include "stm32f7xx_hal_spi.h" +#endif /* HAL_SPI_MODULE_ENABLED */ + +#ifdef HAL_TIM_MODULE_ENABLED + #include "stm32f7xx_hal_tim.h" +#endif /* HAL_TIM_MODULE_ENABLED */ + +#ifdef HAL_UART_MODULE_ENABLED + #include "stm32f7xx_hal_uart.h" +#endif /* HAL_UART_MODULE_ENABLED */ + +#ifdef HAL_USART_MODULE_ENABLED + #include "stm32f7xx_hal_usart.h" +#endif /* HAL_USART_MODULE_ENABLED */ + +#ifdef HAL_IRDA_MODULE_ENABLED + #include "stm32f7xx_hal_irda.h" +#endif /* HAL_IRDA_MODULE_ENABLED */ + +#ifdef HAL_SMARTCARD_MODULE_ENABLED + #include "stm32f7xx_hal_smartcard.h" +#endif /* HAL_SMARTCARD_MODULE_ENABLED */ + +#ifdef HAL_WWDG_MODULE_ENABLED + #include "stm32f7xx_hal_wwdg.h" +#endif /* HAL_WWDG_MODULE_ENABLED */ + +#ifdef HAL_PCD_MODULE_ENABLED + #include "stm32f7xx_hal_pcd.h" +#endif /* HAL_PCD_MODULE_ENABLED */ + +#ifdef HAL_HCD_MODULE_ENABLED + #include "stm32f7xx_hal_hcd.h" +#endif /* HAL_HCD_MODULE_ENABLED */ + +#ifdef HAL_DFSDM_MODULE_ENABLED + #include "stm32f7xx_hal_dfsdm.h" +#endif /* HAL_DFSDM_MODULE_ENABLED */ + +#ifdef HAL_DSI_MODULE_ENABLED + #include "stm32f7xx_hal_dsi.h" +#endif /* HAL_DSI_MODULE_ENABLED */ + +#ifdef HAL_JPEG_MODULE_ENABLED + #include "stm32f7xx_hal_jpeg.h" +#endif /* HAL_JPEG_MODULE_ENABLED */ + +#ifdef HAL_MDIOS_MODULE_ENABLED + #include "stm32f7xx_hal_mdios.h" +#endif /* HAL_MDIOS_MODULE_ENABLED */ + +/* Exported macro ------------------------------------------------------------*/ +#ifdef USE_FULL_ASSERT +/** + * @brief The assert_param macro is used for function's parameters check. + * @param expr: If expr is false, it calls assert_failed function + * which reports the name of the source file and the source + * line number of the call that failed. + * If expr is true, it returns no value. + * @retval None + */ + #define assert_param(expr) ((expr) ? (void)0 : assert_failed((uint8_t *)__FILE__, __LINE__)) +/* Exported functions ------------------------------------------------------- */ + void assert_failed(uint8_t* file, uint32_t line); +#else + #define assert_param(expr) ((void)0U) +#endif /* USE_FULL_ASSERT */ + + +#ifdef __cplusplus +} +#endif + +#endif /* __STM32F7xx_HAL_CONF_H */ + + +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ From 4966fb2e13ca2629763e76d82b67e531c3e20ede Mon Sep 17 00:00:00 2001 From: hathach Date: Thu, 2 Jul 2020 01:22:26 +0700 Subject: [PATCH 37/48] clean up --- src/portable/st/synopsys/dcd_synopsys.c | 93 ++++++++++--------------- 1 file changed, 36 insertions(+), 57 deletions(-) diff --git a/src/portable/st/synopsys/dcd_synopsys.c b/src/portable/st/synopsys/dcd_synopsys.c index d5e36a97a..03238f8e2 100644 --- a/src/portable/st/synopsys/dcd_synopsys.c +++ b/src/portable/st/synopsys/dcd_synopsys.c @@ -147,12 +147,13 @@ typedef struct { typedef volatile uint32_t * usb_fifo_t; #if TUD_OPT_RHPORT == 1 -# define EP_MAX EP_MAX_HS -# define EP_FIFO_SIZE EP_FIFO_SIZE_HS + #define EP_MAX EP_MAX_HS + #define EP_FIFO_SIZE EP_FIFO_SIZE_HS #else -# define EP_MAX EP_MAX_FS -# define EP_FIFO_SIZE EP_FIFO_SIZE_FS + #define EP_MAX EP_MAX_FS + #define EP_FIFO_SIZE EP_FIFO_SIZE_FS #endif + xfer_ctl_t xfer_status[EP_MAX][2]; #define XFER_CTL_BASE(_ep, _dir) &xfer_status[_ep][_dir] @@ -325,63 +326,44 @@ static void edpt_schedule_packets(uint8_t rhport, uint8_t const epnum, uint8_t c } -# if defined(USB_HS_PHYC) && TUD_OPT_HIGH_SPEED +#if defined(USB_HS_PHYC) && TUD_OPT_HIGH_SPEED static bool USB_HS_PHYCInit(void) { - USB_HS_PHYC_GlobalTypeDef *usb_hs_phyc = (USB_HS_PHYC_GlobalTypeDef *)USB_HS_PHYC_CONTROLLER_BASE; - // Enable LDO - usb_hs_phyc->USB_HS_PHYC_LDO |= USB_HS_PHYC_LDO_ENABLE; - int32_t count = 2000000; - while(1) { - if (usb_hs_phyc->USB_HS_PHYC_LDO & USB_HS_PHYC_LDO_STATUS) - break; - TU_ASSERT(count > 0); - } - uint32_t phyc_pll = 0; - switch (HSE_VALUE) { - case 12000000: - phyc_pll = USB_HS_PHYC_PLL1_PLLSEL_12MHZ; - break; - case 12500000: - phyc_pll = USB_HS_PHYC_PLL1_PLLSEL_12_5MHZ; - break; - case 16000000: - phyc_pll = USB_HS_PHYC_PLL1_PLLSEL_16MHZ; - break; - case 24000000: - phyc_pll = USB_HS_PHYC_PLL1_PLLSEL_24MHZ; - break; - case 25000000: - phyc_pll = USB_HS_PHYC_PLL1_PLLSEL_25MHZ; - break; - case 32000000: - // Value not defined in header - phyc_pll = USB_HS_PHYC_PLL1_PLLSEL_Msk; - break; + USB_HS_PHYC_GlobalTypeDef *usb_hs_phyc = (USB_HS_PHYC_GlobalTypeDef*) USB_HS_PHYC_CONTROLLER_BASE; + + // Enable LDO + usb_hs_phyc->USB_HS_PHYC_LDO |= USB_HS_PHYC_LDO_ENABLE; + + // Wait until LDO ready + while ( 0 == (usb_hs_phyc->USB_HS_PHYC_LDO & USB_HS_PHYC_LDO_STATUS) ) {} + + uint32_t phyc_pll = 0; + switch ( HSE_VALUE ) + { + case 12000000: phyc_pll = USB_HS_PHYC_PLL1_PLLSEL_12MHZ ; break; + case 12500000: phyc_pll = USB_HS_PHYC_PLL1_PLLSEL_12_5MHZ ; break; + case 16000000: phyc_pll = USB_HS_PHYC_PLL1_PLLSEL_16MHZ ; break; + case 24000000: phyc_pll = USB_HS_PHYC_PLL1_PLLSEL_24MHZ ; break; + case 25000000: phyc_pll = USB_HS_PHYC_PLL1_PLLSEL_25MHZ ; break; + case 32000000: phyc_pll = USB_HS_PHYC_PLL1_PLLSEL_Msk ; break; // Value not defined in header default: - TU_ASSERT(0); - } - usb_hs_phyc->USB_HS_PHYC_PLL = phyc_pll; + TU_ASSERT(0); + } + usb_hs_phyc->USB_HS_PHYC_PLL = phyc_pll; - // Use magic value as in stm32f7xx_ll_usb. -# if !defined (USB_HS_PHYC_TUNE_VALUE) -# define USB_HS_PHYC_TUNE_VALUE 0x00000F13U /*!< Value of USB HS PHY Tune */ -# endif /* USB_HS_PHYC_TUNE_VALUE */ - // Control the tuning interface of the High Speed PHY */ - usb_hs_phyc->USB_HS_PHYC_TUNE |= USB_HS_PHYC_TUNE_VALUE; + // Control the tuning interface of the High Speed PHY + // Use magic value from ST driver + usb_hs_phyc->USB_HS_PHYC_TUNE |= 0x00000F13U; - // Enable PLL internal PHY - usb_hs_phyc->USB_HS_PHYC_PLL = phyc_pll | USB_HS_PHYC_PLL_PLLEN; + // Enable PLL internal PHY + usb_hs_phyc->USB_HS_PHYC_PLL |= USB_HS_PHYC_PLL_PLLEN; - /* Original ST code has 2 ms delay for PLL stabilization. - * Primitive test shows that more than 10 USB un/replug cycle - * showed no error with enumeration - * //#include "../../../../hw/bsp//board.h" - * //board_delay(2); - */ - return true; + // Original ST code has 2 ms delay for PLL stabilization. + // Primitive test shows that more than 10 USB un/replug cycle showed no error with enumeration + + return true; } -# endif +#endif /*------------------------------------------------------------------*/ /* Controller API @@ -417,9 +399,6 @@ void dcd_init (uint8_t rhport) // Enables control of a High Speed USB PHY USB_HS_PHYCInit(); - - // Disable external VBUS detection - usb_otg->GUSBCFG &= ~USB_OTG_GUSBCFG_ULPIEVBUSD; #endif } else #endif From 9a290febcdd7aaa50657f3d31da31bd493fa3a0e Mon Sep 17 00:00:00 2001 From: hathach Date: Thu, 2 Jul 2020 11:58:40 +0700 Subject: [PATCH 38/48] change default port some stm bsp - f769disco default port is highspeed port1 - remove PORT0 on stlink since the board only populated HS connector --- hw/bsp/stlinkv3mini/board.mk | 12 +---- hw/bsp/stm32f723disco/board.mk | 9 ++-- hw/bsp/stm32h743eval/board.mk | 13 +++++- src/portable/st/synopsys/dcd_synopsys.c | 58 +++++++++++++------------ 4 files changed, 49 insertions(+), 43 deletions(-) diff --git a/hw/bsp/stlinkv3mini/board.mk b/hw/bsp/stlinkv3mini/board.mk index 8576eeaa8..1a64c3735 100644 --- a/hw/bsp/stlinkv3mini/board.mk +++ b/hw/bsp/stlinkv3mini/board.mk @@ -1,5 +1,3 @@ -PORT ?= 1 - CFLAGS += \ -flto \ -mthumb \ @@ -11,14 +9,8 @@ CFLAGS += \ -DSTM32F723xx \ -DHSE_VALUE=25000000 \ -DCFG_TUSB_MCU=OPT_MCU_STM32F7 \ - -DBOARD_DEVICE_RHPORT_NUM=$(PORT) - -ifeq ($(PORT), 1) -CFLAGS += -DBOARD_DEVICE_RHPORT_SPEED=OPT_MODE_HIGH_SPEED -$(info "PORT1 HS") -else -$(info "PORT0") -endif + -DBOARD_DEVICE_RHPORT_NUM=1 \ + -DBOARD_DEVICE_RHPORT_SPEED=OPT_MODE_HIGH_SPEED # mcu driver cause following warnings CFLAGS += -Wno-error=shadow -Wno-error=cast-align diff --git a/hw/bsp/stm32f723disco/board.mk b/hw/bsp/stm32f723disco/board.mk index 2bd3b0756..2cf3ac633 100644 --- a/hw/bsp/stm32f723disco/board.mk +++ b/hw/bsp/stm32f723disco/board.mk @@ -1,4 +1,5 @@ -PORT ?= 0 +# Default is Highspeed port +PORT ?= 1 CFLAGS += \ -flto \ @@ -14,10 +15,10 @@ CFLAGS += \ -DBOARD_DEVICE_RHPORT_NUM=$(PORT) ifeq ($(PORT), 1) -CFLAGS += -DBOARD_DEVICE_RHPORT_SPEED=OPT_MODE_HIGH_SPEED -$(info "PORT1 HS") + CFLAGS += -DBOARD_DEVICE_RHPORT_SPEED=OPT_MODE_HIGH_SPEED + $(info "PORT1 High Speed") else -$(info "PORT0") + $(info "PORT0 Full Speed") endif # mcu driver cause following warnings diff --git a/hw/bsp/stm32h743eval/board.mk b/hw/bsp/stm32h743eval/board.mk index cbf37a95d..47d592c58 100644 --- a/hw/bsp/stm32h743eval/board.mk +++ b/hw/bsp/stm32h743eval/board.mk @@ -1,3 +1,6 @@ +# Default is Highspeed port +PORT ?= 1 + CFLAGS += \ -flto \ -mthumb \ @@ -8,8 +11,14 @@ CFLAGS += \ -nostdlib -nostartfiles \ -DSTM32H743xx \ -DCFG_TUSB_MCU=OPT_MCU_STM32H7 \ - -DBOARD_DEVICE_RHPORT_NUM=1 \ - -DBOARD_DEVICE_RHPORT_SPEED=OPT_MODE_HIGH_SPEED + -DBOARD_DEVICE_RHPORT_NUM=$(PORT) + +ifeq ($(PORT), 1) + CFLAGS += -DBOARD_DEVICE_RHPORT_SPEED=OPT_MODE_HIGH_SPEED + $(info "PORT1 High Speed") +else + $(info "PORT0 Full Speed") +endif # suppress warning caused by vendor mcu driver CFLAGS += -Wno-error=maybe-uninitialized -Wno-error=cast-align diff --git a/src/portable/st/synopsys/dcd_synopsys.c b/src/portable/st/synopsys/dcd_synopsys.c index 03238f8e2..a2d1983c2 100644 --- a/src/portable/st/synopsys/dcd_synopsys.c +++ b/src/portable/st/synopsys/dcd_synopsys.c @@ -390,7 +390,7 @@ void dcd_init (uint8_t rhport) // Select default internal VBUS Indicator and Drive for ULPI usb_otg->GUSBCFG &= ~(USB_OTG_GUSBCFG_ULPIEVBUSD | USB_OTG_GUSBCFG_ULPIEVBUSI); -#if defined(USB_HS_PHYC) + #if defined(USB_HS_PHYC) // Highspeed with embedded UTMI PHYC // Select UTMI Interface @@ -399,8 +399,9 @@ void dcd_init (uint8_t rhport) // Enables control of a High Speed USB PHY USB_HS_PHYCInit(); -#endif - } else + #endif + } + else #endif { // Enable internal PHY @@ -770,43 +771,46 @@ static void handle_rxflvl_ints(uint8_t rhport, USB_OTG_OUTEndpointTypeDef * out_ switch(pktsts) { case 0x01: // Global OUT NAK (Interrupt) - break; + break; + case 0x02: // Out packet recvd - { - xfer_ctl_t * xfer = XFER_CTL_BASE(epnum, TUSB_DIR_OUT); + { + xfer_ctl_t * xfer = XFER_CTL_BASE(epnum, TUSB_DIR_OUT); - // Read packet off RxFIFO - read_fifo_packet(rhport, xfer->buffer, bcnt); + // Read packet off RxFIFO + read_fifo_packet(rhport, xfer->buffer, bcnt); - // Increment pointer to xfer data - xfer->buffer += bcnt; + // Increment pointer to xfer data + xfer->buffer += bcnt; - // Truncate transfer length in case of short packet - if(bcnt < xfer->max_size) { - xfer->total_len -= (out_ep[epnum].DOEPTSIZ & USB_OTG_DOEPTSIZ_XFRSIZ_Msk) >> USB_OTG_DOEPTSIZ_XFRSIZ_Pos; - if(epnum == 0) { - xfer->total_len -= ep0_pending[TUSB_DIR_OUT]; - ep0_pending[TUSB_DIR_OUT] = 0; - } + // Truncate transfer length in case of short packet + if(bcnt < xfer->max_size) { + xfer->total_len -= (out_ep[epnum].DOEPTSIZ & USB_OTG_DOEPTSIZ_XFRSIZ_Msk) >> USB_OTG_DOEPTSIZ_XFRSIZ_Pos; + if(epnum == 0) { + xfer->total_len -= ep0_pending[TUSB_DIR_OUT]; + ep0_pending[TUSB_DIR_OUT] = 0; } } - break; + } + break; + case 0x03: // Out packet done (Interrupt) break; + case 0x04: // Setup packet done (Interrupt) out_ep[epnum].DOEPTSIZ |= (3 << USB_OTG_DOEPTSIZ_STUPCNT_Pos); - break; + break; + case 0x06: // Setup packet recvd - { - // We can receive up to three setup packets in succession, but - // only the last one is valid. - _setup_packet[0] = (* rx_fifo); - _setup_packet[1] = (* rx_fifo); - } - break; + // We can receive up to three setup packets in succession, but + // only the last one is valid. + _setup_packet[0] = (* rx_fifo); + _setup_packet[1] = (* rx_fifo); + break; + default: // Invalid TU_BREAKPOINT(); - break; + break; } } From 4cec866994f32f729844d0159e14c178f5aa904f Mon Sep 17 00:00:00 2001 From: hathach Date: Thu, 2 Jul 2020 14:57:00 +0700 Subject: [PATCH 39/48] correct HSE_VALUE in hal_conf - although it is define in CFLAGS, it is worth to correct to be consistent with other build - extract set_speed() --- README.md | 2 +- docs/boards.md | 5 + hw/bsp/stlinkv3mini/stm32f7xx_hal_conf.h | 2 +- hw/bsp/stm32f723disco/stm32f7xx_hal_conf.h | 2 +- hw/bsp/stm32f769disco/stm32f7xx_hal_conf.h | 2 +- src/portable/st/synopsys/dcd_synopsys.c | 128 +++++++++++---------- 6 files changed, 77 insertions(+), 64 deletions(-) diff --git a/README.md b/README.md index f9a7d0b73..8246ff460 100644 --- a/README.md +++ b/README.md @@ -39,7 +39,7 @@ The stack supports the following MCUs: - LPC Series: 11Uxx, 13xx, 175x_6x, 177x_8x, 18xx, 40xx, 43xx, 51Uxx, 54xxx, 55xx - iMX RT Series: RT1011, RT1015, RT1021, RT1052, RT1062, RT1064 - **Sony:** CXD56 -- **ST:** STM32 series: L0, F0, F1, F2, F3, F4, F7, H7 (device only) +- **ST:** STM32 series: L0, F0, F1, F2, F3, F4, F7, H7 both FullSpeed and HighSpeed - **TI:** MSP430 - **[ValentyUSB](https://github.com/im-tomu/valentyusb)** eptri diff --git a/docs/boards.md b/docs/boards.md index 57b1410bc..d3dcec375 100644 --- a/docs/boards.md +++ b/docs/boards.md @@ -85,6 +85,7 @@ This code base already had supported for a handful of following boards (sorted a - [Adafruit Feather STM32F405](https://www.adafruit.com/product/4382) - [Micro Python PyBoard v1.1](https://store.micropython.org/product/PYBv1.1) +- [STLink-V3 Mini](https://www.st.com/en/development-tools/stlink-v3mini.html) - [STM32 L035c8 Discovery](https://www.st.com/en/evaluation-tools/32l0538discovery.html) - [STM32 F070rb Nucleo](https://www.st.com/en/evaluation-tools/nucleo-f070rb.html) - [STM32 F072rb Discovery](https://www.st.com/en/evaluation-tools/32f072bdiscovery.html) @@ -96,9 +97,13 @@ This code base already had supported for a handful of following boards (sorted a - STM32 F411ce Black Pill - [STM32 F411ve Discovery](https://www.st.com/en/evaluation-tools/32f411ediscovery.html) - [STM32 F412zg Discovery](https://www.st.com/en/evaluation-tools/32f412gdiscovery.html) +- [STM32 F723e Discovery](https://www.st.com/en/evaluation-tools/32f723ediscovery.html) - [STM32 F746zg Nucleo](https://www.st.com/en/evaluation-tools/nucleo-f746zg.html) +- [STM32 F746g Discovery](https://www.st.com/en/evaluation-tools/32f746gdiscovery.html) - [STM32 F767zi Nucleo](https://www.st.com/en/evaluation-tools/nucleo-f767zi.html) +- [STM32 F769i Discovery](https://www.st.com/en/evaluation-tools/32f769idiscovery.html) - [STM32 H743zi Nucleo](https://www.st.com/en/evaluation-tools/nucleo-h743zi.html) +- [STM32 H743i Evaluation](https://www.st.com/en/evaluation-tools/stm32h743i-eval.html) ### TI diff --git a/hw/bsp/stlinkv3mini/stm32f7xx_hal_conf.h b/hw/bsp/stlinkv3mini/stm32f7xx_hal_conf.h index 03dec8f0d..581f0e46a 100644 --- a/hw/bsp/stlinkv3mini/stm32f7xx_hal_conf.h +++ b/hw/bsp/stlinkv3mini/stm32f7xx_hal_conf.h @@ -87,7 +87,7 @@ * (when HSE is used as system clock source, directly or through the PLL). */ #if !defined (HSE_VALUE) - #define HSE_VALUE ((uint32_t)8000000U) /*!< Value of the External oscillator in Hz */ + #define HSE_VALUE ((uint32_t)25000000U) /*!< Value of the External oscillator in Hz */ #endif /* HSE_VALUE */ #if !defined (HSE_STARTUP_TIMEOUT) diff --git a/hw/bsp/stm32f723disco/stm32f7xx_hal_conf.h b/hw/bsp/stm32f723disco/stm32f7xx_hal_conf.h index 03dec8f0d..581f0e46a 100644 --- a/hw/bsp/stm32f723disco/stm32f7xx_hal_conf.h +++ b/hw/bsp/stm32f723disco/stm32f7xx_hal_conf.h @@ -87,7 +87,7 @@ * (when HSE is used as system clock source, directly or through the PLL). */ #if !defined (HSE_VALUE) - #define HSE_VALUE ((uint32_t)8000000U) /*!< Value of the External oscillator in Hz */ + #define HSE_VALUE ((uint32_t)25000000U) /*!< Value of the External oscillator in Hz */ #endif /* HSE_VALUE */ #if !defined (HSE_STARTUP_TIMEOUT) diff --git a/hw/bsp/stm32f769disco/stm32f7xx_hal_conf.h b/hw/bsp/stm32f769disco/stm32f7xx_hal_conf.h index 03dec8f0d..581f0e46a 100644 --- a/hw/bsp/stm32f769disco/stm32f7xx_hal_conf.h +++ b/hw/bsp/stm32f769disco/stm32f7xx_hal_conf.h @@ -87,7 +87,7 @@ * (when HSE is used as system clock source, directly or through the PLL). */ #if !defined (HSE_VALUE) - #define HSE_VALUE ((uint32_t)8000000U) /*!< Value of the External oscillator in Hz */ + #define HSE_VALUE ((uint32_t)25000000U) /*!< Value of the External oscillator in Hz */ #endif /* HSE_VALUE */ #if !defined (HSE_STARTUP_TIMEOUT) diff --git a/src/portable/st/synopsys/dcd_synopsys.c b/src/portable/st/synopsys/dcd_synopsys.c index a2d1983c2..50984c830 100644 --- a/src/portable/st/synopsys/dcd_synopsys.c +++ b/src/portable/st/synopsys/dcd_synopsys.c @@ -285,12 +285,74 @@ static void set_turnaround(USB_OTG_GlobalTypeDef * usb_otg, tusb_speed_t speed) } } -static tusb_speed_t get_speed(USB_OTG_DeviceTypeDef* dev) +static tusb_speed_t get_speed(uint8_t rhport) { + USB_OTG_DeviceTypeDef * dev = DEVICE_BASE(rhport); uint32_t const enum_spd = (dev->DSTS & USB_OTG_DSTS_ENUMSPD_Msk) >> USB_OTG_DSTS_ENUMSPD_Pos; return (enum_spd == DCD_HIGH_SPEED) ? TUSB_SPEED_HIGH : TUSB_SPEED_FULL; } +static void set_speed(uint8_t rhport, tusb_speed_t speed) +{ + uint32_t bitvalue; + + if ( rhport == 1 ) + { + bitvalue = ((TUSB_SPEED_HIGH == speed) ? DCD_HIGH_SPEED : DCD_FULL_SPEED_USE_HS); + } + else + { + bitvalue = DCD_FULL_SPEED; + } + + USB_OTG_DeviceTypeDef * dev = DEVICE_BASE(rhport); + + // Clear and set speed bits + dev->DCFG &= ~(3 << USB_OTG_DCFG_DSPD_Pos); + dev->DCFG |= (bitvalue << USB_OTG_DCFG_DSPD_Pos); +} + +#if defined(USB_HS_PHYC) && TUD_OPT_HIGH_SPEED +static bool USB_HS_PHYCInit(void) +{ + USB_HS_PHYC_GlobalTypeDef *usb_hs_phyc = (USB_HS_PHYC_GlobalTypeDef*) USB_HS_PHYC_CONTROLLER_BASE; + + // Enable LDO + usb_hs_phyc->USB_HS_PHYC_LDO |= USB_HS_PHYC_LDO_ENABLE; + + // Wait until LDO ready + while ( 0 == (usb_hs_phyc->USB_HS_PHYC_LDO & USB_HS_PHYC_LDO_STATUS) ) {} + + uint32_t phyc_pll = 0; + + // TODO Try to get HSE_VALUE from registers instead of depending CFLAGS + switch ( HSE_VALUE ) + { + case 12000000: phyc_pll = USB_HS_PHYC_PLL1_PLLSEL_12MHZ ; break; + case 12500000: phyc_pll = USB_HS_PHYC_PLL1_PLLSEL_12_5MHZ ; break; + case 16000000: phyc_pll = USB_HS_PHYC_PLL1_PLLSEL_16MHZ ; break; + case 24000000: phyc_pll = USB_HS_PHYC_PLL1_PLLSEL_24MHZ ; break; + case 25000000: phyc_pll = USB_HS_PHYC_PLL1_PLLSEL_25MHZ ; break; + case 32000000: phyc_pll = USB_HS_PHYC_PLL1_PLLSEL_Msk ; break; // Value not defined in header + default: + TU_ASSERT(0); + } + usb_hs_phyc->USB_HS_PHYC_PLL = phyc_pll; + + // Control the tuning interface of the High Speed PHY + // Use magic value from ST driver + usb_hs_phyc->USB_HS_PHYC_TUNE |= 0x00000F13U; + + // Enable PLL internal PHY + usb_hs_phyc->USB_HS_PHYC_PLL |= USB_HS_PHYC_PLL_PLLEN; + + // Original ST code has 2 ms delay for PLL stabilization. + // Primitive test shows that more than 10 USB un/replug cycle showed no error with enumeration + + return true; +} +#endif + static void edpt_schedule_packets(uint8_t rhport, uint8_t const epnum, uint8_t const dir, uint16_t const num_packets, uint16_t total_bytes) { USB_OTG_DeviceTypeDef * dev = DEVICE_BASE(rhport); USB_OTG_OUTEndpointTypeDef * out_ep = OUT_EP_BASE(rhport); @@ -325,46 +387,6 @@ static void edpt_schedule_packets(uint8_t rhport, uint8_t const epnum, uint8_t c } } - -#if defined(USB_HS_PHYC) && TUD_OPT_HIGH_SPEED -static bool USB_HS_PHYCInit(void) -{ - USB_HS_PHYC_GlobalTypeDef *usb_hs_phyc = (USB_HS_PHYC_GlobalTypeDef*) USB_HS_PHYC_CONTROLLER_BASE; - - // Enable LDO - usb_hs_phyc->USB_HS_PHYC_LDO |= USB_HS_PHYC_LDO_ENABLE; - - // Wait until LDO ready - while ( 0 == (usb_hs_phyc->USB_HS_PHYC_LDO & USB_HS_PHYC_LDO_STATUS) ) {} - - uint32_t phyc_pll = 0; - switch ( HSE_VALUE ) - { - case 12000000: phyc_pll = USB_HS_PHYC_PLL1_PLLSEL_12MHZ ; break; - case 12500000: phyc_pll = USB_HS_PHYC_PLL1_PLLSEL_12_5MHZ ; break; - case 16000000: phyc_pll = USB_HS_PHYC_PLL1_PLLSEL_16MHZ ; break; - case 24000000: phyc_pll = USB_HS_PHYC_PLL1_PLLSEL_24MHZ ; break; - case 25000000: phyc_pll = USB_HS_PHYC_PLL1_PLLSEL_25MHZ ; break; - case 32000000: phyc_pll = USB_HS_PHYC_PLL1_PLLSEL_Msk ; break; // Value not defined in header - default: - TU_ASSERT(0); - } - usb_hs_phyc->USB_HS_PHYC_PLL = phyc_pll; - - // Control the tuning interface of the High Speed PHY - // Use magic value from ST driver - usb_hs_phyc->USB_HS_PHYC_TUNE |= 0x00000F13U; - - // Enable PLL internal PHY - usb_hs_phyc->USB_HS_PHYC_PLL |= USB_HS_PHYC_PLL_PLLEN; - - // Original ST code has 2 ms delay for PLL stabilization. - // Primitive test shows that more than 10 USB un/replug cycle showed no error with enumeration - - return true; -} -#endif - /*------------------------------------------------------------------*/ /* Controller API *------------------------------------------------------------------*/ @@ -431,21 +453,10 @@ void dcd_init (uint8_t rhport) // (non zero-length packet), send STALL back and discard. dev->DCFG |= USB_OTG_DCFG_NZLSOHSK; - // Clear speed bits - dev->DCFG &= ~(3 << USB_OTG_DCFG_DSPD_Pos); + set_speed(rhport, TUD_OPT_HIGH_SPEED ? TUSB_SPEED_HIGH : TUSB_SPEED_FULL); - if ( rhport == 1 ) - { - dev->DCFG |= ((TUD_OPT_HIGH_SPEED ? DCD_HIGH_SPEED : DCD_FULL_SPEED_USE_HS) << USB_OTG_DCFG_DSPD_Pos); - } - else - { - // full speed = 0x03 - dev->DCFG |= (DCD_FULL_SPEED << USB_OTG_DCFG_DSPD_Pos); - - // Enable internal USB transceiver. - usb_otg->GCCFG |= USB_OTG_GCCFG_PWRDWN; - } + // Enable internal USB transceiver. + if ( rhport == 0 ) usb_otg->GCCFG |= USB_OTG_GCCFG_PWRDWN; usb_otg->GINTMSK |= USB_OTG_GINTMSK_USBRST | USB_OTG_GINTMSK_ENUMDNEM | USB_OTG_GINTMSK_USBSUSPM | USB_OTG_GINTMSK_WUIM | @@ -511,7 +522,7 @@ bool dcd_edpt_open (uint8_t rhport, tusb_desc_endpoint_t const * desc_edpt) TU_ASSERT(epnum < EP_MAX); // TODO ISO endpoint can be up to 1024 bytes - TU_ASSERT(desc_edpt->wMaxPacketSize.size <= (get_speed(dev) == TUSB_SPEED_HIGH ? 512 : 64)); + TU_ASSERT(desc_edpt->wMaxPacketSize.size <= (get_speed(rhport) == TUSB_SPEED_HIGH ? 512 : 64)); xfer_ctl_t * xfer = XFER_CTL_BASE(epnum, dir); xfer->max_size = desc_edpt->wMaxPacketSize.size; @@ -575,9 +586,6 @@ bool dcd_edpt_open (uint8_t rhport, tusb_desc_endpoint_t const * desc_edpt) _allocated_fifo_words += fifo_size; - //TU_LOG2_INT(fifo_size); - //TU_LOG2_INT(_allocated_fifo_words); - in_ep[epnum].DIEPCTL |= (1 << USB_OTG_DIEPCTL_USBAEP_Pos) | (epnum << USB_OTG_DIEPCTL_TXFNUM_Pos) | (desc_edpt->bmAttributes.xfer << USB_OTG_DIEPCTL_EPTYP_Pos) | @@ -925,7 +933,7 @@ void dcd_int_handler(uint8_t rhport) usb_otg->GINTSTS = USB_OTG_GINTSTS_ENUMDNE; - tusb_speed_t const speed = get_speed(dev); + tusb_speed_t const speed = get_speed(rhport); set_turnaround(usb_otg, speed); dcd_event_bus_reset(rhport, speed, true); From a09a86d29931adf801d4293df879ec54164f689d Mon Sep 17 00:00:00 2001 From: hathach Date: Fri, 3 Jul 2020 01:19:02 +0700 Subject: [PATCH 40/48] fix NVIC disable typo --- src/portable/st/synopsys/dcd_synopsys.c | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/portable/st/synopsys/dcd_synopsys.c b/src/portable/st/synopsys/dcd_synopsys.c index 50984c830..288b4e50c 100644 --- a/src/portable/st/synopsys/dcd_synopsys.c +++ b/src/portable/st/synopsys/dcd_synopsys.c @@ -340,7 +340,7 @@ static bool USB_HS_PHYCInit(void) usb_hs_phyc->USB_HS_PHYC_PLL = phyc_pll; // Control the tuning interface of the High Speed PHY - // Use magic value from ST driver + // Use magic value (USB_HS_PHYC_TUNE_VALUE) from ST driver usb_hs_phyc->USB_HS_PHYC_TUNE |= 0x00000F13U; // Enable PLL internal PHY @@ -473,7 +473,7 @@ void dcd_int_enable (uint8_t rhport) void dcd_int_disable (uint8_t rhport) { - NVIC_EnableIRQ(_dcd_rhport[rhport].irqnum); + NVIC_DisableIRQ(_dcd_rhport[rhport].irqnum); } void dcd_set_address (uint8_t rhport, uint8_t dev_addr) From ad5ae8c31d286d17fc8bab81b42a19d77173aadb Mon Sep 17 00:00:00 2001 From: hathach Date: Fri, 3 Jul 2020 14:50:39 +0700 Subject: [PATCH 41/48] update per review --- src/portable/st/synopsys/dcd_synopsys.c | 89 +++++++++++++------------ 1 file changed, 47 insertions(+), 42 deletions(-) diff --git a/src/portable/st/synopsys/dcd_synopsys.c b/src/portable/st/synopsys/dcd_synopsys.c index 288b4e50c..ff227b55b 100644 --- a/src/portable/st/synopsys/dcd_synopsys.c +++ b/src/portable/st/synopsys/dcd_synopsys.c @@ -28,6 +28,10 @@ #include "tusb_option.h" +// Since TinyUSB doesn't use SOF for now, and this interrupt too often (1ms interval) +// We disable SOF for now until needed later on +#define USE_SOF 0 + #if defined (STM32F105x8) || defined (STM32F105xB) || defined (STM32F105xC) || \ defined (STM32F107xB) || defined (STM32F107xC) #define STM32F1_SYNOPSYS @@ -95,31 +99,28 @@ #include "device/dcd.h" //--------------------------------------------------------------------+ -// +// MACRO TYPEDEF CONSTANT ENUM //--------------------------------------------------------------------+ -typedef struct -{ - uint32_t regs; // registers - const IRQn_Type irqnum; // IRQ number -// const uint8_t ep_count; // Max bi-directional Endpoints -}dcd_rhport_t; +// On STM32 we associate Port0 to OTG_FS, and Port1 to OTG_HS +#if TUD_OPT_RHPORT == 0 + #define EP_MAX EP_MAX_FS + #define EP_FIFO_SIZE EP_FIFO_SIZE_FS + #define RHPORT_REGS_BASE USB_OTG_FS_PERIPH_BASE + #define RHPORT_IRQn OTG_FS_IRQn -// To be consistent across stm32 port. We will number OTG_FS as Rhport0, and OTG_HS as Rhport1 -static const dcd_rhport_t _dcd_rhport[] = -{ - { .regs = USB_OTG_FS_PERIPH_BASE, .irqnum = OTG_FS_IRQn } - -#ifdef USB_OTG_HS - ,{ .regs = USB_OTG_HS_PERIPH_BASE, .irqnum = OTG_HS_IRQn } +#else + #define EP_MAX EP_MAX_HS + #define EP_FIFO_SIZE EP_FIFO_SIZE_HS + #define RHPORT_REGS_BASE USB_OTG_HS_PERIPH_BASE + #define RHPORT_IRQn OTG_HS_IRQn #endif -}; -#define GLOBAL_BASE(_port) ((USB_OTG_GlobalTypeDef*) _dcd_rhport[_port].regs) -#define DEVICE_BASE(_port) (USB_OTG_DeviceTypeDef *) (_dcd_rhport[_port].regs + USB_OTG_DEVICE_BASE) -#define OUT_EP_BASE(_port) (USB_OTG_OUTEndpointTypeDef *) (_dcd_rhport[_port].regs + USB_OTG_OUT_ENDPOINT_BASE) -#define IN_EP_BASE(_port) (USB_OTG_INEndpointTypeDef *) (_dcd_rhport[_port].regs + USB_OTG_IN_ENDPOINT_BASE) -#define FIFO_BASE(_port, _x) ((volatile uint32_t *) (_dcd_rhport[_port].regs + USB_OTG_FIFO_BASE + (_x) * USB_OTG_FIFO_SIZE)) +#define GLOBAL_BASE(_port) ((USB_OTG_GlobalTypeDef*) RHPORT_REGS_BASE) +#define DEVICE_BASE(_port) (USB_OTG_DeviceTypeDef *) (RHPORT_REGS_BASE + USB_OTG_DEVICE_BASE) +#define OUT_EP_BASE(_port) (USB_OTG_OUTEndpointTypeDef *) (RHPORT_REGS_BASE + USB_OTG_OUT_ENDPOINT_BASE) +#define IN_EP_BASE(_port) (USB_OTG_INEndpointTypeDef *) (RHPORT_REGS_BASE + USB_OTG_IN_ENDPOINT_BASE) +#define FIFO_BASE(_port, _x) ((volatile uint32_t *) (RHPORT_REGS_BASE + USB_OTG_FIFO_BASE + (_x) * USB_OTG_FIFO_SIZE)) enum { @@ -128,14 +129,6 @@ enum DCD_FULL_SPEED = 3, // Full speed with internal PHY }; -/*------------------------------------------------------------------*/ -/* MACRO TYPEDEF CONSTANT ENUM - *------------------------------------------------------------------*/ - -// Since TinyUSB doesn't use SOF for now, and this interrupt too often (1ms interval) -// We disable SOF for now until needed later on -#define USE_SOF 0 - static TU_ATTR_ALIGNED(4) uint32_t _setup_packet[2]; typedef struct { @@ -146,14 +139,6 @@ typedef struct { typedef volatile uint32_t * usb_fifo_t; -#if TUD_OPT_RHPORT == 1 - #define EP_MAX EP_MAX_HS - #define EP_FIFO_SIZE EP_FIFO_SIZE_HS -#else - #define EP_MAX EP_MAX_FS - #define EP_FIFO_SIZE EP_FIFO_SIZE_FS -#endif - xfer_ctl_t xfer_status[EP_MAX][2]; #define XFER_CTL_BASE(_ep, _dir) &xfer_status[_ep][_dir] @@ -166,6 +151,8 @@ static uint16_t _allocated_fifo_words; // Setup the control endpoint 0. static void bus_reset(uint8_t rhport) { + (void) rhport; + USB_OTG_GlobalTypeDef * usb_otg = GLOBAL_BASE(rhport); USB_OTG_DeviceTypeDef * dev = DEVICE_BASE(rhport); USB_OTG_OUTEndpointTypeDef * out_ep = OUT_EP_BASE(rhport); @@ -287,6 +274,7 @@ static void set_turnaround(USB_OTG_GlobalTypeDef * usb_otg, tusb_speed_t speed) static tusb_speed_t get_speed(uint8_t rhport) { + (void) rhport; USB_OTG_DeviceTypeDef * dev = DEVICE_BASE(rhport); uint32_t const enum_spd = (dev->DSTS & USB_OTG_DSTS_ENUMSPD_Msk) >> USB_OTG_DSTS_ENUMSPD_Pos; return (enum_spd == DCD_HIGH_SPEED) ? TUSB_SPEED_HIGH : TUSB_SPEED_FULL; @@ -353,7 +341,10 @@ static bool USB_HS_PHYCInit(void) } #endif -static void edpt_schedule_packets(uint8_t rhport, uint8_t const epnum, uint8_t const dir, uint16_t const num_packets, uint16_t total_bytes) { +static void edpt_schedule_packets(uint8_t rhport, uint8_t const epnum, uint8_t const dir, uint16_t const num_packets, uint16_t total_bytes) +{ + (void) rhport; + USB_OTG_DeviceTypeDef * dev = DEVICE_BASE(rhport); USB_OTG_OUTEndpointTypeDef * out_ep = OUT_EP_BASE(rhport); USB_OTG_INEndpointTypeDef * in_ep = IN_EP_BASE(rhport); @@ -437,7 +428,7 @@ void dcd_init (uint8_t rhport) while ((usb_otg->GRSTCTL & USB_OTG_GRSTCTL_CSRST) == USB_OTG_GRSTCTL_CSRST) {} // Restart PHY clock - *((volatile uint32_t *)(_dcd_rhport[rhport].regs + USB_OTG_PCGCCTL_BASE)) = 0; + *((volatile uint32_t *)(RHPORT_REGS_BASE + USB_OTG_PCGCCTL_BASE)) = 0; // Clear all interrupts usb_otg->GINTSTS |= usb_otg->GINTSTS; @@ -468,12 +459,14 @@ void dcd_init (uint8_t rhport) void dcd_int_enable (uint8_t rhport) { - NVIC_EnableIRQ(_dcd_rhport[rhport].irqnum); + (void) rhport; + NVIC_EnableIRQ(RHPORT_IRQn); } void dcd_int_disable (uint8_t rhport) { - NVIC_DisableIRQ(_dcd_rhport[rhport].irqnum); + (void) rhport; + NVIC_DisableIRQ(RHPORT_IRQn); } void dcd_set_address (uint8_t rhport, uint8_t dev_addr) @@ -492,6 +485,7 @@ void dcd_remote_wakeup(uint8_t rhport) void dcd_connect(uint8_t rhport) { + (void) rhport; USB_OTG_DeviceTypeDef * dev = DEVICE_BASE(rhport); dev->DCTL &= ~USB_OTG_DCTL_SDIS; @@ -499,6 +493,7 @@ void dcd_connect(uint8_t rhport) void dcd_disconnect(uint8_t rhport) { + (void) rhport; USB_OTG_DeviceTypeDef * dev = DEVICE_BASE(rhport); dev->DCTL |= USB_OTG_DCTL_SDIS; @@ -633,6 +628,8 @@ bool dcd_edpt_xfer (uint8_t rhport, uint8_t ep_addr, uint8_t * buffer, uint16_t // (send STALL versus NAK handshakes back). Refactor into resuable function. void dcd_edpt_stall (uint8_t rhport, uint8_t ep_addr) { + (void) rhport; + USB_OTG_GlobalTypeDef * usb_otg = GLOBAL_BASE(rhport); USB_OTG_DeviceTypeDef * dev = DEVICE_BASE(rhport); USB_OTG_OUTEndpointTypeDef * out_ep = OUT_EP_BASE(rhport); @@ -685,6 +682,8 @@ void dcd_edpt_stall (uint8_t rhport, uint8_t ep_addr) void dcd_edpt_clear_stall (uint8_t rhport, uint8_t ep_addr) { + (void) rhport; + USB_OTG_OUTEndpointTypeDef * out_ep = OUT_EP_BASE(rhport); USB_OTG_INEndpointTypeDef * in_ep = IN_EP_BASE(rhport); @@ -713,7 +712,10 @@ void dcd_edpt_clear_stall (uint8_t rhport, uint8_t ep_addr) /*------------------------------------------------------------------*/ // Read a single data packet from receive FIFO -static void read_fifo_packet(uint8_t rhport, uint8_t * dst, uint16_t len){ +static void read_fifo_packet(uint8_t rhport, uint8_t * dst, uint16_t len) +{ + (void) rhport; + usb_fifo_t rx_fifo = FIFO_BASE(rhport, 0); // Reading full available 32 bit words from fifo @@ -742,7 +744,10 @@ static void read_fifo_packet(uint8_t rhport, uint8_t * dst, uint16_t len){ } // Write a single data packet to EPIN FIFO -static void write_fifo_packet(uint8_t rhport, uint8_t fifo_num, uint8_t * src, uint16_t len){ +static void write_fifo_packet(uint8_t rhport, uint8_t fifo_num, uint8_t * src, uint16_t len) +{ + (void) rhport; + usb_fifo_t tx_fifo = FIFO_BASE(rhport, fifo_num); // Pushing full available 32 bit words to fifo From fd3817818921981aa67e1fb845f926c010444fea Mon Sep 17 00:00:00 2001 From: Uwe Bonnes Date: Wed, 1 Jul 2020 23:07:18 +0200 Subject: [PATCH 42/48] STM32/OTG_HS: Allow OTG_HS port to run at FS speed. Add "REDUCE_SPEED=1" to the compile options. --- hw/bsp/stlinkv3mini/board.mk | 18 ++++++++++++++++-- hw/bsp/stm32f723disco/board.mk | 13 +++++++++---- hw/bsp/stm32f746disco/board.mk | 10 ++++++++-- hw/bsp/stm32f769disco/board.mk | 11 ++++++++++- hw/mcu/nordic/nrfx | 2 +- src/portable/st/synopsys/dcd_synopsys.c | 8 +++----- 6 files changed, 47 insertions(+), 15 deletions(-) diff --git a/hw/bsp/stlinkv3mini/board.mk b/hw/bsp/stlinkv3mini/board.mk index 1a64c3735..47148ec4d 100644 --- a/hw/bsp/stlinkv3mini/board.mk +++ b/hw/bsp/stlinkv3mini/board.mk @@ -1,3 +1,6 @@ +PORT ?= 1 +REDUCE_SPEED ?= 0 + CFLAGS += \ -flto \ -mthumb \ @@ -9,8 +12,19 @@ CFLAGS += \ -DSTM32F723xx \ -DHSE_VALUE=25000000 \ -DCFG_TUSB_MCU=OPT_MCU_STM32F7 \ - -DBOARD_DEVICE_RHPORT_NUM=1 \ - -DBOARD_DEVICE_RHPORT_SPEED=OPT_MODE_HIGH_SPEED + -DBOARD_DEVICE_RHPORT_NUM=$(PORT) + +ifeq ($(PORT), 1) + ifeq ($(REDUCE_SPEED), 0) +CFLAGS += -DBOARD_DEVICE_RHPORT_SPEED=OPT_MODE_HIGH_SPEED +$(info "Using OTG_HS in HS mode") + else +CFLAGS += -DBOARD_DEVICE_RHPORT_SPEED=OPT_MODE_FULL_SPEED +$(info "Using OTG_HS in FS mode") + endif +else +$(info "Using OTG_FS") +endif # mcu driver cause following warnings CFLAGS += -Wno-error=shadow -Wno-error=cast-align diff --git a/hw/bsp/stm32f723disco/board.mk b/hw/bsp/stm32f723disco/board.mk index 2cf3ac633..47148ec4d 100644 --- a/hw/bsp/stm32f723disco/board.mk +++ b/hw/bsp/stm32f723disco/board.mk @@ -1,5 +1,5 @@ -# Default is Highspeed port PORT ?= 1 +REDUCE_SPEED ?= 0 CFLAGS += \ -flto \ @@ -15,10 +15,15 @@ CFLAGS += \ -DBOARD_DEVICE_RHPORT_NUM=$(PORT) ifeq ($(PORT), 1) - CFLAGS += -DBOARD_DEVICE_RHPORT_SPEED=OPT_MODE_HIGH_SPEED - $(info "PORT1 High Speed") + ifeq ($(REDUCE_SPEED), 0) +CFLAGS += -DBOARD_DEVICE_RHPORT_SPEED=OPT_MODE_HIGH_SPEED +$(info "Using OTG_HS in HS mode") + else +CFLAGS += -DBOARD_DEVICE_RHPORT_SPEED=OPT_MODE_FULL_SPEED +$(info "Using OTG_HS in FS mode") + endif else - $(info "PORT0 Full Speed") +$(info "Using OTG_FS") endif # mcu driver cause following warnings diff --git a/hw/bsp/stm32f746disco/board.mk b/hw/bsp/stm32f746disco/board.mk index 76a54cdfd..d7329a28f 100644 --- a/hw/bsp/stm32f746disco/board.mk +++ b/hw/bsp/stm32f746disco/board.mk @@ -1,4 +1,5 @@ PORT ?= 0 +REDUCE_SPEED ?= 0 CFLAGS += \ -flto \ @@ -14,10 +15,15 @@ CFLAGS += \ -DBOARD_DEVICE_RHPORT_NUM=$(PORT) ifeq ($(PORT), 1) + ifeq ($(REDUCE_SPEED), 0) CFLAGS += -DBOARD_DEVICE_RHPORT_SPEED=OPT_MODE_HIGH_SPEED -$(info "PORT1 HS") +$(info "Using OTG_HS in HS mode") + else +CFLAGS += -DBOARD_DEVICE_RHPORT_SPEED=OPT_MODE_FULL_SPEED +$(info "Using OTG_HS in FS mode") + endif else -$(info "PORT0") +$(info "Using OTG_FS") endif # mcu driver cause following warnings diff --git a/hw/bsp/stm32f769disco/board.mk b/hw/bsp/stm32f769disco/board.mk index 62c05cca5..43b677ddd 100644 --- a/hw/bsp/stm32f769disco/board.mk +++ b/hw/bsp/stm32f769disco/board.mk @@ -1,3 +1,5 @@ +REDUCE_SPEED ?= 0 + CFLAGS += \ -flto \ -mthumb \ @@ -10,7 +12,14 @@ CFLAGS += \ -DHSE_VALUE=25000000 \ -DCFG_TUSB_MCU=OPT_MCU_STM32F7 \ -DBOARD_DEVICE_RHPORT_NUM=1 \ - -DBOARD_DEVICE_RHPORT_SPEED=OPT_MODE_HIGH_SPEED + +ifeq ($(REDUCE_SPEED), 0) +CFLAGS += -DBOARD_DEVICE_RHPORT_SPEED=OPT_MODE_HIGH_SPEED +$(info "Using OTG_HS in HS mode") +else +CFLAGS += -DBOARD_DEVICE_RHPORT_SPEED=OPT_MODE_FULL_SPEED +$(info "Using OTG_HS in FS mode") +endif # suppress warning caused by vendor mcu driver CFLAGS += -Wno-error=cast-align -Wno-error=shadow diff --git a/hw/mcu/nordic/nrfx b/hw/mcu/nordic/nrfx index a5397bea5..281cc2e17 160000 --- a/hw/mcu/nordic/nrfx +++ b/hw/mcu/nordic/nrfx @@ -1 +1 @@ -Subproject commit a5397bea558fb4b6838081a22d1ee679289d7417 +Subproject commit 281cc2e178fd9a470d844b3afdea9eb322a0b0e8 diff --git a/src/portable/st/synopsys/dcd_synopsys.c b/src/portable/st/synopsys/dcd_synopsys.c index 50984c830..6c3a10b00 100644 --- a/src/portable/st/synopsys/dcd_synopsys.c +++ b/src/portable/st/synopsys/dcd_synopsys.c @@ -312,7 +312,8 @@ static void set_speed(uint8_t rhport, tusb_speed_t speed) dev->DCFG |= (bitvalue << USB_OTG_DCFG_DSPD_Pos); } -#if defined(USB_HS_PHYC) && TUD_OPT_HIGH_SPEED + +#if defined(USB_HS_PHYC) static bool USB_HS_PHYCInit(void) { USB_HS_PHYC_GlobalTypeDef *usb_hs_phyc = (USB_HS_PHYC_GlobalTypeDef*) USB_HS_PHYC_CONTROLLER_BASE; @@ -398,7 +399,6 @@ void dcd_init (uint8_t rhport) USB_OTG_GlobalTypeDef * usb_otg = GLOBAL_BASE(rhport); // No HNP/SRP (no OTG support), program timeout later. -#if TUD_OPT_HIGH_SPEED // TODO may pass parameter instead of using macro for HighSpeed if ( rhport == 1 ) { // On selected MCUs HS port1 can be used with external PHY via ULPI interface @@ -421,10 +421,8 @@ void dcd_init (uint8_t rhport) // Enables control of a High Speed USB PHY USB_HS_PHYCInit(); - #endif - } - else #endif + } else { // Enable internal PHY usb_otg->GUSBCFG |= USB_OTG_GUSBCFG_PHYSEL; From 4b7539bd6320cc6659fe458e91a51ffb7896f45c Mon Sep 17 00:00:00 2001 From: Uwe Bonnes Date: Thu, 2 Jul 2020 00:23:38 +0200 Subject: [PATCH 43/48] stm32h745disco: Only OTG_FS is available. Does not enumerate on replug yet. --- hw/bsp/stm32h745disco/STM32H74xXIHx_FLASH.ld | 173 +++++++ hw/bsp/stm32h745disco/board.mk | 58 +++ hw/bsp/stm32h745disco/stm32h745disco.c | 399 +++++++++++++++ hw/bsp/stm32h745disco/stm32h7xx_hal_conf.h | 482 +++++++++++++++++++ 4 files changed, 1112 insertions(+) create mode 100644 hw/bsp/stm32h745disco/STM32H74xXIHx_FLASH.ld create mode 100644 hw/bsp/stm32h745disco/board.mk create mode 100644 hw/bsp/stm32h745disco/stm32h745disco.c create mode 100644 hw/bsp/stm32h745disco/stm32h7xx_hal_conf.h diff --git a/hw/bsp/stm32h745disco/STM32H74xXIHx_FLASH.ld b/hw/bsp/stm32h745disco/STM32H74xXIHx_FLASH.ld new file mode 100644 index 000000000..59b9ff4df --- /dev/null +++ b/hw/bsp/stm32h745disco/STM32H74xXIHx_FLASH.ld @@ -0,0 +1,173 @@ +/* +***************************************************************************** +** + +** File : LinkerScript.ld +** +** Abstract : Linker script for STM32H743XIHx Device with +** 2048KByte FLASH, 128KByte RAM +** +** Set heap size, stack size and stack location according +** to application requirements. +** +** Set memory bank area and size if external memory is used. +** +** Target : STMicroelectronics STM32 +** +** +** Distribution: The file is distributed as is, without any warranty +** of any kind. +** +** (c)Copyright Ac6. +** You may use this file as-is or modify it according to the needs of your +** project. Distribution of this file (unmodified or modified) is not +** permitted. Ac6 permit registered System Workbench for MCU users the +** rights to distribute the assembled, compiled & linked contents of this +** file as part of an application binary file, provided that it is built +** using the System Workbench for MCU toolchain. +** +***************************************************************************** +*/ + +/* Entry Point */ +ENTRY(Reset_Handler) + +/* Highest address of the user mode stack */ +_estack = 0x20020000; /* end of RAM */ +/* Generate a link error if heap and stack don't fit into RAM */ +_Min_Heap_Size = 0x200; /* required amount of heap */ +_Min_Stack_Size = 0x400; /* required amount of stack */ + +/* Specify the memory areas */ +MEMORY +{ +DTCMRAM (xrw) : ORIGIN = 0x20000000, LENGTH = 128K +RAM_D1 (xrw) : ORIGIN = 0x24000000, LENGTH = 512K +RAM_D2 (xrw) : ORIGIN = 0x30000000, LENGTH = 288K +RAM_D3 (xrw) : ORIGIN = 0x38000000, LENGTH = 64K +ITCMRAM (xrw) : ORIGIN = 0x00000000, LENGTH = 64K +FLASH (rx) : ORIGIN = 0x8000000, LENGTH = 2048K +} + +/* Define output sections */ +SECTIONS +{ + /* The startup code goes first into FLASH */ + .isr_vector : + { + . = ALIGN(4); + KEEP(*(.isr_vector)) /* Startup code */ + . = ALIGN(4); + } >FLASH + + /* The program code and other data goes into FLASH */ + .text : + { + . = ALIGN(4); + *(.text) /* .text sections (code) */ + *(.text*) /* .text* sections (code) */ + *(.glue_7) /* glue arm to thumb code */ + *(.glue_7t) /* glue thumb to arm code */ + *(.eh_frame) + + KEEP (*(.init)) + KEEP (*(.fini)) + + . = ALIGN(4); + _etext = .; /* define a global symbols at end of code */ + } >FLASH + + /* Constant data goes into FLASH */ + .rodata : + { + . = ALIGN(4); + *(.rodata) /* .rodata sections (constants, strings, etc.) */ + *(.rodata*) /* .rodata* sections (constants, strings, etc.) */ + . = ALIGN(4); + } >FLASH + + .ARM.extab : { *(.ARM.extab* .gnu.linkonce.armextab.*) } >FLASH + .ARM : { + __exidx_start = .; + *(.ARM.exidx*) + __exidx_end = .; + } >FLASH + + .preinit_array : + { + PROVIDE_HIDDEN (__preinit_array_start = .); + KEEP (*(.preinit_array*)) + PROVIDE_HIDDEN (__preinit_array_end = .); + } >FLASH + .init_array : + { + PROVIDE_HIDDEN (__init_array_start = .); + KEEP (*(SORT(.init_array.*))) + KEEP (*(.init_array*)) + PROVIDE_HIDDEN (__init_array_end = .); + } >FLASH + .fini_array : + { + PROVIDE_HIDDEN (__fini_array_start = .); + KEEP (*(SORT(.fini_array.*))) + KEEP (*(.fini_array*)) + PROVIDE_HIDDEN (__fini_array_end = .); + } >FLASH + + /* used by the startup to initialize data */ + _sidata = LOADADDR(.data); + + /* Initialized data sections goes into RAM, load LMA copy after code */ + .data : + { + . = ALIGN(4); + _sdata = .; /* create a global symbol at data start */ + *(.data) /* .data sections */ + *(.data*) /* .data* sections */ + + . = ALIGN(4); + _edata = .; /* define a global symbol at data end */ + } >DTCMRAM AT> FLASH + + + /* Uninitialized data section */ + . = ALIGN(4); + .bss : + { + /* This is used by the startup in order to initialize the .bss secion */ + _sbss = .; /* define a global symbol at bss start */ + __bss_start__ = _sbss; + *(.bss) + *(.bss*) + *(COMMON) + + . = ALIGN(4); + _ebss = .; /* define a global symbol at bss end */ + __bss_end__ = _ebss; + } >DTCMRAM + + /* User_heap_stack section, used to check that there is enough RAM left */ + ._user_heap_stack : + { + . = ALIGN(8); + PROVIDE ( end = . ); + PROVIDE ( _end = . ); + . = . + _Min_Heap_Size; + . = . + _Min_Stack_Size; + . = ALIGN(8); + } >DTCMRAM + + + + /* Remove information from the standard libraries */ + /DISCARD/ : + { + libc.a ( * ) + libm.a ( * ) + libgcc.a ( * ) + } + + .ARM.attributes 0 : { *(.ARM.attributes) } +} + + diff --git a/hw/bsp/stm32h745disco/board.mk b/hw/bsp/stm32h745disco/board.mk new file mode 100644 index 000000000..b3477b1e6 --- /dev/null +++ b/hw/bsp/stm32h745disco/board.mk @@ -0,0 +1,58 @@ +# STM32H745I-DISCO uses OTG_FS +# FIXME: Reset enumerates, un/replug USB plug does not enumerate + +CFLAGS += \ + -flto \ + -mthumb \ + -mabi=aapcs \ + -mcpu=cortex-m7 \ + -mfloat-abi=hard \ + -mfpu=fpv5-d16 \ + -nostdlib -nostartfiles \ + -DSTM32H745xx \ + -DCORE_CM7 \ + -DCFG_TUSB_MCU=OPT_MCU_STM32H7 \ + -DBOARD_DEVICE_RHPORT_NUM=0 \ + -DBOARD_DEVICE_RHPORT_SPEED=OPT_MODE_FULL_SPEED + +# suppress warning caused by vendor mcu driver +CFLAGS += -Wno-error=maybe-uninitialized -Wno-error=cast-align + +ST_HAL_DRIVER = hw/mcu/st/st_driver/STM32H7xx_HAL_Driver +ST_CMSIS = hw/mcu/st/st_driver/CMSIS/Device/ST/STM32H7xx + +# All source paths should be relative to the top level. +LD_FILE = hw/bsp/$(BOARD)/STM32H74xXIHx_FLASH.ld + +SRC_C += \ + $(ST_CMSIS)/Source/Templates/system_stm32h7xx.c \ + $(ST_HAL_DRIVER)/Src/stm32h7xx_hal.c \ + $(ST_HAL_DRIVER)/Src/stm32h7xx_hal_cortex.c \ + $(ST_HAL_DRIVER)/Src/stm32h7xx_hal_rcc.c \ + $(ST_HAL_DRIVER)/Src/stm32h7xx_hal_rcc_ex.c \ + $(ST_HAL_DRIVER)/Src/stm32h7xx_hal_gpio.c \ + $(ST_HAL_DRIVER)/Src/stm32h7xx_hal_uart.c \ + $(ST_HAL_DRIVER)/Src/stm32h7xx_hal_pwr_ex.c + +SRC_S += \ + $(ST_CMSIS)/Source/Templates/gcc/startup_stm32h745xx.s + +INC += \ + $(TOP)/hw/mcu/st/st_driver/CMSIS/Include \ + $(TOP)/$(ST_CMSIS)/Include \ + $(TOP)/$(ST_HAL_DRIVER)/Inc \ + $(TOP)/hw/bsp/$(BOARD) + +# For TinyUSB port source +VENDOR = st +CHIP_FAMILY = synopsys + +# For freeRTOS port source +FREERTOS_PORT = ARM_CM7/r0p1 + +# For flash-jlink target +JLINK_DEVICE = stm32h745xi +JLINK_IF = swd + +# flash target using on-board stlink +flash: flash-stlink diff --git a/hw/bsp/stm32h745disco/stm32h745disco.c b/hw/bsp/stm32h745disco/stm32h745disco.c new file mode 100644 index 000000000..ce4034af0 --- /dev/null +++ b/hw/bsp/stm32h745disco/stm32h745disco.c @@ -0,0 +1,399 @@ +/* + * The MIT License (MIT) + * + * Copyright (c) 2019 William D. Jones (thor0505@comcast.net), + * Ha Thach (tinyusb.org) + * Uwe Bonnes (bon@elektron.ikp.physik.tu-darmstadt.de + * + * Permission is hereby granted, free of charge, to any person obtaining a copy + * of this software and associated documentation files (the "Software"), to deal + * in the Software without restriction, including without limitation the rights + * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell + * copies of the Software, and to permit persons to whom the Software is + * furnished to do so, subject to the following conditions: + * + * The above copyright notice and this permission notice shall be included in + * all copies or substantial portions of the Software. + * + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR + * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE + * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER + * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, + * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN + * THE SOFTWARE. + * + * This file is part of the TinyUSB stack. + */ + +#include "../board.h" + +#include "stm32h7xx_hal.h" + +//--------------------------------------------------------------------+ +// Forward USB interrupt events to TinyUSB IRQ Handler +//--------------------------------------------------------------------+ + +// Despite being call USB2_OTG +// OTG_FS is marked as RHPort0 by TinyUSB to be consistent across stm32 port +void OTG_FS_IRQHandler(void) +{ + tud_int_handler(0); +} + +// Despite being call USB2_OTG +// OTG_HS is marked as RHPort1 by TinyUSB to be consistent across stm32 port +void OTG_HS_IRQHandler(void) +{ + tud_int_handler(1); +} + + +//--------------------------------------------------------------------+ +// MACRO TYPEDEF CONSTANT ENUM +//--------------------------------------------------------------------+ + +#define LED_PORT GPIOJ +#define LED_PIN GPIO_PIN_2 +#define LED_STATE_ON 1 + +// Blue push-button +#define BUTTON_PORT GPIOC +#define BUTTON_PIN GPIO_PIN_13 +#define BUTTON_STATE_ACTIVE 1 + +// UART +#define UARTx USART3 +#define UART_GPIO_PORT GPIOB +#define UART_GPIO_AF GPIO_AF7_USART3 +#define UART_TX_PIN GPIO_PIN_10 +#define UART_RX_PIN GPIO_PIN_11 + +UART_HandleTypeDef UartHandle; + +// enable all LED, Button, Uart, USB clock +static void all_rcc_clk_enable(void) +{ + __HAL_RCC_GPIOA_CLK_ENABLE(); // OTG_FS + __HAL_RCC_GPIOB_CLK_ENABLE(); // USART3 (VCP + __HAL_RCC_GPIOC_CLK_ENABLE(); // Button + __HAL_RCC_GPIOJ_CLK_ENABLE(); // LED + __HAL_RCC_USART3_CLK_ENABLE(); // Uart module +} + +/* PWR, RCC, GPIO (All): AHB4 (D3 domain) + USB{1,2} OTG_{H,F}S: AHB1 (D2 domain) +*/ + +/** + * @brief System Clock Configuration + * The system Clock is configured as follow : + * System Clock source = PLL (HSE) + * SYSCLK(Hz) = 400000000 (CPU Clock) + * HCLK(Hz) = 200000000 (AXI and AHBs Clock) + * AHB Prescaler = 2 + * D1 APB3 Prescaler = 2 (APB3 Clock 100MHz) + * D2 APB1 Prescaler = 2 (APB1 Clock 100MHz) + * D2 APB2 Prescaler = 2 (APB2 Clock 100MHz) + * D3 APB4 Prescaler = 2 (APB4 Clock 100MHz) + * HSE Frequency(Hz) = 25000000 + * PLL_M = 5 + * PLL_N = 160 + * PLL_P = 2 + * PLL_Q = 4 + * PLL_R = 2 + * PLL3_M = 25 + * PLL3_N = 336 + * PLL3_P = 2 + * PLL3_Q = 7 + * PLL3_R = 2 + * VDD(V) = 3.3 + * Flash Latency(WS) = 4 + * @param None + * @retval None + */ + +void SystemClock_Config(void) +{ + RCC_ClkInitTypeDef RCC_ClkInitStruct; + RCC_OscInitTypeDef RCC_OscInitStruct; + RCC_PeriphCLKInitTypeDef PeriphClkInitStruct; + + /*!< Supply configuration update enable */ + /* For STM32H750XB, use "HAL_PWREx_ConfigSupply(PWR_LDO_SUPPLY);" */ + HAL_PWREx_ConfigSupply(PWR_DIRECT_SMPS_SUPPLY); + + /* The voltage scaling allows optimizing the power consumption when the + device is clocked below the maximum system frequency, to update the + voltage scaling value regarding system frequency refer to product + datasheet. */ + __HAL_PWR_VOLTAGESCALING_CONFIG(PWR_REGULATOR_VOLTAGE_SCALE1); + + while ((PWR->D3CR & (PWR_D3CR_VOSRDY)) != PWR_D3CR_VOSRDY) {} + + /* Enable HSE Oscillator and activate PLL with HSE as source */ + RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_HSE; + RCC_OscInitStruct.HSEState = RCC_HSE_BYPASS; + RCC_OscInitStruct.HSIState = RCC_HSI_OFF; + RCC_OscInitStruct.CSIState = RCC_CSI_OFF; + RCC_OscInitStruct.PLL.PLLState = RCC_PLL_ON; + RCC_OscInitStruct.PLL.PLLSource = RCC_PLLSOURCE_HSE; + + /* PLL1 for System Clock */ + RCC_OscInitStruct.PLL.PLLM = 5; + RCC_OscInitStruct.PLL.PLLN = 160; + RCC_OscInitStruct.PLL.PLLFRACN = 0; + RCC_OscInitStruct.PLL.PLLP = 2; + RCC_OscInitStruct.PLL.PLLR = 2; + RCC_OscInitStruct.PLL.PLLQ = 4; + + RCC_OscInitStruct.PLL.PLLVCOSEL = RCC_PLL1VCOMEDIUM; + RCC_OscInitStruct.PLL.PLLRGE = RCC_PLL1VCIRANGE_2; + HAL_RCC_OscConfig(&RCC_OscInitStruct); + + /* PLL3 for USB Clock */ + PeriphClkInitStruct.PLL3.PLL3M = 25; + PeriphClkInitStruct.PLL3.PLL3N = 336; + PeriphClkInitStruct.PLL3.PLL3FRACN = 0; + PeriphClkInitStruct.PLL3.PLL3P = 2; + PeriphClkInitStruct.PLL3.PLL3R = 2; + PeriphClkInitStruct.PLL3.PLL3Q = 7; + + PeriphClkInitStruct.PeriphClockSelection = RCC_PERIPHCLK_USB; + PeriphClkInitStruct.UsbClockSelection = RCC_USBCLKSOURCE_PLL3; + HAL_RCCEx_PeriphCLKConfig(&PeriphClkInitStruct); + + /* Select PLL as system clock source and configure bus clocks dividers */ + RCC_ClkInitStruct.ClockType = (RCC_CLOCKTYPE_SYSCLK | RCC_CLOCKTYPE_HCLK | RCC_CLOCKTYPE_D1PCLK1 | RCC_CLOCKTYPE_PCLK1 | \ + RCC_CLOCKTYPE_PCLK2 | RCC_CLOCKTYPE_D3PCLK1); + + RCC_ClkInitStruct.SYSCLKSource = RCC_SYSCLKSOURCE_PLLCLK; + RCC_ClkInitStruct.SYSCLKDivider = RCC_SYSCLK_DIV1; + RCC_ClkInitStruct.AHBCLKDivider = RCC_HCLK_DIV2; + RCC_ClkInitStruct.APB1CLKDivider = RCC_APB1_DIV2; + RCC_ClkInitStruct.APB2CLKDivider = RCC_APB2_DIV2; + RCC_ClkInitStruct.APB3CLKDivider = RCC_APB3_DIV1; + HAL_RCC_ClockConfig(&RCC_ClkInitStruct, FLASH_LATENCY_4); + + /*activate CSI clock mondatory for I/O Compensation Cell*/ + __HAL_RCC_CSI_ENABLE() ; + + /* Enable SYSCFG clock mondatory for I/O Compensation Cell */ + __HAL_RCC_SYSCFG_CLK_ENABLE() ; + + /* Enables the I/O Compensation Cell */ + HAL_EnableCompensationCell(); +} + +void board_init(void) +{ + SystemClock_Config(); + all_rcc_clk_enable(); + + // 1ms tick timer + SysTick_Config(SystemCoreClock / 1000); + +#if CFG_TUSB_OS == OPT_OS_FREERTOS + // If freeRTOS is used, IRQ priority is limit by max syscall ( smaller is higher ) + NVIC_SetPriority(OTG_FS_IRQn, configLIBRARY_MAX_SYSCALL_INTERRUPT_PRIORITY ); + NVIC_SetPriority(OTG_HS_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); + + // Button + GPIO_InitStruct.Pin = BUTTON_PIN; + GPIO_InitStruct.Mode = GPIO_MODE_INPUT; + GPIO_InitStruct.Pull = GPIO_NOPULL; + GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_HIGH; + HAL_GPIO_Init(BUTTON_PORT, &GPIO_InitStruct); + + // Uart + GPIO_InitStruct.Pin = UART_TX_PIN | UART_RX_PIN; + GPIO_InitStruct.Mode = GPIO_MODE_AF_PP; + GPIO_InitStruct.Pull = GPIO_PULLUP; + GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_VERY_HIGH; + GPIO_InitStruct.Alternate = UART_GPIO_AF; + HAL_GPIO_Init(UART_GPIO_PORT, &GPIO_InitStruct); + + UartHandle.Instance = UARTx; + UartHandle.Init.BaudRate = CFG_BOARD_UART_BAUDRATE; + UartHandle.Init.WordLength = UART_WORDLENGTH_8B; + UartHandle.Init.StopBits = UART_STOPBITS_1; + UartHandle.Init.Parity = UART_PARITY_NONE; + UartHandle.Init.HwFlowCtl = UART_HWCONTROL_NONE; + UartHandle.Init.Mode = UART_MODE_TX_RX; + UartHandle.Init.OverSampling = UART_OVERSAMPLING_16; + HAL_UART_Init(&UartHandle); + +#if BOARD_DEVICE_RHPORT_NUM == 0 + // Despite being call USB2_OTG + // OTG_FS is marked as RHPort0 by TinyUSB to be consistent across stm32 port + // PA9 VUSB, PA10 ID, PA11 DM, PA12 DP + + __HAL_RCC_GPIOA_CLK_ENABLE(); + + /* Configure DM DP Pins */ + GPIO_InitStruct.Pin = GPIO_PIN_11 | GPIO_PIN_12; + GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_HIGH; + GPIO_InitStruct.Mode = GPIO_MODE_AF_PP; + GPIO_InitStruct.Pull = GPIO_NOPULL; + GPIO_InitStruct.Alternate = GPIO_AF10_OTG1_FS; + HAL_GPIO_Init(GPIOA, &GPIO_InitStruct); + + /* Configure VBUS Pin */ + GPIO_InitStruct.Pin = GPIO_PIN_9; + GPIO_InitStruct.Mode = GPIO_MODE_INPUT; + GPIO_InitStruct.Pull = GPIO_NOPULL; + HAL_GPIO_Init(GPIOA, &GPIO_InitStruct); + + /* This for ID line debug */ + GPIO_InitStruct.Pin = GPIO_PIN_10; + GPIO_InitStruct.Mode = GPIO_MODE_AF_OD; + GPIO_InitStruct.Pull = GPIO_PULLUP; + GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_HIGH; + GPIO_InitStruct.Alternate = GPIO_AF10_OTG1_FS; + HAL_GPIO_Init(GPIOA, &GPIO_InitStruct); + + // https://community.st.com/s/question/0D50X00009XkYZLSA3/stm32h7-nucleo-usb-fs-cdc + // TODO: Board init actually works fine without this line. +// HAL_PWREx_EnableUSBVoltageDetector(); + __HAL_RCC_USB2_OTG_FS_CLK_ENABLE(); + + // Enable VBUS sense (B device) via pin PA9 + USB_OTG_FS->GCCFG |= USB_OTG_GCCFG_VBDEN; + +#elif BOARD_DEVICE_RHPORT_NUM == 1 + + // Despite being call USB2_OTG + // OTG_HS is marked as RHPort1 by TinyUSB to be consistent across stm32 port + __GPIOA_CLK_ENABLE(); + __GPIOB_CLK_ENABLE(); + __GPIOC_CLK_ENABLE(); + __GPIOH_CLK_ENABLE(); + __GPIOI_CLK_ENABLE(); + + /* CLK */ + GPIO_InitStruct.Pin = GPIO_PIN_5; + GPIO_InitStruct.Mode = GPIO_MODE_AF_PP; + GPIO_InitStruct.Pull = GPIO_NOPULL; + GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_VERY_HIGH; + GPIO_InitStruct.Alternate = GPIO_AF10_OTG2_HS; + HAL_GPIO_Init(GPIOA, &GPIO_InitStruct); + + /* D0 */ + GPIO_InitStruct.Pin = GPIO_PIN_3; + GPIO_InitStruct.Mode = GPIO_MODE_AF_PP; + GPIO_InitStruct.Pull = GPIO_NOPULL; + GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_VERY_HIGH; + GPIO_InitStruct.Alternate = GPIO_AF10_OTG2_HS; + HAL_GPIO_Init(GPIOA, &GPIO_InitStruct); + + /* D1 D2 D3 D4 D5 D6 D7 */ + GPIO_InitStruct.Pin = GPIO_PIN_0 | GPIO_PIN_1 | GPIO_PIN_5 | GPIO_PIN_10 | GPIO_PIN_11 | GPIO_PIN_12 | GPIO_PIN_13; + GPIO_InitStruct.Mode = GPIO_MODE_AF_PP; + GPIO_InitStruct.Pull = GPIO_NOPULL; + GPIO_InitStruct.Alternate = GPIO_AF10_OTG2_HS; + HAL_GPIO_Init(GPIOB, &GPIO_InitStruct); + + /* STP */ + GPIO_InitStruct.Pin = GPIO_PIN_0; + GPIO_InitStruct.Mode = GPIO_MODE_AF_PP; + GPIO_InitStruct.Pull = GPIO_NOPULL; + GPIO_InitStruct.Alternate = GPIO_AF10_OTG2_HS; + HAL_GPIO_Init(GPIOC, &GPIO_InitStruct); + + /* NXT */ + GPIO_InitStruct.Pin = GPIO_PIN_4; + GPIO_InitStruct.Mode = GPIO_MODE_AF_PP; + GPIO_InitStruct.Pull = GPIO_NOPULL; + GPIO_InitStruct.Alternate = GPIO_AF10_OTG2_HS; + HAL_GPIO_Init(GPIOH, &GPIO_InitStruct); + + /* DIR */ + GPIO_InitStruct.Pin = GPIO_PIN_11; + GPIO_InitStruct.Mode = GPIO_MODE_AF_PP; + GPIO_InitStruct.Pull = GPIO_NOPULL; + GPIO_InitStruct.Alternate = GPIO_AF10_OTG2_HS; + HAL_GPIO_Init(GPIOI, &GPIO_InitStruct); + + // Enable ULPI clock + __HAL_RCC_USB1_OTG_HS_ULPI_CLK_ENABLE(); + + /* Enable USB HS Clocks */ + __HAL_RCC_USB1_OTG_HS_CLK_ENABLE(); + + // No VBUS sense + USB_OTG_HS->GCCFG &= ~USB_OTG_GCCFG_VBDEN; + + // B-peripheral session valid override enable + USB_OTG_HS->GOTGCTL |= USB_OTG_GOTGCTL_BVALOEN; + USB_OTG_HS->GOTGCTL |= USB_OTG_GOTGCTL_BVALOVAL; + + // Force device mode + USB_OTG_HS->GUSBCFG &= ~USB_OTG_GUSBCFG_FHMOD; + USB_OTG_HS->GUSBCFG |= USB_OTG_GUSBCFG_FDMOD; + + HAL_PWREx_EnableUSBVoltageDetector(); +#endif // rhport = 1 + +} + +//--------------------------------------------------------------------+ +// Board porting API +//--------------------------------------------------------------------+ + +void board_led_write(bool state) +{ + HAL_GPIO_WritePin(LED_PORT, LED_PIN, state); +} + +uint32_t board_button_read(void) +{ + return (BUTTON_STATE_ACTIVE == HAL_GPIO_ReadPin(BUTTON_PORT, BUTTON_PIN)) ? 1 : 0; +} + +int board_uart_read(uint8_t* buf, int len) +{ + (void) buf; (void) len; + return 0; +} + +int board_uart_write(void const * buf, int len) +{ + HAL_UART_Transmit(&UartHandle, (uint8_t*) buf, len, 0xffff); + return len; +} + + +#if CFG_TUSB_OS == OPT_OS_NONE +volatile uint32_t system_ticks = 0; +void SysTick_Handler (void) +{ + system_ticks++; +} + +uint32_t board_millis(void) +{ + return system_ticks; +} +#endif + +void HardFault_Handler (void) +{ + asm("bkpt"); +} + +// Required by __libc_init_array in startup code if we are compiling using +// -nostdlib/-nostartfiles. +void _init(void) +{ + +} diff --git a/hw/bsp/stm32h745disco/stm32h7xx_hal_conf.h b/hw/bsp/stm32h745disco/stm32h7xx_hal_conf.h new file mode 100644 index 000000000..b9fa348ec --- /dev/null +++ b/hw/bsp/stm32h745disco/stm32h7xx_hal_conf.h @@ -0,0 +1,482 @@ +/** + ****************************************************************************** + * @file stm32h7xx_hal_conf_template.h + * @brief HAL configuration template file. + * This file should be copied to the application folder and renamed + * to stm32h7xx_hal_conf.h. + ****************************************************************************** + * @attention + * + *

© COPYRIGHT(c) 2019 STMicroelectronics

+ * + * Redistribution and use in source and binary forms, with or without modification, + * are permitted provided that the following conditions are met: + * 1. Redistributions of source code must retain the above copyright notice, + * this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * 3. Neither the name of STMicroelectronics nor the names of its contributors + * may be used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE + * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE + * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR + * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, + * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE + * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __STM32H7xx_HAL_CONF_H +#define __STM32H7xx_HAL_CONF_H + +#ifdef __cplusplus + extern "C" { +#endif + +/* Exported types ------------------------------------------------------------*/ +/* Exported constants --------------------------------------------------------*/ + +/* ########################## Module Selection ############################## */ +/** + * @brief This is the list of modules to be used in the HAL driver + */ +#define HAL_MODULE_ENABLED +#define HAL_ADC_MODULE_ENABLED +/* #define HAL_CEC_MODULE_ENABLED */ +/* #define HAL_COMP_MODULE_ENABLED */ +#define HAL_CORTEX_MODULE_ENABLED +/* #define HAL_CRC_MODULE_ENABLED */ +/* #define HAL_CRYP_MODULE_ENABLED */ +/* #define HAL_DAC_MODULE_ENABLED */ +/* #define HAL_DCMI_MODULE_ENABLED */ +/* #define HAL_DFSDM_MODULE_ENABLED */ +#define HAL_DMA_MODULE_ENABLED +/* #define HAL_DMA2D_MODULE_ENABLED */ +/* #define HAL_ETH_MODULE_ENABLED */ +/* #define HAL_EXTI_MODULE_ENABLED */ +/* #define HAL_FDCAN_MODULE_ENABLED */ +#define HAL_FLASH_MODULE_ENABLED +#define HAL_GPIO_MODULE_ENABLED +/* #define HAL_HASH_MODULE_ENABLED */ +/* #define HAL_HCD_MODULE_ENABLED */ +/* #define HAL_HRTIM_MODULE_ENABLED */ +/* #define HAL_HSEM_MODULE_ENABLED */ +/* #define HAL_I2C_MODULE_ENABLED */ +/* #define HAL_I2S_MODULE_ENABLED */ +/* #define HAL_IRDA_MODULE_ENABLED */ +/* #define HAL_IWDG_MODULE_ENABLED */ +/* #define HAL_JPEG_MODULE_ENABLED */ +/* #define HAL_LPTIM_MODULE_ENABLED */ +/* #define HAL_LTDC_MODULE_ENABLED */ +/* #define HAL_MDIOS_MODULE_ENABLED */ +/* #define HAL_MDMA_MODULE_ENABLED */ +/* #define HAL_MMC_MODULE_ENABLED */ +/* #define HAL_NAND_MODULE_ENABLED */ +/* #define HAL_NOR_MODULE_ENABLED */ +/* #define HAL_OPAMP_MODULE_ENABLED */ +/* #define HAL_PCD_MODULE_ENABLED */ +#define HAL_PWR_MODULE_ENABLED +/* #define HAL_QSPI_MODULE_ENABLED */ +/* #define HAL_RAMECC_MODULE_ENABLED */ +#define HAL_RCC_MODULE_ENABLED +/* #define HAL_RNG_MODULE_ENABLED */ +/* #define HAL_RTC_MODULE_ENABLED */ +/* #define HAL_SAI_MODULE_ENABLED */ +/* #define HAL_SD_MODULE_ENABLED */ +/* #define HAL_SDRAM_MODULE_ENABLED */ +/* #define HAL_SMARTCARD_MODULE_ENABLED */ +/* #define HAL_SMBUS_MODULE_ENABLED */ +/* #define HAL_SPDIFRX_MODULE_ENABLED */ +#define HAL_SPI_MODULE_ENABLED +/* #define HAL_SRAM_MODULE_ENABLED */ +/* #define HAL_SWPMI_MODULE_ENABLED */ +/* #define HAL_TIM_MODULE_ENABLED */ +#define HAL_UART_MODULE_ENABLED +/* #define HAL_USART_MODULE_ENABLED */ +/* #define HAL_WWDG_MODULE_ENABLED */ + +/* ########################## Oscillator Values adaptation ####################*/ +/** + * @brief Adjust the value of External High Speed oscillator (HSE) used in your application. + * This value is used by the RCC HAL module to compute the system frequency + * (when HSE is used as system clock source, directly or through the PLL). + */ +#if !defined (HSE_VALUE) +#define HSE_VALUE ((uint32_t)25000000) /*!< Value of the External oscillator in Hz */ +#endif /* HSE_VALUE */ + +#if !defined (HSE_STARTUP_TIMEOUT) + #define HSE_STARTUP_TIMEOUT ((uint32_t)5000) /*!< Time out for HSE start up, in ms */ +#endif /* HSE_STARTUP_TIMEOUT */ + +/** + * @brief Internal oscillator (CSI) default value. + * This value is the default CSI value after Reset. + */ +#if !defined (CSI_VALUE) + #define CSI_VALUE ((uint32_t)4000000) /*!< Value of the Internal oscillator in Hz*/ +#endif /* CSI_VALUE */ + +/** + * @brief Internal High Speed oscillator (HSI) value. + * This value is used by the RCC HAL module to compute the system frequency + * (when HSI is used as system clock source, directly or through the PLL). + */ +#if !defined (HSI_VALUE) + #define HSI_VALUE ((uint32_t)64000000) /*!< Value of the Internal oscillator in Hz*/ +#endif /* HSI_VALUE */ + +/** + * @brief External Low Speed oscillator (LSE) value. + * This value is used by the UART, RTC HAL module to compute the system frequency + */ +#if !defined (LSE_VALUE) + #define LSE_VALUE ((uint32_t)32768) /*!< Value of the External oscillator in Hz*/ +#endif /* LSE_VALUE */ + + +#if !defined (LSE_STARTUP_TIMEOUT) + #define LSE_STARTUP_TIMEOUT ((uint32_t)5000) /*!< Time out for LSE start up, in ms */ +#endif /* LSE_STARTUP_TIMEOUT */ + +#if !defined (LSI_VALUE) + #define LSI_VALUE ((uint32_t)32000) /*!< 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 clock source for I2S peripheral + * This value is used by the I2S HAL module to compute the I2S clock source + * frequency, this source is inserted directly through I2S_CKIN pad. + */ +#if !defined (EXTERNAL_CLOCK_VALUE) + #define EXTERNAL_CLOCK_VALUE 12288000U /*!< Value of the External clock in Hz*/ +#endif /* EXTERNAL_CLOCK_VALUE */ + +/* Tip: To avoid modifying this file each time you need to use different HSE, + === you can define the HSE value in your toolchain compiler preprocessor. */ + +/* ########################### System Configuration ######################### */ +/** + * @brief This is the HAL system configuration section + */ +#define VDD_VALUE ((uint32_t)3300) /*!< Value of VDD in mv */ +#define TICK_INT_PRIORITY ((uint32_t)0x0F) /*!< tick interrupt priority */ +#define USE_RTOS 0 +#define USE_SD_TRANSCEIVER 1U /*!< use uSD Transceiver */ +#define USE_SPI_CRC 1U /*!< use CRC in SPI */ + +#define USE_HAL_ADC_REGISTER_CALLBACKS 0U /* ADC register callback disabled */ +#define USE_HAL_CEC_REGISTER_CALLBACKS 0U /* CEC register callback disabled */ +#define USE_HAL_COMP_REGISTER_CALLBACKS 0U /* COMP register callback disabled */ +#define USE_HAL_CRYP_REGISTER_CALLBACKS 0U /* CRYP register callback disabled */ +#define USE_HAL_DAC_REGISTER_CALLBACKS 0U /* DAC register callback disabled */ +#define USE_HAL_DCMI_REGISTER_CALLBACKS 0U /* DCMI register callback disabled */ +#define USE_HAL_DFSDM_REGISTER_CALLBACKS 0U /* DFSDM register callback disabled */ +#define USE_HAL_DMA2D_REGISTER_CALLBACKS 0U /* DMA2D register callback disabled */ +#define USE_HAL_DSI_REGISTER_CALLBACKS 0U /* DSI register callback disabled */ +#define USE_HAL_ETH_REGISTER_CALLBACKS 0U /* ETH register callback disabled */ +#define USE_HAL_FDCAN_REGISTER_CALLBACKS 0U /* FDCAN register callback disabled */ +#define USE_HAL_NAND_REGISTER_CALLBACKS 0U /* NAND register callback disabled */ +#define USE_HAL_NOR_REGISTER_CALLBACKS 0U /* NOR register callback disabled */ +#define USE_HAL_SDRAM_REGISTER_CALLBACKS 0U /* SDRAM register callback disabled */ +#define USE_HAL_SRAM_REGISTER_CALLBACKS 0U /* SRAM register callback disabled */ +#define USE_HAL_HASH_REGISTER_CALLBACKS 0U /* HASH register callback disabled */ +#define USE_HAL_HCD_REGISTER_CALLBACKS 0U /* HCD register callback disabled */ +#define USE_HAL_HRTIM_REGISTER_CALLBACKS 0U /* HRTIM register callback disabled */ +#define USE_HAL_I2C_REGISTER_CALLBACKS 0U /* I2C register callback disabled */ +#define USE_HAL_I2S_REGISTER_CALLBACKS 0U /* I2S register callback disabled */ +#define USE_HAL_JPEG_REGISTER_CALLBACKS 0U /* JPEG register callback disabled */ +#define USE_HAL_LPTIM_REGISTER_CALLBACKS 0U /* LPTIM register callback disabled */ +#define USE_HAL_LTDC_REGISTER_CALLBACKS 0U /* LTDC register callback disabled */ +#define USE_HAL_MDIOS_REGISTER_CALLBACKS 0U /* MDIO register callback disabled */ +#define USE_HAL_OPAMP_REGISTER_CALLBACKS 0U /* MDIO register callback disabled */ +#define USE_HAL_PCD_REGISTER_CALLBACKS 0U /* PCD register callback disabled */ +#define USE_HAL_QSPI_REGISTER_CALLBACKS 0U /* QSPI register callback disabled */ +#define USE_HAL_RNG_REGISTER_CALLBACKS 0U /* RNG register callback disabled */ +#define USE_HAL_RTC_REGISTER_CALLBACKS 0U /* RTC register callback disabled */ +#define USE_HAL_SAI_REGISTER_CALLBACKS 0U /* SAI register callback disabled */ +#define USE_HAL_SPDIFRX_REGISTER_CALLBACKS 0U /* SPDIFRX register callback disabled */ +#define USE_HAL_SMBUS_REGISTER_CALLBACKS 0U /* SMBUS register callback disabled */ +#define USE_HAL_SPI_REGISTER_CALLBACKS 0U /* SPI register callback disabled */ +#define USE_HAL_SWPMI_REGISTER_CALLBACKS 0U /* SWPMI register callback disabled */ +#define USE_HAL_TIM_REGISTER_CALLBACKS 0U /* TIM register callback disabled */ +#define USE_HAL_UART_REGISTER_CALLBACKS 0U /* UART register callback disabled */ +#define USE_HAL_USART_REGISTER_CALLBACKS 0U /* USART register callback disabled */ +#define USE_HAL_WWDG_REGISTER_CALLBACKS 0U /* WWDG register callback disabled */ + +/* ########################### Ethernet Configuration ######################### */ +#define ETH_TX_DESC_CNT 4 /* number of Ethernet Tx DMA descriptors */ +#define ETH_RX_DESC_CNT 4 /* number of Ethernet Rx DMA descriptors */ + +#define ETH_MAC_ADDR0 ((uint8_t)0x02) +#define ETH_MAC_ADDR1 ((uint8_t)0x00) +#define ETH_MAC_ADDR2 ((uint8_t)0x00) +#define ETH_MAC_ADDR3 ((uint8_t)0x00) +#define ETH_MAC_ADDR4 ((uint8_t)0x00) +#define ETH_MAC_ADDR5 ((uint8_t)0x00) + +/* ########################## Assert Selection ############################## */ +/** + * @brief Uncomment the line below to expanse the "assert_param" macro in the + * HAL drivers code + */ +/* #define USE_FULL_ASSERT 1 */ + + +/* Includes ------------------------------------------------------------------*/ +/** + * @brief Include module's header file + */ + +#ifdef HAL_RCC_MODULE_ENABLED + #include "stm32h7xx_hal_rcc.h" +#endif /* HAL_RCC_MODULE_ENABLED */ + +#ifdef HAL_GPIO_MODULE_ENABLED + #include "stm32h7xx_hal_gpio.h" +#endif /* HAL_GPIO_MODULE_ENABLED */ + +#ifdef HAL_DMA_MODULE_ENABLED + #include "stm32h7xx_hal_dma.h" +#endif /* HAL_DMA_MODULE_ENABLED */ + +#ifdef HAL_MDMA_MODULE_ENABLED + #include "stm32h7xx_hal_mdma.h" +#endif /* HAL_MDMA_MODULE_ENABLED */ + +#ifdef HAL_HASH_MODULE_ENABLED + #include "stm32h7xx_hal_hash.h" +#endif /* HAL_HASH_MODULE_ENABLED */ + +#ifdef HAL_DCMI_MODULE_ENABLED + #include "stm32h7xx_hal_dcmi.h" +#endif /* HAL_DCMI_MODULE_ENABLED */ + +#ifdef HAL_DMA2D_MODULE_ENABLED + #include "stm32h7xx_hal_dma2d.h" +#endif /* HAL_DMA2D_MODULE_ENABLED */ + +#ifdef HAL_DSI_MODULE_ENABLED + #include "stm32h7xx_hal_dsi.h" +#endif /* HAL_DSI_MODULE_ENABLED */ + +#ifdef HAL_DFSDM_MODULE_ENABLED + #include "stm32h7xx_hal_dfsdm.h" +#endif /* HAL_DFSDM_MODULE_ENABLED */ + +#ifdef HAL_ETH_MODULE_ENABLED + #include "stm32h7xx_hal_eth.h" +#endif /* HAL_ETH_MODULE_ENABLED */ + +#ifdef HAL_EXTI_MODULE_ENABLED + #include "stm32h7xx_hal_exti.h" +#endif /* HAL_EXTI_MODULE_ENABLED */ + +#ifdef HAL_CORTEX_MODULE_ENABLED + #include "stm32h7xx_hal_cortex.h" +#endif /* HAL_CORTEX_MODULE_ENABLED */ + +#ifdef HAL_ADC_MODULE_ENABLED + #include "stm32h7xx_hal_adc.h" +#endif /* HAL_ADC_MODULE_ENABLED */ + +#ifdef HAL_FDCAN_MODULE_ENABLED + #include "stm32h7xx_hal_fdcan.h" +#endif /* HAL_FDCAN_MODULE_ENABLED */ + +#ifdef HAL_CEC_MODULE_ENABLED + #include "stm32h7xx_hal_cec.h" +#endif /* HAL_CEC_MODULE_ENABLED */ + +#ifdef HAL_COMP_MODULE_ENABLED + #include "stm32h7xx_hal_comp.h" +#endif /* HAL_COMP_MODULE_ENABLED */ + +#ifdef HAL_CRC_MODULE_ENABLED + #include "stm32h7xx_hal_crc.h" +#endif /* HAL_CRC_MODULE_ENABLED */ + +#ifdef HAL_CRYP_MODULE_ENABLED + #include "stm32h7xx_hal_cryp.h" +#endif /* HAL_CRYP_MODULE_ENABLED */ + +#ifdef HAL_DAC_MODULE_ENABLED + #include "stm32h7xx_hal_dac.h" +#endif /* HAL_DAC_MODULE_ENABLED */ + +#ifdef HAL_FLASH_MODULE_ENABLED + #include "stm32h7xx_hal_flash.h" +#endif /* HAL_FLASH_MODULE_ENABLED */ + +#ifdef HAL_HRTIM_MODULE_ENABLED + #include "stm32h7xx_hal_hrtim.h" +#endif /* HAL_HRTIM_MODULE_ENABLED */ + +#ifdef HAL_HSEM_MODULE_ENABLED + #include "stm32h7xx_hal_hsem.h" +#endif /* HAL_HSEM_MODULE_ENABLED */ + +#ifdef HAL_SRAM_MODULE_ENABLED + #include "stm32h7xx_hal_sram.h" +#endif /* HAL_SRAM_MODULE_ENABLED */ + +#ifdef HAL_NOR_MODULE_ENABLED + #include "stm32h7xx_hal_nor.h" +#endif /* HAL_NOR_MODULE_ENABLED */ + +#ifdef HAL_NAND_MODULE_ENABLED + #include "stm32h7xx_hal_nand.h" +#endif /* HAL_NAND_MODULE_ENABLED */ + +#ifdef HAL_I2C_MODULE_ENABLED + #include "stm32h7xx_hal_i2c.h" +#endif /* HAL_I2C_MODULE_ENABLED */ + +#ifdef HAL_I2S_MODULE_ENABLED + #include "stm32h7xx_hal_i2s.h" +#endif /* HAL_I2S_MODULE_ENABLED */ + +#ifdef HAL_IWDG_MODULE_ENABLED + #include "stm32h7xx_hal_iwdg.h" +#endif /* HAL_IWDG_MODULE_ENABLED */ + +#ifdef HAL_JPEG_MODULE_ENABLED + #include "stm32h7xx_hal_jpeg.h" +#endif /* HAL_JPEG_MODULE_ENABLED */ + +#ifdef HAL_MDIOS_MODULE_ENABLED + #include "stm32h7xx_hal_mdios.h" +#endif /* HAL_MDIOS_MODULE_ENABLED */ + +#ifdef HAL_MMC_MODULE_ENABLED + #include "stm32h7xx_hal_mmc.h" +#endif /* HAL_MMC_MODULE_ENABLED */ + +#ifdef HAL_LPTIM_MODULE_ENABLED +#include "stm32h7xx_hal_lptim.h" +#endif /* HAL_LPTIM_MODULE_ENABLED */ + +#ifdef HAL_LTDC_MODULE_ENABLED +#include "stm32h7xx_hal_ltdc.h" +#endif /* HAL_LTDC_MODULE_ENABLED */ + +#ifdef HAL_OPAMP_MODULE_ENABLED +#include "stm32h7xx_hal_opamp.h" +#endif /* HAL_OPAMP_MODULE_ENABLED */ + +#ifdef HAL_PWR_MODULE_ENABLED + #include "stm32h7xx_hal_pwr.h" +#endif /* HAL_PWR_MODULE_ENABLED */ + +#ifdef HAL_QSPI_MODULE_ENABLED + #include "stm32h7xx_hal_qspi.h" +#endif /* HAL_QSPI_MODULE_ENABLED */ + +#ifdef HAL_RAMECC_MODULE_ENABLED + #include "stm32h7xx_hal_ramecc.h" +#endif /* HAL_HCD_MODULE_ENABLED */ + +#ifdef HAL_RNG_MODULE_ENABLED + #include "stm32h7xx_hal_rng.h" +#endif /* HAL_RNG_MODULE_ENABLED */ + +#ifdef HAL_RTC_MODULE_ENABLED + #include "stm32h7xx_hal_rtc.h" +#endif /* HAL_RTC_MODULE_ENABLED */ + +#ifdef HAL_SAI_MODULE_ENABLED + #include "stm32h7xx_hal_sai.h" +#endif /* HAL_SAI_MODULE_ENABLED */ + +#ifdef HAL_SD_MODULE_ENABLED + #include "stm32h7xx_hal_sd.h" +#endif /* HAL_SD_MODULE_ENABLED */ + +#ifdef HAL_SDRAM_MODULE_ENABLED + #include "stm32h7xx_hal_sdram.h" +#endif /* HAL_SDRAM_MODULE_ENABLED */ + +#ifdef HAL_SPI_MODULE_ENABLED + #include "stm32h7xx_hal_spi.h" +#endif /* HAL_SPI_MODULE_ENABLED */ + +#ifdef HAL_SPDIFRX_MODULE_ENABLED + #include "stm32h7xx_hal_spdifrx.h" +#endif /* HAL_SPDIFRX_MODULE_ENABLED */ + +#ifdef HAL_SWPMI_MODULE_ENABLED + #include "stm32h7xx_hal_swpmi.h" +#endif /* HAL_SWPMI_MODULE_ENABLED */ + +#ifdef HAL_TIM_MODULE_ENABLED + #include "stm32h7xx_hal_tim.h" +#endif /* HAL_TIM_MODULE_ENABLED */ + +#ifdef HAL_UART_MODULE_ENABLED + #include "stm32h7xx_hal_uart.h" +#endif /* HAL_UART_MODULE_ENABLED */ + +#ifdef HAL_USART_MODULE_ENABLED + #include "stm32h7xx_hal_usart.h" +#endif /* HAL_USART_MODULE_ENABLED */ + +#ifdef HAL_IRDA_MODULE_ENABLED + #include "stm32h7xx_hal_irda.h" +#endif /* HAL_IRDA_MODULE_ENABLED */ + +#ifdef HAL_SMARTCARD_MODULE_ENABLED + #include "stm32h7xx_hal_smartcard.h" +#endif /* HAL_SMARTCARD_MODULE_ENABLED */ + +#ifdef HAL_SMBUS_MODULE_ENABLED + #include "stm32h7xx_hal_smbus.h" +#endif /* HAL_SMBUS_MODULE_ENABLED */ + +#ifdef HAL_WWDG_MODULE_ENABLED + #include "stm32h7xx_hal_wwdg.h" +#endif /* HAL_WWDG_MODULE_ENABLED */ + +#ifdef HAL_PCD_MODULE_ENABLED + #include "stm32h7xx_hal_pcd.h" +#endif /* HAL_PCD_MODULE_ENABLED */ + +#ifdef HAL_HCD_MODULE_ENABLED + #include "stm32h7xx_hal_hcd.h" +#endif /* HAL_HCD_MODULE_ENABLED */ + +/* Exported macro ------------------------------------------------------------*/ +#ifdef USE_FULL_ASSERT +/** + * @brief The assert_param macro is used for function's parameters check. + * @param expr: If expr is false, it calls assert_failed function + * which reports the name of the source file and the source + * line number of the call that failed. + * If expr is true, it returns no value. + * @retval None + */ + #define assert_param(expr) ((expr) ? (void)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 /* __STM32H7xx_HAL_CONF_H */ + + +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ From 5c24d5ca72d6657b1be03ded699fdf525abb0525 Mon Sep 17 00:00:00 2001 From: Uwe Bonnes Date: Thu, 2 Jul 2020 19:40:32 +0200 Subject: [PATCH 44/48] stm32h745disco: HAL_PWREx_EnableUSBVoltageDetector() is needed for hot replug. --- hw/bsp/stm32h745disco/stm32h745disco.c | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/hw/bsp/stm32h745disco/stm32h745disco.c b/hw/bsp/stm32h745disco/stm32h745disco.c index ce4034af0..d4fcdbfc0 100644 --- a/hw/bsp/stm32h745disco/stm32h745disco.c +++ b/hw/bsp/stm32h745disco/stm32h745disco.c @@ -263,8 +263,7 @@ void board_init(void) HAL_GPIO_Init(GPIOA, &GPIO_InitStruct); // https://community.st.com/s/question/0D50X00009XkYZLSA3/stm32h7-nucleo-usb-fs-cdc - // TODO: Board init actually works fine without this line. -// HAL_PWREx_EnableUSBVoltageDetector(); + HAL_PWREx_EnableUSBVoltageDetector(); __HAL_RCC_USB2_OTG_FS_CLK_ENABLE(); // Enable VBUS sense (B device) via pin PA9 From 11c6d4cdaea007cbe804dfc7d512bd82562e41d2 Mon Sep 17 00:00:00 2001 From: Uwe Bonnes Date: Fri, 3 Jul 2020 10:59:02 +0200 Subject: [PATCH 45/48] stlinkv3mini: Only OTG_HS has connector. --- hw/bsp/stlinkv3mini/board.mk | 14 +++++--------- 1 file changed, 5 insertions(+), 9 deletions(-) diff --git a/hw/bsp/stlinkv3mini/board.mk b/hw/bsp/stlinkv3mini/board.mk index 47148ec4d..b77fb5a51 100644 --- a/hw/bsp/stlinkv3mini/board.mk +++ b/hw/bsp/stlinkv3mini/board.mk @@ -1,4 +1,5 @@ -PORT ?= 1 +# Only OTG-HS has a connector on this board + REDUCE_SPEED ?= 0 CFLAGS += \ @@ -12,18 +13,13 @@ CFLAGS += \ -DSTM32F723xx \ -DHSE_VALUE=25000000 \ -DCFG_TUSB_MCU=OPT_MCU_STM32F7 \ - -DBOARD_DEVICE_RHPORT_NUM=$(PORT) - -ifeq ($(PORT), 1) - ifeq ($(REDUCE_SPEED), 0) + -DBOARD_DEVICE_RHPORT_NUM=1 +ifeq ($(REDUCE_SPEED), 0) CFLAGS += -DBOARD_DEVICE_RHPORT_SPEED=OPT_MODE_HIGH_SPEED $(info "Using OTG_HS in HS mode") - else +else CFLAGS += -DBOARD_DEVICE_RHPORT_SPEED=OPT_MODE_FULL_SPEED $(info "Using OTG_HS in FS mode") - endif -else -$(info "Using OTG_FS") endif # mcu driver cause following warnings From 8f433e67ac8dda31f3798f900b698454476730bc Mon Sep 17 00:00:00 2001 From: Uwe Bonnes Date: Fri, 3 Jul 2020 15:47:35 +0200 Subject: [PATCH 46/48] Add stm32l4r5nucleo. USB and UARTwork. USB runs from LSE stabilized MSI48 LPUART on PORTG needs VDDIO2 enabled. --- hw/bsp/stm32l4r5nucleo/STM32L4RXxI_FLASH.ld | 167 +++++++++ hw/bsp/stm32l4r5nucleo/board.mk | 49 +++ hw/bsp/stm32l4r5nucleo/stm32l4r5nucleo.c | 287 +++++++++++++++ hw/bsp/stm32l4r5nucleo/stm32l4xx_hal_conf.h | 382 ++++++++++++++++++++ 4 files changed, 885 insertions(+) create mode 100644 hw/bsp/stm32l4r5nucleo/STM32L4RXxI_FLASH.ld create mode 100644 hw/bsp/stm32l4r5nucleo/board.mk create mode 100644 hw/bsp/stm32l4r5nucleo/stm32l4r5nucleo.c create mode 100644 hw/bsp/stm32l4r5nucleo/stm32l4xx_hal_conf.h diff --git a/hw/bsp/stm32l4r5nucleo/STM32L4RXxI_FLASH.ld b/hw/bsp/stm32l4r5nucleo/STM32L4RXxI_FLASH.ld new file mode 100644 index 000000000..f93a16041 --- /dev/null +++ b/hw/bsp/stm32l4r5nucleo/STM32L4RXxI_FLASH.ld @@ -0,0 +1,167 @@ +/* +***************************************************************************** +** + +** File : LinkerScript.ld +** +** Abstract : Linker script for STM32L4RxI Device with +** 2048KByte FLASH, 640KByte RAM +** +** Set heap size, stack size and stack location according +** to application requirements. +** +** Set memory bank area and size if external memory is used. +** +** Target : STMicroelectronics STM32 +** +** +** Distribution: The file is distributed as is, without any warranty +** of any kind. +** +** (c)Copyright Ac6. +** You may use this file as-is or modify it according to the needs of your +** project. Distribution of this file (unmodified or modified) is not +** permitted. Ac6 permit registered System Workbench for MCU users the +** rights to distribute the assembled, compiled & linked contents of this +** file as part of an application binary file, provided that it is built +** using the System Workbench for MCU toolchain. +** +***************************************************************************** +*/ + +/* Entry Point */ +ENTRY(Reset_Handler) + +/* Highest address of the user mode stack */ +_estack = 0x200a0000; /* 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 = 0x460; /* required amount of stack */ + +/* Specify the memory areas */ +MEMORY +{ +RAM (xrw) : ORIGIN = 0x20000000, LENGTH = 640K +FLASH (rx) : ORIGIN = 0x8000000, LENGTH = 2048K +} + +/* Define output sections */ +SECTIONS +{ + /* The startup code goes first into FLASH */ + .isr_vector : + { + . = ALIGN(4); + KEEP(*(.isr_vector)) /* Startup code */ + . = ALIGN(4); + } >FLASH + + /* The program code and other data goes into FLASH */ + .text : + { + . = ALIGN(4); + *(.text) /* .text sections (code) */ + *(.text*) /* .text* sections (code) */ + *(.glue_7) /* glue arm to thumb code */ + *(.glue_7t) /* glue thumb to arm code */ + *(.eh_frame) + + KEEP (*(.init)) + KEEP (*(.fini)) + + . = ALIGN(4); + _etext = .; /* define a global symbols at end of code */ + } >FLASH + + /* Constant data goes into FLASH */ + .rodata : + { + . = ALIGN(4); + *(.rodata) /* .rodata sections (constants, strings, etc.) */ + *(.rodata*) /* .rodata* sections (constants, strings, etc.) */ + . = ALIGN(4); + } >FLASH + + .ARM.extab : { *(.ARM.extab* .gnu.linkonce.armextab.*) } >FLASH + .ARM : { + __exidx_start = .; + *(.ARM.exidx*) + __exidx_end = .; + } >FLASH + + .preinit_array : + { + PROVIDE_HIDDEN (__preinit_array_start = .); + KEEP (*(.preinit_array*)) + PROVIDE_HIDDEN (__preinit_array_end = .); + } >FLASH + .init_array : + { + PROVIDE_HIDDEN (__init_array_start = .); + KEEP (*(SORT(.init_array.*))) + KEEP (*(.init_array*)) + PROVIDE_HIDDEN (__init_array_end = .); + } >FLASH + .fini_array : + { + PROVIDE_HIDDEN (__fini_array_start = .); + KEEP (*(SORT(.fini_array.*))) + KEEP (*(.fini_array*)) + PROVIDE_HIDDEN (__fini_array_end = .); + } >FLASH + + /* used by the startup to initialize data */ + _sidata = LOADADDR(.data); + + /* Initialized data sections goes into RAM, load LMA copy after code */ + .data : + { + . = ALIGN(4); + _sdata = .; /* create a global symbol at data start */ + *(.data) /* .data sections */ + *(.data*) /* .data* sections */ + + . = ALIGN(4); + _edata = .; /* define a global symbol at data end */ + } >RAM AT> FLASH + + + /* Uninitialized data section */ + . = ALIGN(4); + .bss : + { + /* This is used by the startup in order to initialize the .bss secion */ + _sbss = .; /* define a global symbol at bss start */ + __bss_start__ = _sbss; + *(.bss) + *(.bss*) + *(COMMON) + + . = ALIGN(4); + _ebss = .; /* define a global symbol at bss end */ + __bss_end__ = _ebss; + } >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/stm32l4r5nucleo/board.mk b/hw/bsp/stm32l4r5nucleo/board.mk new file mode 100644 index 000000000..8ccefb7f8 --- /dev/null +++ b/hw/bsp/stm32l4r5nucleo/board.mk @@ -0,0 +1,49 @@ +CFLAGS += \ + -flto \ + -mthumb \ + -mabi=aapcs \ + -mcpu=cortex-m4 \ + -mfloat-abi=hard \ + -mfpu=fpv4-sp-d16 \ + -nostdlib -nostartfiles \ + -DHSE_VALUE=8000000 \ + -DSTM32L4R5xx \ + -DCFG_TUSB_MCU=OPT_MCU_STM32L4 + +# suppress warning caused by vendor mcu driver +CFLAGS += -Wno-error=maybe-uninitialized -Wno-error=cast-align + +ST_HAL_DRIVER = hw/mcu/st/st_driver/STM32L4xx_HAL_Driver +ST_CMSIS = hw/mcu/st/st_driver/CMSIS/Device/ST/STM32L4xx + +# All source paths should be relative to the top level. +LD_FILE = hw/bsp/$(BOARD)/STM32L4RXxI_FLASH.ld + +SRC_C += \ + $(ST_CMSIS)/Source/Templates/system_stm32l4xx.c \ + $(ST_HAL_DRIVER)/Src/stm32l4xx_hal.c \ + $(ST_HAL_DRIVER)/Src/stm32l4xx_hal_cortex.c \ + $(ST_HAL_DRIVER)/Src/stm32l4xx_hal_rcc.c \ + $(ST_HAL_DRIVER)/Src/stm32l4xx_hal_rcc_ex.c \ + $(ST_HAL_DRIVER)/Src/stm32l4xx_hal_gpio.c \ + $(ST_HAL_DRIVER)/Src/stm32l4xx_hal_uart.c \ + $(ST_HAL_DRIVER)/Src/stm32l4xx_hal_pwr_ex.c + +SRC_S += \ + $(ST_CMSIS)/Source/Templates/gcc/startup_stm32l4r5xx.s + +INC += \ + $(TOP)/hw/mcu/st/st_driver/CMSIS/Include \ + $(TOP)/$(ST_CMSIS)/Include \ + $(TOP)/$(ST_HAL_DRIVER)/Inc \ + $(TOP)/hw/bsp/$(BOARD) + +# For TinyUSB port source +VENDOR = st +CHIP_FAMILY = synopsys + +# For freeRTOS port source +FREERTOS_PORT = ARM_CM4F + +# flash target using on-board stlink +flash: flash-stlink diff --git a/hw/bsp/stm32l4r5nucleo/stm32l4r5nucleo.c b/hw/bsp/stm32l4r5nucleo/stm32l4r5nucleo.c new file mode 100644 index 000000000..bab66b550 --- /dev/null +++ b/hw/bsp/stm32l4r5nucleo/stm32l4r5nucleo.c @@ -0,0 +1,287 @@ +/* + * The MIT License (MIT) + * + * Copyright (c) 2019 William D. Jones (thor0505@comcast.net), + * Ha Thach (tinyusb.org) + * Uwe Bonnes (bon@elektron.ikp.physik.tu-darmstadt.de) + * + * Permission is hereby granted, free of charge, to any person obtaining a copy + * of this software and associated documentation files (the "Software"), to deal + * in the Software without restriction, including without limitation the rights + * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell + * copies of the Software, and to permit persons to whom the Software is + * furnished to do so, subject to the following conditions: + * + * The above copyright notice and this permission notice shall be included in + * all copies or substantial portions of the Software. + * + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR + * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE + * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER + * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, + * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN + * THE SOFTWARE. + * + * This file is part of the TinyUSB stack. + */ + +#include "../board.h" + +#include "stm32l4xx_hal.h" + +//--------------------------------------------------------------------+ +// Forward USB interrupt events to TinyUSB IRQ Handler +//--------------------------------------------------------------------+ +void OTG_FS_IRQHandler(void) +{ + tud_int_handler(0); +} + +//--------------------------------------------------------------------+ +// MACRO TYPEDEF CONSTANT ENUM +//--------------------------------------------------------------------+ + +#define LED_PORT GPIOB +#define LED_PIN GPIO_PIN_14 +#define LED_STATE_ON 1 + +#define BUTTON_PORT GPIOC +#define BUTTON_PIN GPIO_PIN_13 +#define BUTTON_STATE_ACTIVE 1 + +#define UARTx LPUART1 +#define UART_GPIO_PORT GPIOG +#define UART_GPIO_AF GPIO_AF8_LPUART1 +#define UART_TX_PIN GPIO_PIN_7 +#define UART_RX_PIN GPIO_PIN_8 + +UART_HandleTypeDef UartHandle; + +// enable all LED, Button, Uart, USB clock +static void all_rcc_clk_enable(void) +{ + __HAL_RCC_GPIOA_CLK_ENABLE(); // USB D+, D- + __HAL_RCC_GPIOB_CLK_ENABLE(); // LED + __HAL_RCC_GPIOC_CLK_ENABLE(); // Button + __HAL_RCC_GPIOG_CLK_ENABLE(); // Uart TX, RX + __HAL_RCC_LPUART1_CLK_ENABLE(); // LPUart1 module +} + +/** + * @brief System Clock Configuration + * The system Clock is configured as follow : + * System Clock source = PLL (MSI) + * SYSCLK(Hz) = 120000000 + * HCLK(Hz) = 120000000 + * AHB Prescaler = 1 + * APB1 Prescaler = 1 + * APB2 Prescaler = 1 + * MSI Frequency(Hz) = 48000000 + * PLL_M = 12 + * PLL_N = 60 + * PLL_P = 2 + * PLL_Q = 2 + * VDD(V) = 3.3 + * Main regulator output voltage = Scale1 mode + * Flash Latency(WS) = 5 + * The USB clock configuration from PLLSAI: + * PLLSAIP = 8 FIXME + * PLLSAIN = 384 FIXME + * PLLSAIQ = 7 FIXME + * @param None + * @retval None + */ +void SystemClock_Config(void) +{ + RCC_ClkInitTypeDef RCC_ClkInitStruct; + RCC_OscInitTypeDef RCC_OscInitStruct; + RCC_PeriphCLKInitTypeDef PeriphClkInitStruct = {0}; + + /* Activate PLL with MSI , stabilizied via PLL by LSE */ + RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_LSE | RCC_OSCILLATORTYPE_MSI; + RCC_OscInitStruct.MSIState = RCC_MSI_ON; + RCC_OscInitStruct.LSEState = RCC_LSE_ON; + RCC_OscInitStruct.MSIClockRange = RCC_MSIRANGE_11; + RCC_OscInitStruct.MSICalibrationValue = RCC_MSICALIBRATION_DEFAULT; + RCC_OscInitStruct.PLL.PLLState = RCC_PLL_ON; + RCC_OscInitStruct.PLL.PLLSource = RCC_PLLSOURCE_MSI; + RCC_OscInitStruct.PLL.PLLM = 12; + RCC_OscInitStruct.PLL.PLLN = 60; + RCC_OscInitStruct.PLL.PLLP = RCC_PLLP_DIV2; + RCC_OscInitStruct.PLL.PLLQ = 2; + HAL_RCC_OscConfig(&RCC_OscInitStruct); + + /* Enable MSI Auto-calibration through LSE */ + HAL_RCCEx_EnableMSIPLLMode(); + + /* Select MSI output as USB clock source */ + PeriphClkInitStruct.PeriphClockSelection = RCC_PERIPHCLK_USB; + PeriphClkInitStruct.UsbClockSelection = RCC_USBCLKSOURCE_MSI; + HAL_RCCEx_PeriphCLKConfig(&PeriphClkInitStruct); + + /* Select MSI output as USB clock source */ + PeriphClkInitStruct.PeriphClockSelection = RCC_PERIPHCLK_LPUART1; + PeriphClkInitStruct.Lpuart1ClockSelection = RCC_LPUART1CLKSOURCE_PCLK1; + HAL_RCCEx_PeriphCLKConfig(&PeriphClkInitStruct); + + /* Select PLL as system clock source and configure the HCLK, PCLK1 and PCLK2 + clocks dividers */ + RCC_ClkInitStruct.ClockType = (RCC_CLOCKTYPE_SYSCLK | RCC_CLOCKTYPE_HCLK | RCC_CLOCKTYPE_PCLK1 | RCC_CLOCKTYPE_PCLK2); + RCC_ClkInitStruct.SYSCLKSource = RCC_SYSCLKSOURCE_PLLCLK; + // Avoid overshoot and start with HCLK 60 MHz + RCC_ClkInitStruct.AHBCLKDivider = RCC_SYSCLK_DIV2; + RCC_ClkInitStruct.APB1CLKDivider = RCC_HCLK_DIV1; + RCC_ClkInitStruct.APB2CLKDivider = RCC_HCLK_DIV2; + HAL_RCC_ClockConfig(&RCC_ClkInitStruct, FLASH_LATENCY_3); + + /* AHB prescaler divider at 1 as second step */ + RCC_ClkInitStruct.ClockType = RCC_CLOCKTYPE_HCLK; + RCC_ClkInitStruct.AHBCLKDivider = RCC_SYSCLK_DIV1; + HAL_RCC_ClockConfig(&RCC_ClkInitStruct, FLASH_LATENCY_5); +} + +void board_init(void) +{ + /* Enable Power Clock*/ + __HAL_RCC_PWR_CLK_ENABLE(); + /* Enable voltage range 1 boost mode for frequency above 80 Mhz */ + HAL_PWREx_ControlVoltageScaling(PWR_REGULATOR_VOLTAGE_SCALE1_BOOST); + + /* Set tick interrupt priority, default HAL value is intentionally invalid + and that prevents PLL initialization in HAL_RCC_OscConfig() */ + + HAL_InitTick((1UL << __NVIC_PRIO_BITS) - 1UL); + + SystemClock_Config(); + all_rcc_clk_enable(); + +#if CFG_TUSB_OS == OPT_OS_NONE + // 1ms tick timer + SysTick_Config(SystemCoreClock / 1000); +#elif CFG_TUSB_OS == OPT_OS_FREERTOS + // If freeRTOS is used, IRQ priority is limit by max syscall ( smaller is higher ) + //NVIC_SetPriority(USB0_IRQn, configLIBRARY_MAX_SYSCALL_INTERRUPT_PRIORITY ); +#endif + + /* Enable USB power on Pwrctrl CR2 register */ + HAL_PWREx_EnableVddUSB(); + + GPIO_InitTypeDef GPIO_InitStruct; + + // LED + GPIO_InitStruct.Pin = LED_PIN; + GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_PP; + GPIO_InitStruct.Pull = GPIO_PULLUP; + HAL_GPIO_Init(LED_PORT, &GPIO_InitStruct); + + // Button + GPIO_InitStruct.Pin = BUTTON_PIN; + GPIO_InitStruct.Mode = GPIO_MODE_INPUT; + GPIO_InitStruct.Pull = GPIO_NOPULL; + HAL_GPIO_Init(BUTTON_PORT, &GPIO_InitStruct); + + // IOSV bit MUST be set to access GPIO port G[2:15] */ + __HAL_RCC_PWR_CLK_ENABLE(); + HAL_PWREx_EnableVddIO2(); + + // Uart + GPIO_InitStruct.Pin = UART_TX_PIN | UART_RX_PIN; + GPIO_InitStruct.Mode = GPIO_MODE_AF_PP; + GPIO_InitStruct.Pull = GPIO_PULLUP; + GPIO_InitStruct.Alternate = UART_GPIO_AF; + HAL_GPIO_Init(UART_GPIO_PORT, &GPIO_InitStruct); + + UartHandle.Instance = UARTx; + UartHandle.Init.BaudRate = CFG_BOARD_UART_BAUDRATE; + UartHandle.Init.WordLength = UART_WORDLENGTH_8B; + UartHandle.Init.StopBits = UART_STOPBITS_1; + UartHandle.Init.Parity = UART_PARITY_NONE; + UartHandle.Init.HwFlowCtl = UART_HWCONTROL_NONE; + UartHandle.Init.Mode = UART_MODE_TX_RX; + UartHandle.Init.OverSampling = UART_OVERSAMPLING_16; + UartHandle.Init.OneBitSampling = UART_ONE_BIT_SAMPLE_DISABLE; + UartHandle.Init.ClockPrescaler = UART_PRESCALER_DIV1; + UartHandle.AdvancedInit.AdvFeatureInit = UART_ADVFEATURE_NO_INIT; + + HAL_UART_Init(&UartHandle); + + /* Configure USB FS GPIOs */ + /* Configure DM DP Pins */ + GPIO_InitStruct.Pin = (GPIO_PIN_11 | GPIO_PIN_12); + GPIO_InitStruct.Mode = GPIO_MODE_AF_PP; + GPIO_InitStruct.Pull = GPIO_NOPULL; + GPIO_InitStruct.Speed = GPIO_SPEED_HIGH; + GPIO_InitStruct.Alternate = GPIO_AF10_OTG_FS; + HAL_GPIO_Init(GPIOA, &GPIO_InitStruct); + + /* Configure VBUS Pin */ + GPIO_InitStruct.Pin = GPIO_PIN_9; + GPIO_InitStruct.Mode = GPIO_MODE_INPUT; + GPIO_InitStruct.Pull = GPIO_NOPULL; + HAL_GPIO_Init(GPIOA, &GPIO_InitStruct); + + /* Configure ID pin */ + GPIO_InitStruct.Pin = GPIO_PIN_10; + GPIO_InitStruct.Mode = GPIO_MODE_AF_OD; + GPIO_InitStruct.Pull = GPIO_PULLUP; + GPIO_InitStruct.Alternate = GPIO_AF10_OTG_FS; + HAL_GPIO_Init(GPIOA, &GPIO_InitStruct); + + /* Enable USB FS Clocks */ + __HAL_RCC_USB_OTG_FS_CLK_ENABLE(); + + // Enable VBUS sense (B device) via pin PA9 + USB_OTG_FS->GCCFG |= USB_OTG_GCCFG_VBDEN; +} + +//--------------------------------------------------------------------+ +// Board porting API +//--------------------------------------------------------------------+ + +void board_led_write(bool state) +{ + HAL_GPIO_WritePin(LED_PORT, LED_PIN, state ? LED_STATE_ON : (1-LED_STATE_ON)); +} + +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) +{ + HAL_UART_Transmit(&UartHandle, (uint8_t*) buf, len, 0xffff); + return len; +} + +#if CFG_TUSB_OS == OPT_OS_NONE +volatile uint32_t system_ticks = 0; +void SysTick_Handler (void) +{ + system_ticks++; +} + +uint32_t board_millis(void) +{ + return system_ticks; +} +#endif + +void HardFault_Handler (void) +{ + asm("bkpt"); +} + +// Required by __libc_init_array in startup code if we are compiling using +// -nostdlib/-nostartfiles. +void _init(void) +{ + +} diff --git a/hw/bsp/stm32l4r5nucleo/stm32l4xx_hal_conf.h b/hw/bsp/stm32l4r5nucleo/stm32l4xx_hal_conf.h new file mode 100644 index 000000000..66822ff59 --- /dev/null +++ b/hw/bsp/stm32l4r5nucleo/stm32l4xx_hal_conf.h @@ -0,0 +1,382 @@ +/** + ****************************************************************************** + * @file stm32l4xx_hal_conf.h + * @author MCD Application Team + * @brief HAL configuration template file. + * This file should be copied to the application folder and renamed + * to stm32l4xx_hal_conf.h. + ****************************************************************************** + * @attention + * + *

© Copyright (c) 2017 STMicroelectronics. + * All rights reserved.

+ * + * This software component is licensed by ST under BSD 3-Clause license, + * the "License"; You may not use this file except in compliance with the + * License. You may obtain a copy of the License at: + * opensource.org/licenses/BSD-3-Clause + * + ****************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __STM32L4xx_HAL_CONF_H +#define __STM32L4xx_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_CAN_MODULE_ENABLED */ +/* #define HAL_CAN_LEGACY_MODULE_ENABLED */ +/* #define HAL_COMP_MODULE_ENABLED */ +#define HAL_CORTEX_MODULE_ENABLED +/* #define HAL_CRC_MODULE_ENABLED */ +/* #define HAL_CRYP_MODULE_ENABLED */ +/* #define HAL_DAC_MODULE_ENABLED */ +/* #define HAL_DFSDM_MODULE_ENABLED */ +#define HAL_DMA_MODULE_ENABLED +/* #define HAL_FIREWALL_MODULE_ENABLED */ +#define HAL_FLASH_MODULE_ENABLED +/* #define HAL_NAND_MODULE_ENABLED */ +#define HAL_NOR_MODULE_ENABLED +#define HAL_SRAM_MODULE_ENABLED +/* #define HAL_HCD_MODULE_ENABLED */ +#define HAL_GPIO_MODULE_ENABLED +//#define HAL_I2C_MODULE_ENABLED +/* #define HAL_IRDA_MODULE_ENABLED */ +/* #define HAL_IWDG_MODULE_ENABLED */ +//#define HAL_LCD_MODULE_ENABLED +/* #define HAL_LPTIM_MODULE_ENABLED */ +/* #define HAL_OPAMP_MODULE_ENABLED */ +//#define HAL_PCD_MODULE_ENABLED +#define HAL_PWR_MODULE_ENABLED +/* #define HAL_QSPI_MODULE_ENABLED */ +#define HAL_RCC_MODULE_ENABLED +/* #define HAL_RNG_MODULE_ENABLED */ +/* #define HAL_RTC_MODULE_ENABLED */ +//#define HAL_SAI_MODULE_ENABLED +//#define HAL_SD_MODULE_ENABLED +/* #define HAL_SMARTCARD_MODULE_ENABLED */ +/* #define HAL_SMBUS_MODULE_ENABLED */ +/* #define HAL_SPI_MODULE_ENABLED */ +/* #define HAL_SWPMI_MODULE_ENABLED */ +/* #define HAL_TIM_MODULE_ENABLED */ +/* #define HAL_TSC_MODULE_ENABLED */ +#define HAL_UART_MODULE_ENABLED +/* #define HAL_USART_MODULE_ENABLED */ +/* #define HAL_WWDG_MODULE_ENABLED */ + + +/* ########################## Oscillator Values adaptation ####################*/ +/** + * @brief Adjust the value of External High Speed oscillator (HSE) used in your application. + * This value is used by the RCC HAL module to compute the system frequency + * (when HSE is used as system clock source, directly or through the PLL). + */ +#if !defined (HSE_VALUE) + #define HSE_VALUE 8000000U /*!< 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 Multiple Speed oscillator (MSI) default value. + * This value is the default MSI range value after Reset. + */ +#if !defined (MSI_VALUE) + #define MSI_VALUE 4000000U /*!< Value of the Internal oscillator in Hz*/ +#endif /* MSI_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 16000000U /*!< 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 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 */ + +/** + * @brief Internal Low Speed oscillator (LSI) value. + */ +#if !defined (LSI_VALUE) + #define LSI_VALUE 32000U /*!< 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 32768U /*!< Value of the External oscillator in Hz*/ +#endif /* LSE_VALUE */ + +#if !defined (LSE_STARTUP_TIMEOUT) + #define LSE_STARTUP_TIMEOUT 5000U /*!< Time out for LSE start up, in ms */ +#endif /* HSE_STARTUP_TIMEOUT */ + +/** + * @brief External clock source for SAI1 peripheral + * This value is used by the RCC HAL module to compute the SAI1 & SAI2 clock source + * frequency. + */ +#if !defined (EXTERNAL_SAI1_CLOCK_VALUE) + #define EXTERNAL_SAI1_CLOCK_VALUE 48000U /*!< Value of the SAI1 External clock source in Hz*/ +#endif /* EXTERNAL_SAI1_CLOCK_VALUE */ + +/** + * @brief External clock source for SAI2 peripheral + * This value is used by the RCC HAL module to compute the SAI1 & SAI2 clock source + * frequency. + */ +#if !defined (EXTERNAL_SAI2_CLOCK_VALUE) + #define EXTERNAL_SAI2_CLOCK_VALUE 48000U /*!< Value of the SAI2 External clock source in Hz*/ +#endif /* EXTERNAL_SAI2_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 3300U /*!< Value of VDD in mv */ +#define TICK_INT_PRIORITY 0U /*!< tick interrupt priority */ +#define USE_RTOS 0U +#define PREFETCH_ENABLE 0U +#define INSTRUCTION_CACHE_ENABLE 1U +#define DATA_CACHE_ENABLE 1U + +#define USE_HAL_UART_REGISTER_CALLBACKS 0U /* USART register callback disabled */ + +/* ########################## Assert Selection ############################## */ +/** + * @brief Uncomment the line below to expanse the "assert_param" macro in the + * HAL drivers code + */ +/* #define USE_FULL_ASSERT 1U */ + +/* ################## SPI peripheral configuration ########################## */ + +/* CRC FEATURE: Use to activate CRC feature inside HAL SPI Driver + * Activated: CRC code is present inside driver + * Deactivated: CRC code cleaned from driver + */ + +#define USE_SPI_CRC 1U + +/* Includes ------------------------------------------------------------------*/ +/** + * @brief Include module's header file + */ + +#ifdef HAL_RCC_MODULE_ENABLED + #include "stm32l4xx_hal_rcc.h" +#endif /* HAL_RCC_MODULE_ENABLED */ + +#ifdef HAL_GPIO_MODULE_ENABLED + #include "stm32l4xx_hal_gpio.h" +#endif /* HAL_GPIO_MODULE_ENABLED */ + +#ifdef HAL_DMA_MODULE_ENABLED + #include "stm32l4xx_hal_dma.h" +#endif /* HAL_DMA_MODULE_ENABLED */ + +#ifdef HAL_DFSDM_MODULE_ENABLED + #include "stm32l4xx_hal_dfsdm.h" +#endif /* HAL_DFSDM_MODULE_ENABLED */ + +#ifdef HAL_CORTEX_MODULE_ENABLED + #include "stm32l4xx_hal_cortex.h" +#endif /* HAL_CORTEX_MODULE_ENABLED */ + +#ifdef HAL_ADC_MODULE_ENABLED + #include "stm32l4xx_hal_adc.h" +#endif /* HAL_ADC_MODULE_ENABLED */ + +#ifdef HAL_CAN_MODULE_ENABLED + #include "stm32l4xx_hal_can.h" +#endif /* HAL_CAN_MODULE_ENABLED */ + +#ifdef HAL_CAN_LEGACY_MODULE_ENABLED + #include "Legacy/stm32l4xx_hal_can_legacy.h" +#endif /* HAL_CAN_LEGACY_MODULE_ENABLED */ + +#ifdef HAL_COMP_MODULE_ENABLED + #include "stm32l4xx_hal_comp.h" +#endif /* HAL_COMP_MODULE_ENABLED */ + +#ifdef HAL_CRC_MODULE_ENABLED + #include "stm32l4xx_hal_crc.h" +#endif /* HAL_CRC_MODULE_ENABLED */ + +#ifdef HAL_CRYP_MODULE_ENABLED + #include "stm32l4xx_hal_cryp.h" +#endif /* HAL_CRYP_MODULE_ENABLED */ + +#ifdef HAL_DAC_MODULE_ENABLED + #include "stm32l4xx_hal_dac.h" +#endif /* HAL_DAC_MODULE_ENABLED */ + +#ifdef HAL_FIREWALL_MODULE_ENABLED + #include "stm32l4xx_hal_firewall.h" +#endif /* HAL_FIREWALL_MODULE_ENABLED */ + +#ifdef HAL_FLASH_MODULE_ENABLED + #include "stm32l4xx_hal_flash.h" +#endif /* HAL_FLASH_MODULE_ENABLED */ + +#ifdef HAL_SRAM_MODULE_ENABLED + #include "stm32l4xx_hal_sram.h" +#endif /* HAL_SRAM_MODULE_ENABLED */ + +#ifdef HAL_NOR_MODULE_ENABLED + #include "stm32l4xx_hal_nor.h" +#endif /* HAL_NOR_MODULE_ENABLED */ + +#ifdef HAL_NAND_MODULE_ENABLED + #include "stm32l4xx_hal_nand.h" +#endif /* HAL_NAND_MODULE_ENABLED */ + +#ifdef HAL_I2C_MODULE_ENABLED + #include "stm32l4xx_hal_i2c.h" +#endif /* HAL_I2C_MODULE_ENABLED */ + +#ifdef HAL_IWDG_MODULE_ENABLED + #include "stm32l4xx_hal_iwdg.h" +#endif /* HAL_IWDG_MODULE_ENABLED */ + +#ifdef HAL_LCD_MODULE_ENABLED + #include "stm32l4xx_hal_lcd.h" +#endif /* HAL_LCD_MODULE_ENABLED */ + +#ifdef HAL_LPTIM_MODULE_ENABLED +#include "stm32l4xx_hal_lptim.h" +#endif /* HAL_LPTIM_MODULE_ENABLED */ + +#ifdef HAL_OPAMP_MODULE_ENABLED +#include "stm32l4xx_hal_opamp.h" +#endif /* HAL_OPAMP_MODULE_ENABLED */ + +#ifdef HAL_PWR_MODULE_ENABLED + #include "stm32l4xx_hal_pwr.h" +#endif /* HAL_PWR_MODULE_ENABLED */ + +#ifdef HAL_QSPI_MODULE_ENABLED + #include "stm32l4xx_hal_qspi.h" +#endif /* HAL_QSPI_MODULE_ENABLED */ + +#ifdef HAL_RNG_MODULE_ENABLED + #include "stm32l4xx_hal_rng.h" +#endif /* HAL_RNG_MODULE_ENABLED */ + +#ifdef HAL_RTC_MODULE_ENABLED + #include "stm32l4xx_hal_rtc.h" +#endif /* HAL_RTC_MODULE_ENABLED */ + +#ifdef HAL_SAI_MODULE_ENABLED + #include "stm32l4xx_hal_sai.h" +#endif /* HAL_SAI_MODULE_ENABLED */ + +#ifdef HAL_SD_MODULE_ENABLED + #include "stm32l4xx_hal_sd.h" +#endif /* HAL_SD_MODULE_ENABLED */ + +#ifdef HAL_SMBUS_MODULE_ENABLED + #include "stm32l4xx_hal_smbus.h" +#endif /* HAL_SMBUS_MODULE_ENABLED */ + +#ifdef HAL_SPI_MODULE_ENABLED + #include "stm32l4xx_hal_spi.h" +#endif /* HAL_SPI_MODULE_ENABLED */ + +#ifdef HAL_SWPMI_MODULE_ENABLED + #include "stm32l4xx_hal_swpmi.h" +#endif /* HAL_SWPMI_MODULE_ENABLED */ + +#ifdef HAL_TIM_MODULE_ENABLED + #include "stm32l4xx_hal_tim.h" +#endif /* HAL_TIM_MODULE_ENABLED */ + +#ifdef HAL_TSC_MODULE_ENABLED + #include "stm32l4xx_hal_tsc.h" +#endif /* HAL_TSC_MODULE_ENABLED */ + +#ifdef HAL_UART_MODULE_ENABLED + #include "stm32l4xx_hal_uart.h" +#endif /* HAL_UART_MODULE_ENABLED */ + +#ifdef HAL_USART_MODULE_ENABLED + #include "stm32l4xx_hal_usart.h" +#endif /* HAL_USART_MODULE_ENABLED */ + +#ifdef HAL_IRDA_MODULE_ENABLED + #include "stm32l4xx_hal_irda.h" +#endif /* HAL_IRDA_MODULE_ENABLED */ + +#ifdef HAL_SMARTCARD_MODULE_ENABLED + #include "stm32l4xx_hal_smartcard.h" +#endif /* HAL_SMARTCARD_MODULE_ENABLED */ + +#ifdef HAL_WWDG_MODULE_ENABLED + #include "stm32l4xx_hal_wwdg.h" +#endif /* HAL_WWDG_MODULE_ENABLED */ + +#ifdef HAL_PCD_MODULE_ENABLED + #include "stm32l4xx_hal_pcd.h" +#endif /* HAL_PCD_MODULE_ENABLED */ + +#ifdef HAL_HCD_MODULE_ENABLED + #include "stm32l4xx_hal_hcd.h" +#endif /* HAL_HCD_MODULE_ENABLED */ + +/* Exported macro ------------------------------------------------------------*/ +#ifdef USE_FULL_ASSERT +/** + * @brief The assert_param macro is used for function's parameters check. + * @param expr: If expr is false, it calls assert_failed function + * which reports the name of the source file and the source + * line number of the call that failed. + * If expr is true, it returns no value. + * @retval None + */ + #define assert_param(expr) ((expr) ? (void)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 /* __STM32L4xx_HAL_CONF_H */ + + +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ From f82655a21269bcb9472a07c4cda5f47d85dbc007 Mon Sep 17 00:00:00 2001 From: hathach Date: Mon, 6 Jul 2020 18:55:31 +0700 Subject: [PATCH 47/48] correct EP Size for cdc dual and webusb example --- examples/device/cdc_dual_ports/src/tusb_config.h | 4 ++-- examples/device/cdc_dual_ports/src/usb_descriptors.c | 4 ++-- examples/device/webusb_serial/src/tusb_config.h | 8 ++++---- examples/device/webusb_serial/src/usb_descriptors.c | 4 ++-- 4 files changed, 10 insertions(+), 10 deletions(-) diff --git a/examples/device/cdc_dual_ports/src/tusb_config.h b/examples/device/cdc_dual_ports/src/tusb_config.h index e3368e72f..69001bdec 100644 --- a/examples/device/cdc_dual_ports/src/tusb_config.h +++ b/examples/device/cdc_dual_ports/src/tusb_config.h @@ -101,8 +101,8 @@ #define CFG_TUD_VENDOR 0 // CDC FIFO size of TX and RX -#define CFG_TUD_CDC_RX_BUFSIZE 64 -#define CFG_TUD_CDC_TX_BUFSIZE 64 +#define CFG_TUD_CDC_RX_BUFSIZE (TUD_OPT_HIGH_SPEED ? 512 : 64) +#define CFG_TUD_CDC_TX_BUFSIZE (TUD_OPT_HIGH_SPEED ? 512 : 64) #ifdef __cplusplus diff --git a/examples/device/cdc_dual_ports/src/usb_descriptors.c b/examples/device/cdc_dual_ports/src/usb_descriptors.c index 03800d693..a4674b7a9 100644 --- a/examples/device/cdc_dual_ports/src/usb_descriptors.c +++ b/examples/device/cdc_dual_ports/src/usb_descriptors.c @@ -97,10 +97,10 @@ uint8_t const desc_configuration[] = TUD_CONFIG_DESCRIPTOR(1, ITF_NUM_TOTAL, 0, CONFIG_TOTAL_LEN, TUSB_DESC_CONFIG_ATT_REMOTE_WAKEUP, 100), // 1st CDC: Interface number, string index, EP notification address and size, EP data address (out, in) and size. - TUD_CDC_DESCRIPTOR(ITF_NUM_CDC1, 4, 0x81, 8, EPNUM_CDC, 0x80 | EPNUM_CDC, 64), + TUD_CDC_DESCRIPTOR(ITF_NUM_CDC1, 4, 0x81, 8, EPNUM_CDC, 0x80 | EPNUM_CDC, TUD_OPT_HIGH_SPEED ? 512 : 64), // 2nd CDC: Interface number, string index, EP notification address and size, EP data address (out, in) and size. - TUD_CDC_DESCRIPTOR(ITF_NUM_CDC2, 4, 0x83, 8, EPNUM_CDC + 2, 0x80 | (EPNUM_CDC + 2), 64), + TUD_CDC_DESCRIPTOR(ITF_NUM_CDC2, 4, 0x83, 8, EPNUM_CDC + 2, 0x80 | (EPNUM_CDC + 2), TUD_OPT_HIGH_SPEED ? 512 : 64), }; // Invoked when received GET CONFIGURATION DESCRIPTOR diff --git a/examples/device/webusb_serial/src/tusb_config.h b/examples/device/webusb_serial/src/tusb_config.h index c226eefa6..a9b7a82d5 100644 --- a/examples/device/webusb_serial/src/tusb_config.h +++ b/examples/device/webusb_serial/src/tusb_config.h @@ -101,13 +101,13 @@ #define CFG_TUD_VENDOR 1 // CDC FIFO size of TX and RX -#define CFG_TUD_CDC_RX_BUFSIZE 64 -#define CFG_TUD_CDC_TX_BUFSIZE 64 +#define CFG_TUD_CDC_RX_BUFSIZE (TUD_OPT_HIGH_SPEED ? 512 : 64) +#define CFG_TUD_CDC_TX_BUFSIZE (TUD_OPT_HIGH_SPEED ? 512 : 64) // Vendor FIFO size of TX and RX // If not configured vendor endpoints will not be buffered -#define CFG_TUD_VENDOR_RX_BUFSIZE 64 -#define CFG_TUD_VENDOR_TX_BUFSIZE 64 +#define CFG_TUD_VENDOR_RX_BUFSIZE (TUD_OPT_HIGH_SPEED ? 512 : 64) +#define CFG_TUD_VENDOR_TX_BUFSIZE (TUD_OPT_HIGH_SPEED ? 512 : 64) #ifdef __cplusplus diff --git a/examples/device/webusb_serial/src/usb_descriptors.c b/examples/device/webusb_serial/src/usb_descriptors.c index 1a2df76ca..a39b34c3c 100644 --- a/examples/device/webusb_serial/src/usb_descriptors.c +++ b/examples/device/webusb_serial/src/usb_descriptors.c @@ -99,10 +99,10 @@ uint8_t const desc_configuration[] = TUD_CONFIG_DESCRIPTOR(1, ITF_NUM_TOTAL, 0, CONFIG_TOTAL_LEN, TUSB_DESC_CONFIG_ATT_REMOTE_WAKEUP, 100), // Interface number, string index, EP notification address and size, EP data address (out, in) and size. - TUD_CDC_DESCRIPTOR(ITF_NUM_CDC, 4, 0x81, 8, EPNUM_CDC, 0x80 | EPNUM_CDC, 64), + TUD_CDC_DESCRIPTOR(ITF_NUM_CDC, 4, 0x81, 8, EPNUM_CDC, 0x80 | EPNUM_CDC, TUD_OPT_HIGH_SPEED ? 512 : 64), // Interface number, string index, EP Out & IN address, EP size - TUD_VENDOR_DESCRIPTOR(ITF_NUM_VENDOR, 5, EPNUM_VENDOR, 0x80 | EPNUM_VENDOR, 64) + TUD_VENDOR_DESCRIPTOR(ITF_NUM_VENDOR, 5, EPNUM_VENDOR, 0x80 | EPNUM_VENDOR, TUD_OPT_HIGH_SPEED ? 512 : 64) }; // Invoked when received GET CONFIGURATION DESCRIPTOR From 0fd074afd85d84f162ddebbc9b8e009f9136809b Mon Sep 17 00:00:00 2001 From: hathach Date: Wed, 8 Jul 2020 16:29:48 +0700 Subject: [PATCH 48/48] change REDUCE_SPEED=0/1 to explicitly SPEED=high/full update readme, boards.md to add link to new stm boards --- docs/boards.md | 2 ++ examples/readme.md | 33 ++++++++++++++++--------- hw/bsp/stlinkv3mini/board.mk | 13 +++++----- hw/bsp/stm32f723disco/board.mk | 18 +++++++------- hw/bsp/stm32f746disco/board.mk | 18 +++++++------- hw/bsp/stm32f769disco/board.mk | 14 ++++++----- src/portable/st/synopsys/dcd_synopsys.c | 2 +- 7 files changed, 58 insertions(+), 42 deletions(-) diff --git a/docs/boards.md b/docs/boards.md index d3dcec375..271ca2844 100644 --- a/docs/boards.md +++ b/docs/boards.md @@ -87,6 +87,7 @@ This code base already had supported for a handful of following boards (sorted a - [Micro Python PyBoard v1.1](https://store.micropython.org/product/PYBv1.1) - [STLink-V3 Mini](https://www.st.com/en/development-tools/stlink-v3mini.html) - [STM32 L035c8 Discovery](https://www.st.com/en/evaluation-tools/32l0538discovery.html) +- [STM32 L4R5zi Nucleo](https://www.st.com/en/evaluation-tools/nucleo-l4r5zi.html) - [STM32 F070rb Nucleo](https://www.st.com/en/evaluation-tools/nucleo-f070rb.html) - [STM32 F072rb Discovery](https://www.st.com/en/evaluation-tools/32f072bdiscovery.html) - STM32 F103c Blue Pill @@ -104,6 +105,7 @@ This code base already had supported for a handful of following boards (sorted a - [STM32 F769i Discovery](https://www.st.com/en/evaluation-tools/32f769idiscovery.html) - [STM32 H743zi Nucleo](https://www.st.com/en/evaluation-tools/nucleo-h743zi.html) - [STM32 H743i Evaluation](https://www.st.com/en/evaluation-tools/stm32h743i-eval.html) +- [STM32 H745i Discovery](https://www.st.com/en/evaluation-tools/stm32h745i-disco.html) ### TI diff --git a/examples/readme.md b/examples/readme.md index 790427cd2..f6cd380b6 100644 --- a/examples/readme.md +++ b/examples/readme.md @@ -32,28 +32,39 @@ Then compile with `make BOARD=[your_board] all`, for example $ make BOARD=feather_nrf52840_express all ``` +**Port Selection** -To compile for debugging with debug symbols add DEBUG=1, for example - -``` -$ make BOARD=feather_nrf52840_express DEBUG=1 all -If a board has several ports, one port is choosen by default in the individual board.mk file. Choose another port with PORT=x. For example to select the HS port of a STM32F746Disco board, use: +If a board has several ports, one port is chosen by default in the individual board.mk file. Use option `PORT=x` To choose another port. For example to select the HS port of a STM32F746Disco board, use: ``` $ make BOARD=stm32f746disco PORT=1 all ``` -### Debug Log +**Port Speed** -### Log Level +A MCU can support multiple operational speed. By default, the example build system will use the fastest supported on the board. Use option `SPEED=full/high` e.g To force F723 operate at full instead of default high speed + +``` +$ make BOARD=stm32f746disco SPEED=full all +``` + +### Debug + +To compile for debugging with debug symbols add `DEBUG=1`, for example + +``` +$ make BOARD=feather_nrf52840_express DEBUG=1 all +``` + +#### Log Should you have an issue running example and/or submitting an bug report. You could enable TinyUSB built-in debug logging with optional `LOG=`. LOG=1 will only print out error message, LOG=2 print more information with on-going events. LOG=3 or higher is not used yet. ``` -$ make LOG=2 BOARD=feather_nrf52840_express all +$ make BOARD=feather_nrf52840_express LOG=2 all ``` -### Logger +#### Logger By default log message is printed via on-board UART which is slow and take lots of CPU time comparing to USB speed. If your board support on-board/external debugger, it would be more efficient to use it for logging. There are 2 protocols: @@ -67,8 +78,8 @@ By default log message is printed via on-board UART which is slow and take lots - Software viewer should be provided along with your debugger driver. ``` -$ make LOG=2 LOGGER=rtt BOARD=feather_nrf52840_express all -$ make LOG=2 LOGGER=swo BOARD=feather_nrf52840_express all +$ make BOARD=feather_nrf52840_express LOG=2 LOGGER=rtt all +$ make BOARD=feather_nrf52840_express LOG=2 LOGGER=swo all ``` ## Flash diff --git a/hw/bsp/stlinkv3mini/board.mk b/hw/bsp/stlinkv3mini/board.mk index b77fb5a51..4ca6cfd68 100644 --- a/hw/bsp/stlinkv3mini/board.mk +++ b/hw/bsp/stlinkv3mini/board.mk @@ -1,6 +1,6 @@ # Only OTG-HS has a connector on this board -REDUCE_SPEED ?= 0 +SPEED ?= high CFLAGS += \ -flto \ @@ -14,12 +14,13 @@ CFLAGS += \ -DHSE_VALUE=25000000 \ -DCFG_TUSB_MCU=OPT_MCU_STM32F7 \ -DBOARD_DEVICE_RHPORT_NUM=1 -ifeq ($(REDUCE_SPEED), 0) -CFLAGS += -DBOARD_DEVICE_RHPORT_SPEED=OPT_MODE_HIGH_SPEED -$(info "Using OTG_HS in HS mode") + +ifeq ($(SPEED), high) + CFLAGS += -DBOARD_DEVICE_RHPORT_SPEED=OPT_MODE_HIGH_SPEED + $(info "Using OTG_HS in HighSpeed mode") else -CFLAGS += -DBOARD_DEVICE_RHPORT_SPEED=OPT_MODE_FULL_SPEED -$(info "Using OTG_HS in FS mode") + CFLAGS += -DBOARD_DEVICE_RHPORT_SPEED=OPT_MODE_FULL_SPEED + $(info "Using OTG_HS in FullSpeed mode") endif # mcu driver cause following warnings diff --git a/hw/bsp/stm32f723disco/board.mk b/hw/bsp/stm32f723disco/board.mk index 47148ec4d..9ec23bfde 100644 --- a/hw/bsp/stm32f723disco/board.mk +++ b/hw/bsp/stm32f723disco/board.mk @@ -1,5 +1,5 @@ PORT ?= 1 -REDUCE_SPEED ?= 0 +SPEED ?= high CFLAGS += \ -flto \ @@ -15,15 +15,15 @@ CFLAGS += \ -DBOARD_DEVICE_RHPORT_NUM=$(PORT) ifeq ($(PORT), 1) - ifeq ($(REDUCE_SPEED), 0) -CFLAGS += -DBOARD_DEVICE_RHPORT_SPEED=OPT_MODE_HIGH_SPEED -$(info "Using OTG_HS in HS mode") - else -CFLAGS += -DBOARD_DEVICE_RHPORT_SPEED=OPT_MODE_FULL_SPEED -$(info "Using OTG_HS in FS mode") - endif + ifeq ($(SPEED), high) + CFLAGS += -DBOARD_DEVICE_RHPORT_SPEED=OPT_MODE_HIGH_SPEED + $(info "Using OTG_HS in HighSpeed mode") + else + CFLAGS += -DBOARD_DEVICE_RHPORT_SPEED=OPT_MODE_FULL_SPEED + $(info "Using OTG_HS in FullSpeed mode") + endif else -$(info "Using OTG_FS") + $(info "Using OTG_FS") endif # mcu driver cause following warnings diff --git a/hw/bsp/stm32f746disco/board.mk b/hw/bsp/stm32f746disco/board.mk index d7329a28f..48cb3f141 100644 --- a/hw/bsp/stm32f746disco/board.mk +++ b/hw/bsp/stm32f746disco/board.mk @@ -1,5 +1,5 @@ PORT ?= 0 -REDUCE_SPEED ?= 0 +SPEED ?= high CFLAGS += \ -flto \ @@ -15,15 +15,15 @@ CFLAGS += \ -DBOARD_DEVICE_RHPORT_NUM=$(PORT) ifeq ($(PORT), 1) - ifeq ($(REDUCE_SPEED), 0) -CFLAGS += -DBOARD_DEVICE_RHPORT_SPEED=OPT_MODE_HIGH_SPEED -$(info "Using OTG_HS in HS mode") - else -CFLAGS += -DBOARD_DEVICE_RHPORT_SPEED=OPT_MODE_FULL_SPEED -$(info "Using OTG_HS in FS mode") - endif + ifeq ($(SPEED), high) + CFLAGS += -DBOARD_DEVICE_RHPORT_SPEED=OPT_MODE_HIGH_SPEED + $(info "Using OTG_HS in HighSpeed mode") + else + CFLAGS += -DBOARD_DEVICE_RHPORT_SPEED=OPT_MODE_FULL_SPEED + $(info "Using OTG_HS in FullSpeed mode") + endif else -$(info "Using OTG_FS") + $(info "Using OTG_FS") endif # mcu driver cause following warnings diff --git a/hw/bsp/stm32f769disco/board.mk b/hw/bsp/stm32f769disco/board.mk index 43b677ddd..962dddc68 100644 --- a/hw/bsp/stm32f769disco/board.mk +++ b/hw/bsp/stm32f769disco/board.mk @@ -1,4 +1,6 @@ -REDUCE_SPEED ?= 0 +# Only OTG-HS has a connector on this board + +SPEED ?= high CFLAGS += \ -flto \ @@ -13,12 +15,12 @@ CFLAGS += \ -DCFG_TUSB_MCU=OPT_MCU_STM32F7 \ -DBOARD_DEVICE_RHPORT_NUM=1 \ -ifeq ($(REDUCE_SPEED), 0) -CFLAGS += -DBOARD_DEVICE_RHPORT_SPEED=OPT_MODE_HIGH_SPEED -$(info "Using OTG_HS in HS mode") +ifeq ($(SPEED), high) + CFLAGS += -DBOARD_DEVICE_RHPORT_SPEED=OPT_MODE_HIGH_SPEED + $(info "Using OTG_HS in HighSpeed mode") else -CFLAGS += -DBOARD_DEVICE_RHPORT_SPEED=OPT_MODE_FULL_SPEED -$(info "Using OTG_HS in FS mode") + CFLAGS += -DBOARD_DEVICE_RHPORT_SPEED=OPT_MODE_FULL_SPEED + $(info "Using OTG_HS in FullSpeed mode") endif # suppress warning caused by vendor mcu driver diff --git a/src/portable/st/synopsys/dcd_synopsys.c b/src/portable/st/synopsys/dcd_synopsys.c index 35b7f44f9..7eb63e52f 100644 --- a/src/portable/st/synopsys/dcd_synopsys.c +++ b/src/portable/st/synopsys/dcd_synopsys.c @@ -403,7 +403,7 @@ void dcd_init (uint8_t rhport) // Select default internal VBUS Indicator and Drive for ULPI usb_otg->GUSBCFG &= ~(USB_OTG_GUSBCFG_ULPIEVBUSD | USB_OTG_GUSBCFG_ULPIEVBUSI); - #if defined(USB_HS_PHYC) +#if defined(USB_HS_PHYC) // Highspeed with embedded UTMI PHYC // Select UTMI Interface