From 0673be772475671c34a88f4fc2c16d2055dcc682 Mon Sep 17 00:00:00 2001 From: hathach Date: Wed, 2 Oct 2019 12:01:34 +0700 Subject: [PATCH 01/32] ported stm32f1, tested with f103 blue pill --- README.md | 4 +- docs/boards.md | 1 + hw/bsp/stm32f103bluepill/board.mk | 53 +++ hw/bsp/stm32f103bluepill/stm32f103bluepill.c | 182 +++++++++ hw/bsp/stm32f103bluepill/stm32f1xx_hal_conf.h | 379 ++++++++++++++++++ src/portable/st/stm32_fsdev/dcd_stm32_fsdev.c | 17 +- .../st/stm32_fsdev/dcd_stm32_fsdev_pvt_st.h | 4 +- 7 files changed, 635 insertions(+), 5 deletions(-) create mode 100644 hw/bsp/stm32f103bluepill/board.mk create mode 100644 hw/bsp/stm32f103bluepill/stm32f103bluepill.c create mode 100644 hw/bsp/stm32f103bluepill/stm32f1xx_hal_conf.h diff --git a/README.md b/README.md index 0a9cd770c..b82a88955 100644 --- a/README.md +++ b/README.md @@ -26,9 +26,9 @@ TinyUSB is an open-source cross-platform USB Host/Device stack for embedded syst The stack supports the following MCUs - **Nordic:** nRF52840 -- **NXP:** LPC11Uxx, LPC13xx, LPC175x_6x, LPC177x_8x, LPC18xx, LPC40xx, LPC43xx, LPC51Uxx +- **NXP:** LPC Series: 11Uxx, 13xx, 175x_6x, 177x_8x, 18xx, 40xx, 43xx, 51Uxx - **MicroChip:** SAMD21, SAMD51 (device only) -- **ST:** STM32 series: L0, F0, F2, F3, F4, F7, H7 (device only) +- **ST:** STM32 series: L0, F0, F1, F2, F3, F4, F7, H7 (device only) [Here is the list of supported Boards](docs/boards.md) that can be used with provided examples. diff --git a/docs/boards.md b/docs/boards.md index b6b48a7f1..0b38cf568 100644 --- a/docs/boards.md +++ b/docs/boards.md @@ -46,6 +46,7 @@ This code base already had supported for a handful of following boards - [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) +- STM32 F103c Blue Pill - [STM32 F207zg Nucleo](https://www.st.com/en/evaluation-tools/nucleo-f207zg.html) - [STM32 F303vc Discovery](https://www.st.com/en/evaluation-tools/stm32f3discovery.html) - [STM32 F407vg Discovery](https://www.st.com/en/evaluation-tools/stm32f4discovery.html) diff --git a/hw/bsp/stm32f103bluepill/board.mk b/hw/bsp/stm32f103bluepill/board.mk new file mode 100644 index 000000000..4758edf17 --- /dev/null +++ b/hw/bsp/stm32f103bluepill/board.mk @@ -0,0 +1,53 @@ +CFLAGS += \ + -DHSE_VALUE=8000000 \ + -DSTM32F103xB \ + -mthumb \ + -mabi=aapcs \ + -mcpu=cortex-m3 \ + -mfloat-abi=soft \ + -nostdlib -nostartfiles \ + -DCFG_TUSB_MCU=OPT_MCU_STM32F1 + +# mcu driver cause following warnings +#CFLAGS += -Wno-error=unused-parameter + +ST_HAL_DRIVER = hw/mcu/st/st_driver/STM32F1xx_HAL_Driver +ST_CMSIS = hw/mcu/st/st_driver/CMSIS/Device/ST/STM32F1xx + +# All source paths should be relative to the top level. +LD_FILE = $(ST_CMSIS)/Source/Templates/gcc/linker/STM32F103XB_FLASH.ld + +SRC_C += \ + $(ST_CMSIS)/Source/Templates/system_stm32f1xx.c \ + $(ST_HAL_DRIVER)/Src/stm32f1xx_hal.c \ + $(ST_HAL_DRIVER)/Src/stm32f1xx_hal_cortex.c \ + $(ST_HAL_DRIVER)/Src/stm32f1xx_hal_rcc.c \ + $(ST_HAL_DRIVER)/Src/stm32f1xx_hal_rcc_ex.c \ + $(ST_HAL_DRIVER)/Src/stm32f1xx_hal_gpio.c + +SRC_S += \ + $(ST_CMSIS)/Source/Templates/gcc/startup_stm32f103xb.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 = stm32_fsdev + +# For freeRTOS port source +FREERTOS_PORT = ARM_CM3 + +# For flash-jlink target +JLINK_DEVICE = stm32f303vc +JLINK_IF = swd + +# Path to STM32 Cube Programmer CLI, should be added into system path +STM32Prog = STM32_Programmer_CLI + +# flash target using on-board stlink +flash: $(BUILD)/$(BOARD)-firmware.elf + $(STM32Prog) --connect port=swd --write $< --go diff --git a/hw/bsp/stm32f103bluepill/stm32f103bluepill.c b/hw/bsp/stm32f103bluepill/stm32f103bluepill.c new file mode 100644 index 000000000..aade44d35 --- /dev/null +++ b/hw/bsp/stm32f103bluepill/stm32f103bluepill.c @@ -0,0 +1,182 @@ +/* + * The MIT License (MIT) + * + * Copyright (c) 2019 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 "stm32f1xx.h" +#include "stm32f1xx_hal_conf.h" + +#define LED_PORT GPIOC +#define LED_PIN GPIO_PIN_13 +#define LED_STATE_ON 0 + +#define BUTTON_PORT GPIOA +#define BUTTON_PIN GPIO_PIN_0 +#define BUTTON_STATE_ACTIVE 1 + + +/** + * @brief System Clock Configuration + * The system Clock is configured as follow : + * System Clock source = PLL (HSE) + * SYSCLK(Hz) = 72000000 + * HCLK(Hz) = 72000000 + * AHB Prescaler = 1 + * APB1 Prescaler = 2 + * APB2 Prescaler = 1 + * HSE Frequency(Hz) = 8000000 + * HSE PREDIV1 = 1 + * PLLMUL = 9 + * Flash Latency(WS) = 2 + * @param None + * @retval None + */ +void SystemClock_Config(void) +{ + RCC_ClkInitTypeDef clkinitstruct = {0}; + RCC_OscInitTypeDef oscinitstruct = {0}; + RCC_PeriphCLKInitTypeDef rccperiphclkinit = {0}; + + /* Enable HSE Oscillator and activate PLL with HSE as source */ + oscinitstruct.OscillatorType = RCC_OSCILLATORTYPE_HSE; + oscinitstruct.HSEState = RCC_HSE_ON; + oscinitstruct.HSEPredivValue = RCC_HSE_PREDIV_DIV1; + oscinitstruct.PLL.PLLMUL = RCC_PLL_MUL9; + oscinitstruct.PLL.PLLState = RCC_PLL_ON; + oscinitstruct.PLL.PLLSource = RCC_PLLSOURCE_HSE; + HAL_RCC_OscConfig(&oscinitstruct); + + /* USB clock selection */ + rccperiphclkinit.PeriphClockSelection = RCC_PERIPHCLK_USB; + rccperiphclkinit.UsbClockSelection = RCC_USBCLKSOURCE_PLL_DIV1_5; + HAL_RCCEx_PeriphCLKConfig(&rccperiphclkinit); + + /* Select PLL as system clock source and configure the HCLK, PCLK1 and PCLK2 clocks dividers */ + clkinitstruct.ClockType = (RCC_CLOCKTYPE_SYSCLK | RCC_CLOCKTYPE_HCLK | RCC_CLOCKTYPE_PCLK1 | RCC_CLOCKTYPE_PCLK2); + clkinitstruct.SYSCLKSource = RCC_SYSCLKSOURCE_PLLCLK; + clkinitstruct.AHBCLKDivider = RCC_SYSCLK_DIV1; + clkinitstruct.APB1CLKDivider = RCC_HCLK_DIV2; + clkinitstruct.APB2CLKDivider = RCC_HCLK_DIV1; + HAL_RCC_ClockConfig(&clkinitstruct, FLASH_LATENCY_2); +} + +void board_init(void) +{ + #if CFG_TUSB_OS == OPT_OS_NONE + // 1ms tick timer + SysTick_Config(SystemCoreClock / 1000); + #endif + + SystemClock_Config(); + + // Notify runtime of frequency change. + SystemCoreClockUpdate(); + + // LED + __HAL_RCC_GPIOC_CLK_ENABLE(); + GPIO_InitTypeDef GPIO_InitStruct; + 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 + __HAL_RCC_GPIOA_CLK_ENABLE(); + GPIO_InitStruct.Pin = BUTTON_PIN; + GPIO_InitStruct.Mode = GPIO_MODE_INPUT; + GPIO_InitStruct.Pull = GPIO_PULLDOWN; + GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_HIGH; + HAL_GPIO_Init(BUTTON_PORT, &GPIO_InitStruct); + + // USB Pins + // Configure USB DM and DP pins. + __HAL_RCC_GPIOA_CLK_ENABLE(); + GPIO_InitStruct.Pin = (GPIO_PIN_11 | GPIO_PIN_12); + GPIO_InitStruct.Mode = GPIO_MODE_INPUT; + GPIO_InitStruct.Pull = GPIO_NOPULL; + GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_HIGH; + HAL_GPIO_Init(GPIOA, &GPIO_InitStruct); + + // USB Clock enable + __HAL_RCC_USB_CLK_ENABLE(); +} + +//--------------------------------------------------------------------+ +// 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); +} + +#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"); +} + +#ifdef USE_FULL_ASSERT +/** + * @brief Reports the name of the source file and the source line number + * where the assert_param error has occurred. + * @param file: pointer to the source file name + * @param line: assert_param error line source number + * @retval None + */ +void assert_failed(char *file, uint32_t line) +{ + /* USER CODE BEGIN 6 */ + /* User can add his own implementation to report the file name and line number, + tex: printf("Wrong parameters value: file %s on line %d\r\n", file, line) */ + /* USER CODE END 6 */ +} +#endif /* USE_FULL_ASSERT */ + +// Required by __libc_init_array in startup code if we are compiling using +// -nostdlib/-nostartfiles. +void _init(void) +{ + +} diff --git a/hw/bsp/stm32f103bluepill/stm32f1xx_hal_conf.h b/hw/bsp/stm32f103bluepill/stm32f1xx_hal_conf.h new file mode 100644 index 000000000..a4a3f3086 --- /dev/null +++ b/hw/bsp/stm32f103bluepill/stm32f1xx_hal_conf.h @@ -0,0 +1,379 @@ +/** + ****************************************************************************** + * @file USB_Device/HID_Standalone/Inc/stm32f1xx_hal_conf.h + * @author MCD Application Team + * @brief HAL configuration template file. + * This file should be copied to the application folder and renamed + * to stm32f1xx_hal_conf.h. + ****************************************************************************** + * @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 __STM32F1xx_HAL_CONF_H +#define __STM32F1xx_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_CORTEX_MODULE_ENABLED */ +/* #define HAL_CRC_MODULE_ENABLED */ +/* #define HAL_DAC_MODULE_ENABLED */ +#define HAL_DMA_MODULE_ENABLED +#define HAL_EXTI_MODULE_ENABLED +#define HAL_FLASH_MODULE_ENABLED +#define HAL_GPIO_MODULE_ENABLED +/* #define HAL_I2C_MODULE_ENABLED */ +/* #define HAL_I2S_MODULE_ENABLED */ +/* #define HAL_IRDA_MODULE_ENABLED */ +/* #define HAL_IWDG_MODULE_ENABLED */ +/* #define HAL_NOR_MODULE_ENABLED */ +/* #define HAL_PCCARD_MODULE_ENABLED */ +#define HAL_PCD_MODULE_ENABLED +#define HAL_PWR_MODULE_ENABLED +#define HAL_RCC_MODULE_ENABLED +/* #define HAL_RTC_MODULE_ENABLED */ +/* #define HAL_SD_MODULE_ENABLED */ +/* #define HAL_SDRAM_MODULE_ENABLED */ +/* #define HAL_SMARTCARD_MODULE_ENABLED */ +/* #define HAL_SPI_MODULE_ENABLED */ +/* #define HAL_SRAM_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) +#if defined(USE_STM3210C_EVAL) + #define HSE_VALUE 25000000U /*!< Value of the External oscillator in Hz */ +#else + #define HSE_VALUE 8000000U /*!< Value of the External oscillator in Hz */ +#endif +#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 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 8000000U /*!< Value of the Internal oscillator in Hz */ +#endif /* HSI_VALUE */ + +/** + * @brief Internal Low Speed oscillator (LSI) value. + */ +#if !defined (LSI_VALUE) + #define LSI_VALUE 40000U /*!< 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 /* LSE_STARTUP_TIMEOUT */ + +/* 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 0x00U /*!< tick interrupt priority */ +#define USE_RTOS 0U +#define PREFETCH_ENABLE 1U + +#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_DAC_REGISTER_CALLBACKS 0U /* DAC register callback disabled */ +#define USE_HAL_ETH_REGISTER_CALLBACKS 0U /* ETH 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_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_PCCARD_REGISTER_CALLBACKS 0U /* PCCARD register callback disabled */ +#define USE_HAL_PCD_REGISTER_CALLBACKS 0U /* PCD register callback disabled */ +#define USE_HAL_RTC_REGISTER_CALLBACKS 0U /* RTC 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_IRDA_REGISTER_CALLBACKS 0U /* IRDA register callback disabled */ +#define USE_HAL_SRAM_REGISTER_CALLBACKS 0U /* SRAM 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 1U */ + +/* ################## Ethernet peripheral configuration ##################### */ + +/* 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 8U /* 8 Rx buffers of size ETH_RX_BUF_SIZE */ +#define ETH_TXBUFNB 4U /* 4 Tx buffers of size ETH_TX_BUF_SIZE */ + +/* Section 2: PHY configuration section */ + +/* DP83848 PHY Address*/ +#define DP83848_PHY_ADDRESS 0x01U +/* PHY Reset delay these values are based on a 1 ms Systick interrupt*/ +#define PHY_RESET_DELAY 0x000000FFU +/* PHY Configuration delay */ +#define PHY_CONFIG_DELAY 0x00000FFFU + +#define PHY_READ_TO 0x0000FFFFU +#define PHY_WRITE_TO 0x0000FFFFU + +/* Section 3: Common PHY Registers */ + +#define PHY_BCR ((uint16_t)0x0000) /*!< Transceiver Basic Control Register */ +#define PHY_BSR ((uint16_t)0x0001) /*!< 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)0x0010) /*!< PHY status register Offset */ +#define PHY_MICR ((uint16_t)0x0011) /*!< MII Interrupt Control Register */ +#define PHY_MISR ((uint16_t)0x0012) /*!< MII Interrupt Status and Misc. Control Register */ + +#define PHY_LINK_STATUS ((uint16_t)0x0001) /*!< PHY Link mask */ +#define PHY_SPEED_STATUS ((uint16_t)0x0002) /*!< PHY Speed mask */ +#define PHY_DUPLEX_STATUS ((uint16_t)0x0004) /*!< PHY Duplex mask */ + +#define PHY_MICR_INT_EN ((uint16_t)0x0002) /*!< PHY Enable interrupts */ +#define PHY_MICR_INT_OE ((uint16_t)0x0001) /*!< PHY Enable output interrupt events */ + +#define PHY_MISR_LINK_INT_EN ((uint16_t)0x0020) /*!< Enable Interrupt on change of link status */ +#define PHY_LINK_INTERRUPT ((uint16_t)0x2000) /*!< PHY link status interrupt mask */ + +/* ################## 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 "stm32f1xx_hal_rcc.h" +#endif /* HAL_RCC_MODULE_ENABLED */ + +#ifdef HAL_GPIO_MODULE_ENABLED + #include "stm32f1xx_hal_gpio.h" +#endif /* HAL_GPIO_MODULE_ENABLED */ + +#ifdef HAL_EXTI_MODULE_ENABLED + #include "stm32f1xx_hal_exti.h" +#endif /* HAL_EXTI_MODULE_ENABLED */ + +#ifdef HAL_DMA_MODULE_ENABLED + #include "stm32f1xx_hal_dma.h" +#endif /* HAL_DMA_MODULE_ENABLED */ + +#ifdef HAL_CAN_MODULE_ENABLED + #include "stm32f1xx_hal_can.h" +#endif /* HAL_CAN_MODULE_ENABLED */ + +#ifdef HAL_CAN_LEGACY_MODULE_ENABLED + #include "Legacy/stm32f1xx_hal_can_legacy.h" +#endif /* HAL_CAN_LEGACY_MODULE_ENABLED */ + +#ifdef HAL_CORTEX_MODULE_ENABLED + #include "stm32f1xx_hal_cortex.h" +#endif /* HAL_CORTEX_MODULE_ENABLED */ + +#ifdef HAL_ADC_MODULE_ENABLED + #include "stm32f1xx_hal_adc.h" +#endif /* HAL_ADC_MODULE_ENABLED */ + +#ifdef HAL_CRC_MODULE_ENABLED + #include "stm32f1xx_hal_crc.h" +#endif /* HAL_CRC_MODULE_ENABLED */ + +#ifdef HAL_DAC_MODULE_ENABLED + #include "stm32f1xx_hal_dac.h" +#endif /* HAL_DAC_MODULE_ENABLED */ + +#ifdef HAL_FLASH_MODULE_ENABLED + #include "stm32f1xx_hal_flash.h" +#endif /* HAL_FLASH_MODULE_ENABLED */ + +#ifdef HAL_SRAM_MODULE_ENABLED + #include "stm32f1xx_hal_sram.h" +#endif /* HAL_SRAM_MODULE_ENABLED */ + +#ifdef HAL_NOR_MODULE_ENABLED + #include "stm32f1xx_hal_nor.h" +#endif /* HAL_NOR_MODULE_ENABLED */ + +#ifdef HAL_I2C_MODULE_ENABLED + #include "stm32f1xx_hal_i2c.h" +#endif /* HAL_I2C_MODULE_ENABLED */ + +#ifdef HAL_I2S_MODULE_ENABLED + #include "stm32f1xx_hal_i2s.h" +#endif /* HAL_I2S_MODULE_ENABLED */ + +#ifdef HAL_IWDG_MODULE_ENABLED + #include "stm32f1xx_hal_iwdg.h" +#endif /* HAL_IWDG_MODULE_ENABLED */ + +#ifdef HAL_PWR_MODULE_ENABLED + #include "stm32f1xx_hal_pwr.h" +#endif /* HAL_PWR_MODULE_ENABLED */ + +#ifdef HAL_RTC_MODULE_ENABLED + #include "stm32f1xx_hal_rtc.h" +#endif /* HAL_RTC_MODULE_ENABLED */ + +#ifdef HAL_PCCARD_MODULE_ENABLED + #include "stm32f1xx_hal_pccard.h" +#endif /* HAL_PCCARD_MODULE_ENABLED */ + +#ifdef HAL_SD_MODULE_ENABLED + #include "stm32f1xx_hal_sd.h" +#endif /* HAL_SD_MODULE_ENABLED */ + +#ifdef HAL_SDRAM_MODULE_ENABLED + #include "stm32f1xx_hal_sdram.h" +#endif /* HAL_SDRAM_MODULE_ENABLED */ + +#ifdef HAL_SPI_MODULE_ENABLED + #include "stm32f1xx_hal_spi.h" +#endif /* HAL_SPI_MODULE_ENABLED */ + +#ifdef HAL_TIM_MODULE_ENABLED + #include "stm32f1xx_hal_tim.h" +#endif /* HAL_TIM_MODULE_ENABLED */ + +#ifdef HAL_UART_MODULE_ENABLED + #include "stm32f1xx_hal_uart.h" +#endif /* HAL_UART_MODULE_ENABLED */ + +#ifdef HAL_USART_MODULE_ENABLED + #include "stm32f1xx_hal_usart.h" +#endif /* HAL_USART_MODULE_ENABLED */ + +#ifdef HAL_IRDA_MODULE_ENABLED + #include "stm32f1xx_hal_irda.h" +#endif /* HAL_IRDA_MODULE_ENABLED */ + +#ifdef HAL_SMARTCARD_MODULE_ENABLED + #include "stm32f1xx_hal_smartcard.h" +#endif /* HAL_SMARTCARD_MODULE_ENABLED */ + +#ifdef HAL_WWDG_MODULE_ENABLED + #include "stm32f1xx_hal_wwdg.h" +#endif /* HAL_WWDG_MODULE_ENABLED */ + +#ifdef HAL_PCD_MODULE_ENABLED + #include "stm32f1xx_hal_pcd.h" +#endif /* HAL_PCD_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 /* __STM32F1xx_HAL_CONF_H */ + + +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/src/portable/st/stm32_fsdev/dcd_stm32_fsdev.c b/src/portable/st/stm32_fsdev/dcd_stm32_fsdev.c index 9debef2ae..a705694b6 100644 --- a/src/portable/st/stm32_fsdev/dcd_stm32_fsdev.c +++ b/src/portable/st/stm32_fsdev/dcd_stm32_fsdev.c @@ -259,6 +259,12 @@ void dcd_int_enable (uint8_t rhport) NVIC_EnableIRQ(USB_HP_CAN_TX_IRQn); NVIC_EnableIRQ(USB_LP_CAN_RX0_IRQn); NVIC_EnableIRQ(USBWakeUp_IRQn); +#elif CFG_TUSB_MCU == OPT_MCU_STM32F1 + NVIC_EnableIRQ(USB_HP_CAN1_TX_IRQn); + NVIC_EnableIRQ(USB_LP_CAN1_RX0_IRQn); + NVIC_EnableIRQ(USBWakeUp_IRQn); +#else + #error Unknown arch in USB driver #endif } @@ -273,9 +279,14 @@ void dcd_int_disable(uint8_t rhport) NVIC_DisableIRQ(USB_HP_CAN_TX_IRQn); NVIC_DisableIRQ(USB_LP_CAN_RX0_IRQn); NVIC_DisableIRQ(USBWakeUp_IRQn); +#elif CFG_TUSB_MCU == OPT_MCU_STM32F1 + NVIC_DisableIRQ(USB_HP_CAN1_TX_IRQn); + NVIC_DisableIRQ(USB_LP_CAN1_RX0_IRQn); + NVIC_DisableIRQ(USBWakeUp_IRQn); #else #error Unknown arch in USB driver #endif + // I'm not convinced that memory synchronization is completely necessary, but // it isn't a bad idea. __DSB(); @@ -821,7 +832,7 @@ void USB_IRQHandler(void) dcd_fs_irqHandler(); } -#elif (CFG_TUSB_MCU) == (OPT_MCU_STM32F1) +#elif CFG_TUSB_MCU == OPT_MCU_STM32F1 void USB_HP_IRQHandler(void) { dcd_fs_irqHandler(); @@ -853,14 +864,16 @@ void USB_LP_CAN_RX0_IRQHandler(void) { dcd_fs_irqHandler(); } + // USB wakeup interrupt (Channel 42): Triggered by the wakeup event from the USB // Suspend mode. void USBWakeUp_IRQHandler(void) { dcd_fs_irqHandler(); } + #else -#error Which IRQ handler do you need? + #error Which IRQ handler do you need? #endif #endif diff --git a/src/portable/st/stm32_fsdev/dcd_stm32_fsdev_pvt_st.h b/src/portable/st/stm32_fsdev/dcd_stm32_fsdev_pvt_st.h index bbaa52eae..36dca8cd8 100644 --- a/src/portable/st/stm32_fsdev/dcd_stm32_fsdev_pvt_st.h +++ b/src/portable/st/stm32_fsdev/dcd_stm32_fsdev_pvt_st.h @@ -57,7 +57,9 @@ #define PMA_LENGTH (512u) // NO internal Pull-ups // *B, and *C: 2 x 16 bits/word - #error The F102/F103 driver is expected not to work, but it might? Try it? + + // F1 names this differently from the rest + #define USB_CNTR_LPMODE USB_CNTR_LP_MODE #elif defined(STM32F302xB) || defined(STM32F302xC) || \ defined(STM32F303xB) || defined(STM32F303xC) || \ From 0a20e91cc972acf0ae0dcf6dae4c7bad4370c3d6 Mon Sep 17 00:00:00 2001 From: hathach Date: Wed, 2 Oct 2019 14:23:23 +0700 Subject: [PATCH 02/32] move linker file to blue pill bsp --- hw/bsp/stm32f103bluepill/STM32F103XB_FLASH.ld | 167 ++++++++++++++++++ hw/bsp/stm32f103bluepill/board.mk | 2 +- 2 files changed, 168 insertions(+), 1 deletion(-) create mode 100644 hw/bsp/stm32f103bluepill/STM32F103XB_FLASH.ld diff --git a/hw/bsp/stm32f103bluepill/STM32F103XB_FLASH.ld b/hw/bsp/stm32f103bluepill/STM32F103XB_FLASH.ld new file mode 100644 index 000000000..4be9df61b --- /dev/null +++ b/hw/bsp/stm32f103bluepill/STM32F103XB_FLASH.ld @@ -0,0 +1,167 @@ +/* +***************************************************************************** +** +** File : STM32F103XB_FLASH.ld +** +** Abstract : Linker script for STM32F103xB Device with +** 128KByte FLASH, 20KByte 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 = 0x20004FFF; /* 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 = 128K +RAM (xrw) : ORIGIN = 0x20000000, LENGTH = 20K +} + +/* 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/stm32f103bluepill/board.mk b/hw/bsp/stm32f103bluepill/board.mk index 4758edf17..26ad07b74 100644 --- a/hw/bsp/stm32f103bluepill/board.mk +++ b/hw/bsp/stm32f103bluepill/board.mk @@ -15,7 +15,7 @@ ST_HAL_DRIVER = hw/mcu/st/st_driver/STM32F1xx_HAL_Driver ST_CMSIS = hw/mcu/st/st_driver/CMSIS/Device/ST/STM32F1xx # All source paths should be relative to the top level. -LD_FILE = $(ST_CMSIS)/Source/Templates/gcc/linker/STM32F103XB_FLASH.ld +LD_FILE = hw/bsp/$(BOARD)/STM32F103XB_FLASH.ld SRC_C += \ $(ST_CMSIS)/Source/Templates/system_stm32f1xx.c \ From 7fd68efe7b0d1fe95834828f08014ec97f1e005a Mon Sep 17 00:00:00 2001 From: hathach Date: Thu, 3 Oct 2019 13:37:10 +0700 Subject: [PATCH 03/32] couldn't get 32L4 running with crystal less mode --- hw/bsp/stm32l476disco/stm32l476disco.c | 13 ++----------- src/device/dcd.h | 2 +- 2 files changed, 3 insertions(+), 12 deletions(-) diff --git a/hw/bsp/stm32l476disco/stm32l476disco.c b/hw/bsp/stm32l476disco/stm32l476disco.c index ab8f13226..8e01814c6 100644 --- a/hw/bsp/stm32l476disco/stm32l476disco.c +++ b/hw/bsp/stm32l476disco/stm32l476disco.c @@ -28,6 +28,7 @@ #include "stm32l4xx.h" #include "stm32l4xx_hal_conf.h" +#include "stm32l4xx_hal.h" #define LED_PORT GPIOB #define LED_PIN GPIO_PIN_2 @@ -117,8 +118,6 @@ void board_init(void) SystemClock_Config(); - HAL_RCC_MCOConfig(RCC_MCO1, RCC_MCO1SOURCE_MSI, RCC_MCODIV_1);//RCC_MCO1SOURCE_SYSCLK - /* Enable Power Clock*/ __HAL_RCC_PWR_CLK_ENABLE(); @@ -165,20 +164,12 @@ void board_init(void) GPIO_InitStruct.Pull = GPIO_NOPULL; HAL_GPIO_Init(GPIOC, &GPIO_InitStruct); - /* This for ID line */ - GPIO_InitStruct.Pin = GPIO_PIN_12; - GPIO_InitStruct.Mode = GPIO_MODE_AF_OD; - GPIO_InitStruct.Pull = GPIO_PULLUP; - GPIO_InitStruct.Speed = GPIO_SPEED_HIGH; - GPIO_InitStruct.Alternate = GPIO_AF10_OTG_FS; - HAL_GPIO_Init(GPIOC, &GPIO_InitStruct); - /* Enable USB FS Clock */ __HAL_RCC_USB_OTG_FS_CLK_ENABLE(); } //--------------------------------------------------------------------+ -// Board porting API +// board porting API //--------------------------------------------------------------------+ void board_led_write(bool state) diff --git a/src/device/dcd.h b/src/device/dcd.h index 168eb181c..bef062fb1 100644 --- a/src/device/dcd.h +++ b/src/device/dcd.h @@ -42,7 +42,7 @@ typedef enum DCD_EVENT_BUS_RESET = 1, DCD_EVENT_UNPLUGGED, DCD_EVENT_SOF, - DCD_EVENT_SUSPEND, + DCD_EVENT_SUSPEND, // TODO LPM Sleep L1 support DCD_EVENT_RESUME, DCD_EVENT_SETUP_RECEIVED, From 13d37e4a36386cadc4db29b005f33b48d68564b4 Mon Sep 17 00:00:00 2001 From: hathach Date: Thu, 3 Oct 2019 15:23:01 +0700 Subject: [PATCH 04/32] lpcxpresso1549 board test running --- hw/bsp/lpcxpresso1549/board.mk | 47 +++++ hw/bsp/lpcxpresso1549/lpc1549.ld | 246 +++++++++++++++++++++++++ hw/bsp/lpcxpresso1549/lpcxpresso1549.c | 128 +++++++++++++ src/tusb_option.h | 3 +- 4 files changed, 423 insertions(+), 1 deletion(-) create mode 100644 hw/bsp/lpcxpresso1549/board.mk create mode 100644 hw/bsp/lpcxpresso1549/lpc1549.ld create mode 100644 hw/bsp/lpcxpresso1549/lpcxpresso1549.c diff --git a/hw/bsp/lpcxpresso1549/board.mk b/hw/bsp/lpcxpresso1549/board.mk new file mode 100644 index 000000000..682674822 --- /dev/null +++ b/hw/bsp/lpcxpresso1549/board.mk @@ -0,0 +1,47 @@ +CFLAGS += \ + -mthumb \ + -mabi=aapcs \ + -mcpu=cortex-m3 \ + -nostdlib \ + -DCORE_M3 \ + -D__USE_LPCOPEN \ + -DCFG_TUSB_MCU=OPT_MCU_LPC15XX \ + -DCFG_TUSB_MEM_ALIGN='__attribute__((aligned(64)))' + +# -DCFG_TUSB_MEM_SECTION='__attribute__((section(".data.$$RAM3")))' \ +# -DCFG_EXAMPLE_MSC_READONLY \ + +# startup.c and lpc_types.h cause following errors +CFLAGS += -Wno-error=strict-prototypes -Wno-error=unused-parameter -Wno-error=unused-variable + +MCU_DIR = hw/mcu/nxp/lpc_driver/lpc15xx/lpc_chip_15xx + +# All source paths should be relative to the top level. +LD_FILE = hw/bsp/$(BOARD)/lpc1549.ld + +SRC_C += \ + $(MCU_DIR)/../gcc/cr_startup_lpc15xx.c \ + $(MCU_DIR)/src/chip_15xx.c \ + $(MCU_DIR)/src/clock_15xx.c \ + $(MCU_DIR)/src/gpio_15xx.c \ + $(MCU_DIR)/src/iocon_15xx.c \ + $(MCU_DIR)/src/swm_15xx.c \ + $(MCU_DIR)/src/sysctl_15xx.c \ + $(MCU_DIR)/src/sysinit_15xx.c + +INC += \ + $(TOP)/$(MCU_DIR)/inc + +# For TinyUSB port source +VENDOR = nxp +CHIP_FAMILY = lpc_ip3511 + +# For freeRTOS port source +FREERTOS_PORT = ARM_CM3 + +# For flash-jlink target +JLINK_DEVICE = LPC1549 +JLINK_IF = swd + +# flash using jlink +flash: flash-jlink diff --git a/hw/bsp/lpcxpresso1549/lpc1549.ld b/hw/bsp/lpcxpresso1549/lpc1549.ld new file mode 100644 index 000000000..6dd12ade1 --- /dev/null +++ b/hw/bsp/lpcxpresso1549/lpc1549.ld @@ -0,0 +1,246 @@ +/* + * GENERATED FILE - DO NOT EDIT + * Copyright (c) 2008-2013 Code Red Technologies Ltd, + * Copyright 2015, 2018-2019 NXP + * (c) NXP Semiconductors 2013-2019 + * Generated linker script file for LPC1549 + * Created from linkscript.ldt by FMCreateLinkLibraries + * Using Freemarker v2.3.23 + * MCUXpresso IDE v11.0.0 [Build 2516] [2019-06-05] on Oct 3, 2019 2:55:18 PM + */ + + +MEMORY +{ + /* Define each memory region */ + MFlash256 (rx) : ORIGIN = 0x0, LENGTH = 0x40000 /* 256K bytes (alias Flash) */ + Ram0_16 (rwx) : ORIGIN = 0x2000000, LENGTH = 0x4000 /* 16K bytes (alias RAM) */ + Ram1_16 (rwx) : ORIGIN = 0x2004000, LENGTH = 0x4000 /* 16K bytes (alias RAM2) */ + Ram2_4 (rwx) : ORIGIN = 0x2008000, LENGTH = 0x1000 /* 4K bytes (alias RAM3) */ +} + + /* Define a symbol for the top of each memory region */ + __base_MFlash256 = 0x0 ; /* MFlash256 */ + __base_Flash = 0x0 ; /* Flash */ + __top_MFlash256 = 0x0 + 0x40000 ; /* 256K bytes */ + __top_Flash = 0x0 + 0x40000 ; /* 256K bytes */ + __base_Ram0_16 = 0x2000000 ; /* Ram0_16 */ + __base_RAM = 0x2000000 ; /* RAM */ + __top_Ram0_16 = 0x2000000 + 0x4000 ; /* 16K bytes */ + __top_RAM = 0x2000000 + 0x4000 ; /* 16K bytes */ + __base_Ram1_16 = 0x2004000 ; /* Ram1_16 */ + __base_RAM2 = 0x2004000 ; /* RAM2 */ + __top_Ram1_16 = 0x2004000 + 0x4000 ; /* 16K bytes */ + __top_RAM2 = 0x2004000 + 0x4000 ; /* 16K bytes */ + __base_Ram2_4 = 0x2008000 ; /* Ram2_4 */ + __base_RAM3 = 0x2008000 ; /* RAM3 */ + __top_Ram2_4 = 0x2008000 + 0x1000 ; /* 4K bytes */ + __top_RAM3 = 0x2008000 + 0x1000 ; /* 4K bytes */ + +ENTRY(ResetISR) + +SECTIONS +{ + /* MAIN TEXT SECTION */ + .text : ALIGN(4) + { + FILL(0xff) + __vectors_start__ = ABSOLUTE(.) ; + KEEP(*(.isr_vector)) + /* Global Section Table */ + . = ALIGN(4) ; + __section_table_start = .; + __data_section_table = .; + LONG(LOADADDR(.data)); + LONG( ADDR(.data)); + LONG( SIZEOF(.data)); + LONG(LOADADDR(.data_RAM2)); + LONG( ADDR(.data_RAM2)); + LONG( SIZEOF(.data_RAM2)); + LONG(LOADADDR(.data_RAM3)); + LONG( ADDR(.data_RAM3)); + LONG( SIZEOF(.data_RAM3)); + __data_section_table_end = .; + __bss_section_table = .; + LONG( ADDR(.bss)); + LONG( SIZEOF(.bss)); + LONG( ADDR(.bss_RAM2)); + LONG( SIZEOF(.bss_RAM2)); + LONG( ADDR(.bss_RAM3)); + LONG( SIZEOF(.bss_RAM3)); + __bss_section_table_end = .; + __section_table_end = . ; + /* End of Global Section Table */ + + *(.after_vectors*) + + } > MFlash256 + + .text : ALIGN(4) + { + *(.text*) + *(.rodata .rodata.* .constdata .constdata.*) + . = ALIGN(4); + } > MFlash256 + /* + * for exception handling/unwind - some Newlib functions (in common + * with C++ and STDC++) use this. + */ + .ARM.extab : ALIGN(4) + { + *(.ARM.extab* .gnu.linkonce.armextab.*) + } > MFlash256 + + __exidx_start = .; + + .ARM.exidx : ALIGN(4) + { + *(.ARM.exidx* .gnu.linkonce.armexidx.*) + } > MFlash256 + __exidx_end = .; + + _etext = .; + + /* DATA section for Ram1_16 */ + + .data_RAM2 : ALIGN(4) + { + FILL(0xff) + PROVIDE(__start_data_RAM2 = .) ; + *(.ramfunc.$RAM2) + *(.ramfunc.$Ram1_16) + *(.data.$RAM2) + *(.data.$Ram1_16) + *(.data.$RAM2.*) + *(.data.$Ram1_16.*) + . = ALIGN(4) ; + PROVIDE(__end_data_RAM2 = .) ; + } > Ram1_16 AT>MFlash256 + /* DATA section for Ram2_4 */ + + .data_RAM3 : ALIGN(4) + { + FILL(0xff) + PROVIDE(__start_data_RAM3 = .) ; + *(.ramfunc.$RAM3) + *(.ramfunc.$Ram2_4) + *(.data.$RAM3) + *(.data.$Ram2_4) + *(.data.$RAM3.*) + *(.data.$Ram2_4.*) + . = ALIGN(4) ; + PROVIDE(__end_data_RAM3 = .) ; + } > Ram2_4 AT>MFlash256 + /* MAIN DATA SECTION */ + .uninit_RESERVED (NOLOAD) : + { + . = ALIGN(4) ; + KEEP(*(.bss.$RESERVED*)) + . = ALIGN(4) ; + _end_uninit_RESERVED = .; + } > Ram0_16 + + /* Main DATA section (Ram0_16) */ + .data : ALIGN(4) + { + FILL(0xff) + _data = . ; + *(vtable) + *(.ramfunc*) + *(.data*) + . = ALIGN(4) ; + _edata = . ; + } > Ram0_16 AT>MFlash256 + + /* BSS section for Ram1_16 */ + .bss_RAM2 : + { + . = ALIGN(4) ; + PROVIDE(__start_bss_RAM2 = .) ; + *(.bss.$RAM2) + *(.bss.$Ram1_16) + *(.bss.$RAM2.*) + *(.bss.$Ram1_16.*) + . = ALIGN (. != 0 ? 4 : 1) ; /* avoid empty segment */ + PROVIDE(__end_bss_RAM2 = .) ; + } > Ram1_16 + + /* BSS section for Ram2_4 */ + .bss_RAM3 : + { + . = ALIGN(4) ; + PROVIDE(__start_bss_RAM3 = .) ; + *(.bss.$RAM3) + *(.bss.$Ram2_4) + *(.bss.$RAM3.*) + *(.bss.$Ram2_4.*) + . = ALIGN (. != 0 ? 4 : 1) ; /* avoid empty segment */ + PROVIDE(__end_bss_RAM3 = .) ; + } > Ram2_4 + + /* MAIN BSS SECTION */ + .bss : + { + . = ALIGN(4) ; + _bss = .; + *(.bss*) + *(COMMON) + . = ALIGN(4) ; + _ebss = .; + PROVIDE(end = .); + } > Ram0_16 + + /* NOINIT section for Ram1_16 */ + .noinit_RAM2 (NOLOAD) : + { + . = ALIGN(4) ; + *(.noinit.$RAM2) + *(.noinit.$Ram1_16) + *(.noinit.$RAM2.*) + *(.noinit.$Ram1_16.*) + . = ALIGN(4) ; + } > Ram1_16 + + /* NOINIT section for Ram2_4 */ + .noinit_RAM3 (NOLOAD) : + { + . = ALIGN(4) ; + *(.noinit.$RAM3) + *(.noinit.$Ram2_4) + *(.noinit.$RAM3.*) + *(.noinit.$Ram2_4.*) + . = ALIGN(4) ; + } > Ram2_4 + + /* DEFAULT NOINIT SECTION */ + .noinit (NOLOAD): + { + . = ALIGN(4) ; + _noinit = .; + *(.noinit*) + . = ALIGN(4) ; + _end_noinit = .; + } > Ram0_16 + PROVIDE(_pvHeapStart = DEFINED(__user_heap_base) ? __user_heap_base : .); + PROVIDE(_vStackTop = DEFINED(__user_stack_top) ? __user_stack_top : __top_Ram0_16 - 0); + + /* ## Create checksum value (used in startup) ## */ + PROVIDE(__valid_user_code_checksum = 0 - + (_vStackTop + + (ResetISR + 1) + + (NMI_Handler + 1) + + (HardFault_Handler + 1) + + (( DEFINED(MemManage_Handler) ? MemManage_Handler : 0 ) + 1) /* MemManage_Handler may not be defined */ + + (( DEFINED(BusFault_Handler) ? BusFault_Handler : 0 ) + 1) /* BusFault_Handler may not be defined */ + + (( DEFINED(UsageFault_Handler) ? UsageFault_Handler : 0 ) + 1) /* UsageFault_Handler may not be defined */ + ) ); + + /* Provide basic symbols giving location and size of main text + * block, including initial values of RW data sections. Note that + * these will need extending to give a complete picture with + * complex images (e.g multiple Flash banks). + */ + _image_start = LOADADDR(.text); + _image_end = LOADADDR(.data) + SIZEOF(.data); + _image_size = _image_end - _image_start; +} \ No newline at end of file diff --git a/hw/bsp/lpcxpresso1549/lpcxpresso1549.c b/hw/bsp/lpcxpresso1549/lpcxpresso1549.c new file mode 100644 index 000000000..8e178eb76 --- /dev/null +++ b/hw/bsp/lpcxpresso1549/lpcxpresso1549.c @@ -0,0 +1,128 @@ +/* + * The MIT License (MIT) + * + * Copyright (c) 2019 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 "chip.h" +#include "../board.h" + +#define LED_PORT 0 +#define LED_PIN 25 + +// Wake Switch +#define BUTTON_PORT 0 +#define BUTTON_PIN 17 + +/* System oscillator rate and RTC oscillator rate */ +const uint32_t OscRateIn = 12000000; +const uint32_t RTCOscRateIn = 32768; + +/* Pin muxing table, only items that need changing from their default pin + state are in this table. */ +static const PINMUX_GRP_T pinmuxing[] = +{ + {1, 11, (IOCON_MODE_PULLDOWN | IOCON_DIGMODE_EN)}, /* PIO0_3 used for USB_VBUS */ +}; + +// Invoked by startup code +void SystemInit(void) +{ + Chip_Clock_EnablePeriphClock(SYSCTL_CLOCK_IOCON); + Chip_Clock_EnablePeriphClock(SYSCTL_CLOCK_SWM); + Chip_SYSCTL_PeriphReset(RESET_IOCON); + + // Pin Mux + Chip_IOCON_SetPinMuxing(LPC_IOCON, pinmuxing, sizeof(pinmuxing) / sizeof(PINMUX_GRP_T)); + + // SWM USB + Chip_SWM_MovablePortPinAssign(SWM_USB_VBUS_I, 1, 11); + + Chip_SetupXtalClocking(); +} + +void board_init(void) +{ + SystemCoreClockUpdate(); + +#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 + + Chip_GPIO_Init(LPC_GPIO); + + // LED + Chip_GPIO_SetPinDIROutput(LPC_GPIO, LED_PORT, LED_PIN); + + // Button + Chip_GPIO_SetPinDIRInput(LPC_GPIO, BUTTON_PORT, BUTTON_PIN); + + // USB: Setup PLL clock, and power + Chip_USB_Init(); +} + +//--------------------------------------------------------------------+ +// Board porting API +//--------------------------------------------------------------------+ + +#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 board_led_write(bool state) +{ + Chip_GPIO_SetPinState(LPC_GPIO, LED_PORT, LED_PIN, state); +} + +uint32_t board_button_read(void) +{ + // active low + return Chip_GPIO_GetPinState(LPC_GPIO, BUTTON_PORT, BUTTON_PIN) ? 0 : 1; +} + +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; +} diff --git a/src/tusb_option.h b/src/tusb_option.h index 76ea59758..d0cc0be6a 100644 --- a/src/tusb_option.h +++ b/src/tusb_option.h @@ -38,7 +38,8 @@ // LPC #define OPT_MCU_LPC11UXX 1 ///< NXP LPC11Uxx -#define OPT_MCU_LPC13XX 3 ///< NXP LPC13xx +#define OPT_MCU_LPC13XX 2 ///< NXP LPC13xx +#define OPT_MCU_LPC15xx 3 ///< NXP LPC15xx #define OPT_MCU_LPC175X_6X 4 ///< NXP LPC175x, LPC176x #define OPT_MCU_LPC177X_8X 5 ///< NXP LPC177x, LPC178x #define OPT_MCU_LPC18XX 6 ///< NXP LPC18xx From 281cd858b067a240478490af6d302f7881b3aaf7 Mon Sep 17 00:00:00 2001 From: hathach Date: Fri, 4 Oct 2019 13:13:51 +0700 Subject: [PATCH 05/32] adding lpc1549, but couldnt recieve setup packet, though setup received interrupt is triggered --- .../cdc_msc/ses/lpc13xx/lpc13xx.emProject | 2 +- hw/bsp/lpcxpresso11u37/lpcxpresso11u37.c | 4 -- hw/bsp/lpcxpresso1347/board.mk | 2 +- hw/bsp/lpcxpresso1549/board.mk | 6 +-- hw/bsp/lpcxpresso1549/lpcxpresso1549.c | 14 +++---- src/portable/nxp/lpc_ip3511/dcd_lpc_ip3511.c | 38 +++++++++++-------- src/tusb_option.h | 2 +- 7 files changed, 34 insertions(+), 34 deletions(-) diff --git a/examples/device/cdc_msc/ses/lpc13xx/lpc13xx.emProject b/examples/device/cdc_msc/ses/lpc13xx/lpc13xx.emProject index d07cc68ff..f25307dda 100644 --- a/examples/device/cdc_msc/ses/lpc13xx/lpc13xx.emProject +++ b/examples/device/cdc_msc/ses/lpc13xx/lpc13xx.emProject @@ -19,7 +19,7 @@ arm_target_interface_type="SWD" build_treat_warnings_as_errors="Yes" c_preprocessor_definitions="__LPC1347FBD64__;__LPC1300_FAMILY;__LPC134x_SUBFAMILY;ARM_MATH_CM3;FLASH_PLACEMENT=1;CORE_M3;CFG_TUSB_MCU=OPT_MCU_LPC13XX;CFG_TUSB_MEM_SECTION= __attribute__((section(".bss3")));CFG_TUSB_MEM_ALIGN=__attribute__ ((aligned(64)))" - c_user_include_directories="../../src;$(rootDir)/hw;$(rootDir)/hw/mcu/nxp/lpc_driver/lpc_chip_13xx/inc;$(rootDir)/src" + c_user_include_directories="../../src;$(rootDir)/hw;$(rootDir)/hw/mcu/nxp/lpc_driver/lpc13xx/lpc_chip_13xx/inc;$(rootDir)/src" debug_register_definition_file="$(ProjectDir)/LPC13Uxx_Registers.xml" debug_target_connection="J-Link" gcc_enable_all_warnings="Yes" diff --git a/hw/bsp/lpcxpresso11u37/lpcxpresso11u37.c b/hw/bsp/lpcxpresso11u37/lpcxpresso11u37.c index ce093ed29..f7fc16ec2 100644 --- a/hw/bsp/lpcxpresso11u37/lpcxpresso11u37.c +++ b/hw/bsp/lpcxpresso11u37/lpcxpresso11u37.c @@ -58,8 +58,6 @@ static const PINMUX_GRP_T pinmuxing[] = {0, 19, (IOCON_FUNC1 | IOCON_MODE_INACT | IOCON_DIGMODE_EN)}, // UART0 TX }; - -#if 1 /* Setup system clocking */ static void SystemSetupClocking(void) { @@ -114,13 +112,11 @@ static void SystemSetupClocking(void) /* Wait for PLL to lock */ while (!Chip_Clock_IsUSBPLLLocked()) {} } -#endif // Invoked by startup code void SystemInit(void) { SystemSetupClocking(); -// Chip_SystemInit(); Chip_Clock_EnablePeriphClock(SYSCTL_CLOCK_RAM1); /* Enable IOCON clock */ diff --git a/hw/bsp/lpcxpresso1347/board.mk b/hw/bsp/lpcxpresso1347/board.mk index 4e0c70392..0f9be1b56 100644 --- a/hw/bsp/lpcxpresso1347/board.mk +++ b/hw/bsp/lpcxpresso1347/board.mk @@ -7,7 +7,7 @@ CFLAGS += \ -D__USE_LPCOPEN \ -DCFG_EXAMPLE_MSC_READONLY \ -DCFG_TUSB_MCU=OPT_MCU_LPC13XX \ - -DCFG_TUSB_MEM_SECTION='__attribute__((section(".data.$$RAM3")))' \ + -DCFG_TUSB_MEM_SECTION='__attribute__((section(".data.$$RAM2")))' \ -DCFG_TUSB_MEM_ALIGN='__attribute__((aligned(64)))' # startup.c and lpc_types.h cause following errors diff --git a/hw/bsp/lpcxpresso1549/board.mk b/hw/bsp/lpcxpresso1549/board.mk index 682674822..929c63a8d 100644 --- a/hw/bsp/lpcxpresso1549/board.mk +++ b/hw/bsp/lpcxpresso1549/board.mk @@ -5,13 +5,11 @@ CFLAGS += \ -nostdlib \ -DCORE_M3 \ -D__USE_LPCOPEN \ + -DCFG_EXAMPLE_MSC_READONLY \ -DCFG_TUSB_MCU=OPT_MCU_LPC15XX \ -DCFG_TUSB_MEM_ALIGN='__attribute__((aligned(64)))' -# -DCFG_TUSB_MEM_SECTION='__attribute__((section(".data.$$RAM3")))' \ -# -DCFG_EXAMPLE_MSC_READONLY \ - -# startup.c and lpc_types.h cause following errors +# mcu driver cause following warnings CFLAGS += -Wno-error=strict-prototypes -Wno-error=unused-parameter -Wno-error=unused-variable MCU_DIR = hw/mcu/nxp/lpc_driver/lpc15xx/lpc_chip_15xx diff --git a/hw/bsp/lpcxpresso1549/lpcxpresso1549.c b/hw/bsp/lpcxpresso1549/lpcxpresso1549.c index 8e178eb76..e10e24020 100644 --- a/hw/bsp/lpcxpresso1549/lpcxpresso1549.c +++ b/hw/bsp/lpcxpresso1549/lpcxpresso1549.c @@ -40,24 +40,21 @@ const uint32_t RTCOscRateIn = 32768; /* Pin muxing table, only items that need changing from their default pin state are in this table. */ -static const PINMUX_GRP_T pinmuxing[] = +static const PINMUX_GRP_T pinmuxing[] = { - {1, 11, (IOCON_MODE_PULLDOWN | IOCON_DIGMODE_EN)}, /* PIO0_3 used for USB_VBUS */ + {1, 11, (IOCON_MODE_PULLDOWN | IOCON_DIGMODE_EN)}, /* PIO1_11-ISP_1 (VBUS) */ }; // Invoked by startup code void SystemInit(void) { Chip_Clock_EnablePeriphClock(SYSCTL_CLOCK_IOCON); - Chip_Clock_EnablePeriphClock(SYSCTL_CLOCK_SWM); - Chip_SYSCTL_PeriphReset(RESET_IOCON); + Chip_Clock_EnablePeriphClock(SYSCTL_CLOCK_SWM); + Chip_SYSCTL_PeriphReset(RESET_IOCON); - // Pin Mux + // Pin Mux Chip_IOCON_SetPinMuxing(LPC_IOCON, pinmuxing, sizeof(pinmuxing) / sizeof(PINMUX_GRP_T)); - // SWM USB - Chip_SWM_MovablePortPinAssign(SWM_USB_VBUS_I, 1, 11); - Chip_SetupXtalClocking(); } @@ -82,6 +79,7 @@ void board_init(void) Chip_GPIO_SetPinDIRInput(LPC_GPIO, BUTTON_PORT, BUTTON_PIN); // USB: Setup PLL clock, and power + Chip_SWM_MovablePortPinAssign(SWM_USB_VBUS_I, 1, 11); Chip_USB_Init(); } diff --git a/src/portable/nxp/lpc_ip3511/dcd_lpc_ip3511.c b/src/portable/nxp/lpc_ip3511/dcd_lpc_ip3511.c index 160eefb24..5b2bd83e9 100644 --- a/src/portable/nxp/lpc_ip3511/dcd_lpc_ip3511.c +++ b/src/portable/nxp/lpc_ip3511/dcd_lpc_ip3511.c @@ -28,9 +28,11 @@ /* Since 2012 starting with LPC11uxx, NXP start to use common USB Device Controller with code name LPC IP3511 * for almost their new MCUs. Currently supported and tested families are - * - LPC11Uxx - * - LPC13xx - * - LPC51Uxx + * - LPC11U68, LPC11U37 + * - LPC1347 + * - LPC51U68 + * - LPC54114 + * - LPC55s69 * * For similar controller of other families, this file may require some minimal changes to work with. * Previous MCUs such as LPC17xx, LPC40xx, LPC18xx, LPC43xx have their own driver implementation. @@ -38,20 +40,23 @@ #if TUSB_OPT_DEVICE_ENABLED && ( CFG_TUSB_MCU == OPT_MCU_LPC11UXX || \ CFG_TUSB_MCU == OPT_MCU_LPC13XX || \ + CFG_TUSB_MCU == OPT_MCU_LPC15XX || \ CFG_TUSB_MCU == OPT_MCU_LPC51UXX || \ CFG_TUSB_MCU == OPT_MCU_LPC54XXX || \ CFG_TUSB_MCU == OPT_MCU_LPC55XX) -#if CFG_TUSB_MCU == OPT_MCU_LPC11UXX || CFG_TUSB_MCU == OPT_MCU_LPC13XX - // LPC11Uxx and LPC13xx use lpcopen +#if CFG_TUSB_MCU == OPT_MCU_LPC11UXX || CFG_TUSB_MCU == OPT_MCU_LPC13XX || CFG_TUSB_MCU == OPT_MCU_LPC15XX + // LPC 11Uxx, 13xx, 15xx use lpcopen #include "chip.h" #define DCD_REGS LPC_USB #define DCD_IRQHandler USB_IRQHandler + #elif CFG_TUSB_MCU == OPT_MCU_LPC51UXX || CFG_TUSB_MCU == OPT_MCU_LPC54XXX || \ CFG_TUSB_MCU == OPT_MCU_LPC55XX // TODO 55xx has dual usb controllers #include "fsl_device_registers.h" #define DCD_REGS USB0 #define DCD_IRQHandler USB0_IRQHandler + #endif #include "device/dcd.h" @@ -61,6 +66,9 @@ //--------------------------------------------------------------------+ // Number of endpoints +// - 11 13 15 51 54 has 5x2 endpoints +// - 18/43 usb0 & 55s usb1 (HS) has 6x2 endpoints +// - 18/43 usb1 & 55s usb0 (FS) has 4x2 endpoints #define EP_COUNT 10 // only SRAM1 & USB RAM can be used for transfer. @@ -166,7 +174,7 @@ void dcd_init(uint8_t rhport) DCD_REGS->INTSTAT = DCD_REGS->INTSTAT; // clear all pending interrupt DCD_REGS->INTEN = INT_DEVICE_STATUS_MASK; DCD_REGS->DEVCMDSTAT |= CMDSTAT_DEVICE_ENABLE_MASK | CMDSTAT_DEVICE_CONNECT_MASK | - CMDSTAT_RESET_CHANGE_MASK | CMDSTAT_CONNECT_CHANGE_MASK | CMDSTAT_SUSPEND_CHANGE_MASK; + CMDSTAT_RESET_CHANGE_MASK | CMDSTAT_CONNECT_CHANGE_MASK | CMDSTAT_SUSPEND_CHANGE_MASK; NVIC_ClearPendingIRQ(USB0_IRQn); } @@ -270,7 +278,7 @@ bool dcd_edpt_xfer(uint8_t rhport, uint8_t ep_addr, uint8_t* buffer, uint16_t to prepare_ep_xfer(ep_id, get_buf_offset(buffer), total_bytes); - return true; + return true; } //--------------------------------------------------------------------+ @@ -329,7 +337,7 @@ static void process_xfer_isr(uint32_t int_status) void DCD_IRQHandler(void) { - uint32_t const dev_cmd_stat = DCD_REGS->DEVCMDSTAT; + uint32_t const cmd_stat = DCD_REGS->DEVCMDSTAT; uint32_t int_status = DCD_REGS->INTSTAT & DCD_REGS->INTEN; DCD_REGS->INTSTAT = int_status; // Acknowledge handled interrupt @@ -340,16 +348,16 @@ void DCD_IRQHandler(void) if ( int_status & INT_DEVICE_STATUS_MASK ) { DCD_REGS->DEVCMDSTAT |= CMDSTAT_RESET_CHANGE_MASK | CMDSTAT_CONNECT_CHANGE_MASK | CMDSTAT_SUSPEND_CHANGE_MASK; - if ( dev_cmd_stat & CMDSTAT_RESET_CHANGE_MASK) // bus reset + if ( cmd_stat & CMDSTAT_RESET_CHANGE_MASK) // bus reset { bus_reset(); dcd_event_bus_signal(0, DCD_EVENT_BUS_RESET, true); } - if (dev_cmd_stat & CMDSTAT_CONNECT_CHANGE_MASK) + if (cmd_stat & CMDSTAT_CONNECT_CHANGE_MASK) { // device disconnect - if (dev_cmd_stat & CMDSTAT_DEVICE_ADDR_MASK) + if (cmd_stat & CMDSTAT_DEVICE_ADDR_MASK) { // debouncing as this can be set when device is powering dcd_event_bus_signal(0, DCD_EVENT_UNPLUGGED, true); @@ -357,12 +365,12 @@ void DCD_IRQHandler(void) } // TODO support suspend & resume - if (dev_cmd_stat & CMDSTAT_SUSPEND_CHANGE_MASK) + if (cmd_stat & CMDSTAT_SUSPEND_CHANGE_MASK) { - if (dev_cmd_stat & CMDSTAT_DEVICE_SUSPEND_MASK) + if (cmd_stat & CMDSTAT_DEVICE_SUSPEND_MASK) { // suspend signal, bus idle for more than 3ms // Note: Host may delay more than 3 ms before and/or after bus reset before doing enumeration. - if (dev_cmd_stat & CMDSTAT_DEVICE_ADDR_MASK) + if (cmd_stat & CMDSTAT_DEVICE_ADDR_MASK) { dcd_event_bus_signal(0, DCD_EVENT_SUSPEND, true); } @@ -376,7 +384,7 @@ void DCD_IRQHandler(void) } // Setup Receive - if ( tu_bit_test(int_status, 0) && (dev_cmd_stat & CMDSTAT_SETUP_RECEIVED_MASK) ) + if ( tu_bit_test(int_status, 0) && (cmd_stat & CMDSTAT_SETUP_RECEIVED_MASK) ) { // Follow UM flowchart to clear Active & Stall on both Control IN/OUT endpoints _dcd.ep[0][0].active = _dcd.ep[1][0].active = 0; diff --git a/src/tusb_option.h b/src/tusb_option.h index d0cc0be6a..a0823026d 100644 --- a/src/tusb_option.h +++ b/src/tusb_option.h @@ -39,7 +39,7 @@ // LPC #define OPT_MCU_LPC11UXX 1 ///< NXP LPC11Uxx #define OPT_MCU_LPC13XX 2 ///< NXP LPC13xx -#define OPT_MCU_LPC15xx 3 ///< NXP LPC15xx +#define OPT_MCU_LPC15XX 3 ///< NXP LPC15xx #define OPT_MCU_LPC175X_6X 4 ///< NXP LPC175x, LPC176x #define OPT_MCU_LPC177X_8X 5 ///< NXP LPC177x, LPC178x #define OPT_MCU_LPC18XX 6 ///< NXP LPC18xx From 0747c4b61bdb19f2c2e7ecf4ce7033d69487bb76 Mon Sep 17 00:00:00 2001 From: Kamil Tomaszewski Date: Thu, 3 Oct 2019 14:22:43 +0200 Subject: [PATCH 06/32] Add Spresense board --- .gitmodules | 3 + examples/make.mk | 4 + examples/rules.mk | 6 +- hw/bsp/spresense/board.mk | 47 ++++ hw/bsp/spresense/board_spresense.c | 105 ++++++++ hw/mcu/sony/cxd56/spresense-exported-sdk | 1 + src/portable/sony/cxd56/dcd_cxd56.c | 321 +++++++++++++++++++++++ src/tusb_option.h | 2 + 8 files changed, 488 insertions(+), 1 deletion(-) create mode 100644 hw/bsp/spresense/board.mk create mode 100644 hw/bsp/spresense/board_spresense.c create mode 160000 hw/mcu/sony/cxd56/spresense-exported-sdk create mode 100644 src/portable/sony/cxd56/dcd_cxd56.c diff --git a/.gitmodules b/.gitmodules index f61ef719c..ad85278bf 100644 --- a/.gitmodules +++ b/.gitmodules @@ -13,3 +13,6 @@ [submodule "hw/mcu/st/st_driver"] path = hw/mcu/st/st_driver url = https://github.com/hathach/st_driver.git +[submodule "hw/mcu/sony/cxd56/spresense-exported-sdk"] + path = hw/mcu/sony/cxd56/spresense-exported-sdk + url = https://github.com/sonydevworld/spresense-exported-sdk.git diff --git a/examples/make.mk b/examples/make.mk index 22d8f7455..699cc43d6 100644 --- a/examples/make.mk +++ b/examples/make.mk @@ -80,5 +80,9 @@ CFLAGS += \ ifeq ($(DEBUG), 1) CFLAGS += -O0 -ggdb -DCFG_TUSB_DEBUG=1 else +ifneq ($(BOARD), spresense) CFLAGS += -flto -Os +else + CFLAGS += -Os +endif endif diff --git a/examples/rules.mk b/examples/rules.mk index c3daf9dac..c6997c040 100644 --- a/examples/rules.mk +++ b/examples/rules.mk @@ -3,7 +3,11 @@ # # libc -LIBS += -lgcc -lc -lm -lnosys +LIBS += -lgcc -lm -lnosys + +ifneq ($(BOARD), spresense) +LIBS += -lc +endif # TinyUSB Stack source SRC_C += \ diff --git a/hw/bsp/spresense/board.mk b/hw/bsp/spresense/board.mk new file mode 100644 index 000000000..16421686a --- /dev/null +++ b/hw/bsp/spresense/board.mk @@ -0,0 +1,47 @@ +SPRESENSE_SDK = $(TOP)/hw/mcu/sony/cxd56/spresense-exported-sdk + +INC += \ + $(SPRESENSE_SDK)/nuttx/include \ + $(SPRESENSE_SDK)/nuttx/arch \ + $(SPRESENSE_SDK)/nuttx/arch/chip \ + $(SPRESENSE_SDK)/sdk/bsp/include \ + $(SPRESENSE_SDK)/sdk/bsp/include/sdk \ + +CFLAGS += \ + -DCONFIG_WCHAR_BUILTIN \ + -DCONFIG_HAVE_DOUBLE \ + -Dmain=spresense_main \ + -pipe \ + -std=gnu11 \ + -mcpu=cortex-m4 \ + -mthumb \ + -mfpu=fpv4-sp-d16 \ + -mfloat-abi=hard \ + -mabi=aapcs \ + -fno-builtin \ + -fno-strength-reduce \ + -fomit-frame-pointer \ + -DCFG_TUSB_MCU=OPT_MCU_CXD56 \ + +LIBS += \ + $(SPRESENSE_SDK)/sdk/libs/libapps.a \ + $(SPRESENSE_SDK)/sdk/libs/libsdk.a \ + +LD_FILE = hw/mcu/sony/cxd56/spresense-exported-sdk/nuttx/build/ramconfig.ld + +LDFLAGS += \ + -Xlinker --entry=__start \ + -nostartfiles \ + -nodefaultlibs \ + -Wl,--defsym,__stack=_vectors+786432 \ + -Wl,--gc-sections \ + -u spresense_main \ + +# For TinyUSB port source +VENDOR = sony +CHIP_FAMILY = cxd56 + +# flash +flash: + $(SPRESENSE_SDK)/sdk/tools/linux/mkspk -c 2 $(BUILD)/spresense-firmware.elf nuttx $(BUILD)/spresense-firmware.spk + $(SPRESENSE_SDK)/sdk/tools/flash.sh -c /dev/ttyUSB0 $(BUILD)/spresense-firmware.spk diff --git a/hw/bsp/spresense/board_spresense.c b/hw/bsp/spresense/board_spresense.c new file mode 100644 index 000000000..256bccd15 --- /dev/null +++ b/hw/bsp/spresense/board_spresense.c @@ -0,0 +1,105 @@ +/* + * The MIT License (MIT) + * + * Copyright 2019 Sony Semiconductor Solutions Corporation + * + * 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 +#include +#include +#include + +#include "bsp/board.h" + +/*------------------------------------------------------------------*/ +/* MACRO TYPEDEF CONSTANT ENUM + *------------------------------------------------------------------*/ +#define LED_PIN PIN_I2S1_BCK + +#define BUTTON_PIN PIN_HIF_IRQ_OUT + +// Initialize on-board peripherals : led, button, uart and USB +void board_init(void) +{ + boardctl(BOARDIOC_INIT, 0); + + board_gpio_write(PIN_I2S1_BCK, -1); + board_gpio_config(PIN_I2S1_BCK, 0, false, true, PIN_FLOAT); + + board_gpio_write(PIN_HIF_IRQ_OUT, -1); + board_gpio_config(PIN_HIF_IRQ_OUT, 0, true, true, PIN_FLOAT); +}; + +//--------------------------------------------------------------------+ +// Board porting API +//--------------------------------------------------------------------+ + +// Turn LED on or off +void board_led_write(bool state) +{ + board_gpio_write(LED_PIN, state); +} + +// Get the current state of button +// a '1' means active (pressed), a '0' means inactive. +uint32_t board_button_read(void) +{ + if (board_gpio_read(BUTTON_PIN)) + { + return 0; + } + + return 1; +} + +// Get characters from UART +int board_uart_read(uint8_t *buf, int len) +{ + int r = read(0, buf, len); + + return r; +} + +// Send characters to UART +int board_uart_write(void const *buf, int len) +{ + int r = write(1, buf, len); + + return r; +} + +// Get current milliseconds +uint32_t board_millis(void) +{ + struct timespec tp; + + /* Wait until RTC is available */ + while (g_rtc_enabled == false); + + if (clock_gettime(CLOCK_MONOTONIC, &tp)) + { + return 0; + } + + return (((uint64_t)tp.tv_sec) * 1000 + tp.tv_nsec / 1000000); +} diff --git a/hw/mcu/sony/cxd56/spresense-exported-sdk b/hw/mcu/sony/cxd56/spresense-exported-sdk new file mode 160000 index 000000000..b473b28a1 --- /dev/null +++ b/hw/mcu/sony/cxd56/spresense-exported-sdk @@ -0,0 +1 @@ +Subproject commit b473b28a14a03f3d416b6e2c071bcfd4fb92cb63 diff --git a/src/portable/sony/cxd56/dcd_cxd56.c b/src/portable/sony/cxd56/dcd_cxd56.c new file mode 100644 index 000000000..32eb50a6f --- /dev/null +++ b/src/portable/sony/cxd56/dcd_cxd56.c @@ -0,0 +1,321 @@ +/* + * The MIT License (MIT) + * + * Copyright 2019 Sony Semiconductor Solutions Corporation + * + * 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 "tusb_option.h" + +#if TUSB_OPT_DEVICE_ENABLED && CFG_TUSB_MCU == OPT_MCU_CXD56 + +#include +#include + +#include "device/dcd.h" + +#define CXD56_EPNUM (7) + +struct usbdcd_driver_s +{ + struct usbdevclass_driver_s usbdevclass_driver; + FAR struct usbdev_ep_s *ep[CXD56_EPNUM]; + FAR struct usbdev_req_s *req[CXD56_EPNUM]; +}; + +static struct usbdcd_driver_s usbdcd_driver; +static struct usbdev_s *usbdev; + +static int dcd_bind(FAR struct usbdevclass_driver_s *driver, FAR struct usbdev_s *dev); +static void dcd_unbind(FAR struct usbdevclass_driver_s *driver, FAR struct usbdev_s *dev); +static int dcd_setup(FAR struct usbdevclass_driver_s *driver, FAR struct usbdev_s *dev, + FAR const struct usb_ctrlreq_s *ctrl, FAR uint8_t *dataout, size_t outlen); +static void dcd_disconnect(FAR struct usbdevclass_driver_s *driver, FAR struct usbdev_s *dev); +static void dcd_suspend(FAR struct usbdevclass_driver_s *driver, FAR struct usbdev_s *dev); +static void dcd_resume(FAR struct usbdevclass_driver_s *driver, FAR struct usbdev_s *dev); + +static const struct usbdevclass_driverops_s g_driverops = +{ + dcd_bind, /* bind */ + dcd_unbind, /* unbind */ + dcd_setup, /* setup */ + dcd_disconnect, /* disconnect */ + dcd_suspend, /* suspend */ + dcd_resume, /* resume */ +}; + +static void usbdcd_ep0incomplete(FAR struct usbdev_ep_s *ep, FAR struct usbdev_req_s *req) +{ + (void) ep; + + uint8_t ep_addr = (uint32_t)req->priv; + + if (req->result || req->xfrd != req->len) + { + if (req->len) + { + dcd_event_xfer_complete(0, ep_addr, req->xfrd, XFER_RESULT_SUCCESS, true); + } + } + else + { + if (req->xfrd) + { + dcd_event_xfer_complete(0, ep_addr, req->xfrd, XFER_RESULT_SUCCESS, true); + } + } +} + +static int dcd_bind(FAR struct usbdevclass_driver_s *driver, FAR struct usbdev_s *dev) +{ + (void) driver; + + usbdev = dev; + usbdcd_driver.ep[0] = dev->ep0; + + usbdcd_driver.req[0] = EP_ALLOCREQ(usbdcd_driver.ep[0]); + if (usbdcd_driver.req[0] != NULL) + { + usbdcd_driver.req[0]->len = 64; + usbdcd_driver.req[0]->buf = EP_ALLOCBUFFER(usbdcd_driver.ep[0], 64); + if (!usbdcd_driver.req[0]->buf) + { + EP_FREEREQ(usbdcd_driver.ep[0], usbdcd_driver.req[0]); + usbdcd_driver.req[0] = NULL; + } + } + + usbdcd_driver.req[0]->callback = usbdcd_ep0incomplete; + + DEV_CONNECT(dev); + return 0; +} + +static void dcd_unbind(FAR struct usbdevclass_driver_s *driver, FAR struct usbdev_s *dev) +{ + (void) driver; + (void) dev; +} + +static int dcd_setup(FAR struct usbdevclass_driver_s *driver, FAR struct usbdev_s *dev, + FAR const struct usb_ctrlreq_s *ctrl, FAR uint8_t *dataout, size_t outlen) +{ + (void) driver; + (void) dev; + (void) dataout; + (void) outlen; + + dcd_event_setup_received(0, (uint8_t *)ctrl, true); + + return 0; +} + +static void dcd_disconnect(FAR struct usbdevclass_driver_s *driver, FAR struct usbdev_s *dev) +{ + (void) driver; + + dcd_event_bus_signal(0, DCD_EVENT_BUS_RESET, true); + DEV_CONNECT(dev); +} + +static void dcd_suspend(FAR struct usbdevclass_driver_s *driver, FAR struct usbdev_s *dev) +{ + (void) driver; + (void) dev; +} + +static void dcd_resume(FAR struct usbdevclass_driver_s *driver, FAR struct usbdev_s *dev) +{ + (void) driver; + (void) dev; +} + +void dcd_init(uint8_t rhport) +{ + (void) rhport; + + usbdcd_driver.usbdevclass_driver.speed = USB_SPEED_HIGH; + usbdcd_driver.usbdevclass_driver.ops = &g_driverops; + + usbdev_register(&usbdcd_driver.usbdevclass_driver); +} + +// Enable device interrupt +void dcd_int_enable(uint8_t rhport) +{ + (void) rhport; +} + +// Disable device interrupt +void dcd_int_disable(uint8_t rhport) +{ + (void) rhport; +} + +// Receive Set Address request, mcu port must also include status IN response +void dcd_set_address(uint8_t rhport, uint8_t dev_addr) +{ + (void) rhport; + (void) dev_addr; +} + +// Receive Set Config request +void dcd_set_config(uint8_t rhport, uint8_t config_num) +{ + (void) rhport; + (void) config_num; +} + +void dcd_remote_wakeup(uint8_t rhport) +{ + (void) rhport; + + DEV_WAKEUP(usbdev); +} + +//--------------------------------------------------------------------+ +// Endpoint API +//--------------------------------------------------------------------+ + +bool dcd_edpt_open(uint8_t rhport, tusb_desc_endpoint_t const *p_endpoint_desc) +{ + (void) rhport; + + uint8_t epnum = tu_edpt_number(p_endpoint_desc->bEndpointAddress); + uint8_t const dir = tu_edpt_dir(p_endpoint_desc->bEndpointAddress); + uint8_t xfrtype = 0; + struct usb_epdesc_s epdesc; + + if (epnum >= CXD56_EPNUM) + { + return false; + } + + switch (p_endpoint_desc->bmAttributes.xfer) + { + case 1: + xfrtype = USB_EP_ATTR_XFER_ISOC; + break; + case 2: + xfrtype = USB_EP_ATTR_XFER_BULK; + break; + case 3: + xfrtype = USB_EP_ATTR_XFER_INT; + break; + } + + usbdcd_driver.ep[epnum] = DEV_ALLOCEP(usbdev, epnum, dir == TUSB_DIR_IN, xfrtype); + if (usbdcd_driver.ep[epnum] == NULL) + { + return false; + } + + usbdcd_driver.req[epnum] = NULL; + usbdcd_driver.req[epnum] = EP_ALLOCREQ(usbdcd_driver.ep[epnum]); + if (usbdcd_driver.req[epnum] != NULL) + { + usbdcd_driver.req[epnum]->len = p_endpoint_desc->wMaxPacketSize.size; + } + else + { + return false; + } + + usbdcd_driver.req[epnum]->callback = usbdcd_ep0incomplete; + + epdesc.len = p_endpoint_desc->bLength; + epdesc.type = p_endpoint_desc->bDescriptorType; + epdesc.addr = p_endpoint_desc->bEndpointAddress; + epdesc.attr = xfrtype; + epdesc.mxpacketsize[0] = LSBYTE(p_endpoint_desc->wMaxPacketSize.size); + epdesc.mxpacketsize[1] = MSBYTE(p_endpoint_desc->wMaxPacketSize.size); + epdesc.interval = p_endpoint_desc->bInterval; + + if (EP_CONFIGURE(usbdcd_driver.ep[epnum], &epdesc, false) < 0) + { + return false; + } + + return true; +} + +bool dcd_edpt_xfer(uint8_t rhport, uint8_t ep_addr, uint8_t *buffer, uint16_t total_bytes) +{ + (void) rhport; + + uint8_t epnum = tu_edpt_number(ep_addr); + + if (epnum >= CXD56_EPNUM) + { + return false; + } + + usbdcd_driver.req[epnum]->len = total_bytes; + usbdcd_driver.req[epnum]->priv = (void *)((uint32_t)ep_addr); + usbdcd_driver.req[epnum]->flags = 0; + + if (total_bytes) + { + usbdcd_driver.req[epnum]->buf = buffer; + } + else + { + return true; + } + + if (EP_SUBMIT(usbdcd_driver.ep[epnum], usbdcd_driver.req[epnum]) < 0) + { + return false; + } + + return true; +} + +void dcd_edpt_stall(uint8_t rhport, uint8_t ep_addr) +{ + (void) rhport; + + uint8_t epnum = tu_edpt_number(ep_addr); + + if (epnum >= CXD56_EPNUM) + { + return; + } + + EP_STALL(usbdcd_driver.ep[epnum]); +} + +void dcd_edpt_clear_stall(uint8_t rhport, uint8_t ep_addr) +{ + (void) rhport; + + uint8_t epnum = tu_edpt_number(ep_addr); + + if (epnum >= CXD56_EPNUM) + { + return; + } + + EP_RESUME(usbdcd_driver.ep[epnum]); +} + +#endif diff --git a/src/tusb_option.h b/src/tusb_option.h index 76ea59758..28664c732 100644 --- a/src/tusb_option.h +++ b/src/tusb_option.h @@ -67,6 +67,8 @@ #define OPT_MCU_STM32L1 308 ///< ST STM32L1 #define OPT_MCU_STM32L4 309 ///< ST STM32L4 +#define OPT_MCU_CXD56 400 ///< SONY CXD56 + /** @} */ /** \defgroup group_supported_os Supported RTOS From ada73a57c69338457c46806815555989b8cc2a35 Mon Sep 17 00:00:00 2001 From: hathach Date: Mon, 7 Oct 2019 14:27:02 +0700 Subject: [PATCH 07/32] add ti_driver as submodule --- .gitmodules | 3 +++ hw/mcu/ti | 1 + 2 files changed, 4 insertions(+) create mode 160000 hw/mcu/ti diff --git a/.gitmodules b/.gitmodules index f61ef719c..bc6cd7a89 100644 --- a/.gitmodules +++ b/.gitmodules @@ -13,3 +13,6 @@ [submodule "hw/mcu/st/st_driver"] path = hw/mcu/st/st_driver url = https://github.com/hathach/st_driver.git +[submodule "hw/mcu/ti"] + path = hw/mcu/ti + url = https://github.com/hathach/ti_driver.git diff --git a/hw/mcu/ti b/hw/mcu/ti new file mode 160000 index 000000000..80729b033 --- /dev/null +++ b/hw/mcu/ti @@ -0,0 +1 @@ +Subproject commit 80729b033071ca843e31b60efe3b61da9dca27d4 From f86f0e54a97d41f628e551c4c45f064665db627b Mon Sep 17 00:00:00 2001 From: hathach Date: Mon, 7 Oct 2019 15:06:36 +0700 Subject: [PATCH 08/32] added ti_driver submodule --- hw/mcu/nxp/lpc_driver | 2 +- hw/mcu/ti | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/hw/mcu/nxp/lpc_driver b/hw/mcu/nxp/lpc_driver index 7d2ca4123..fa206508e 160000 --- a/hw/mcu/nxp/lpc_driver +++ b/hw/mcu/nxp/lpc_driver @@ -1 +1 @@ -Subproject commit 7d2ca4123ec4fe04c6ea0aa2662d7a6aebc0c4f7 +Subproject commit fa206508e9ea289ceeb9c35442dd8002002f9316 diff --git a/hw/mcu/ti b/hw/mcu/ti index 80729b033..14fd86b9a 160000 --- a/hw/mcu/ti +++ b/hw/mcu/ti @@ -1 +1 @@ -Subproject commit 80729b033071ca843e31b60efe3b61da9dca27d4 +Subproject commit 14fd86b9a69d7fef42d1045ef88fd8bcabe1be49 From b3872febe2651d51a08941352dc1a5e66df74d4b Mon Sep 17 00:00:00 2001 From: Kamil Tomaszewski Date: Mon, 7 Oct 2019 14:03:02 +0200 Subject: [PATCH 09/32] Disable/enable interrupt --- src/portable/sony/cxd56/dcd_cxd56.c | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/src/portable/sony/cxd56/dcd_cxd56.c b/src/portable/sony/cxd56/dcd_cxd56.c index 32eb50a6f..3698e5103 100644 --- a/src/portable/sony/cxd56/dcd_cxd56.c +++ b/src/portable/sony/cxd56/dcd_cxd56.c @@ -163,12 +163,16 @@ void dcd_init(uint8_t rhport) void dcd_int_enable(uint8_t rhport) { (void) rhport; + + __asm volatile ("cpsie i" : : : "memory"); } // Disable device interrupt void dcd_int_disable(uint8_t rhport) { (void) rhport; + + __asm volatile ("cpsid i" : : : "memory"); } // Receive Set Address request, mcu port must also include status IN response From 992360422113d15266552c5e488d87e0db60345e Mon Sep 17 00:00:00 2001 From: Kamil Tomaszewski Date: Mon, 7 Oct 2019 14:04:48 +0200 Subject: [PATCH 10/32] Send SUSPEND and RESUME signals --- src/portable/sony/cxd56/dcd_cxd56.c | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/src/portable/sony/cxd56/dcd_cxd56.c b/src/portable/sony/cxd56/dcd_cxd56.c index 3698e5103..38f3b5c75 100644 --- a/src/portable/sony/cxd56/dcd_cxd56.c +++ b/src/portable/sony/cxd56/dcd_cxd56.c @@ -141,12 +141,16 @@ static void dcd_suspend(FAR struct usbdevclass_driver_s *driver, FAR struct usbd { (void) driver; (void) dev; + + dcd_event_bus_signal(0, DCD_EVENT_SUSPEND, true); } static void dcd_resume(FAR struct usbdevclass_driver_s *driver, FAR struct usbdev_s *dev) { (void) driver; (void) dev; + + dcd_event_bus_signal(0, DCD_EVENT_RESUME, true); } void dcd_init(uint8_t rhport) From 0cea82568c318f1fb0cc2ade0e23811c4a13e724 Mon Sep 17 00:00:00 2001 From: Kamil Tomaszewski Date: Tue, 8 Oct 2019 09:58:56 +0200 Subject: [PATCH 11/32] Disable/enable only USB interrupt --- src/portable/sony/cxd56/dcd_cxd56.c | 5 +++-- 1 file changed, 3 insertions(+), 2 deletions(-) diff --git a/src/portable/sony/cxd56/dcd_cxd56.c b/src/portable/sony/cxd56/dcd_cxd56.c index 38f3b5c75..638b2f979 100644 --- a/src/portable/sony/cxd56/dcd_cxd56.c +++ b/src/portable/sony/cxd56/dcd_cxd56.c @@ -30,6 +30,7 @@ #include #include +#include #include "device/dcd.h" @@ -168,7 +169,7 @@ void dcd_int_enable(uint8_t rhport) { (void) rhport; - __asm volatile ("cpsie i" : : : "memory"); + up_enable_irq(CXD56_IRQ_USB_INT); } // Disable device interrupt @@ -176,7 +177,7 @@ void dcd_int_disable(uint8_t rhport) { (void) rhport; - __asm volatile ("cpsid i" : : : "memory"); + up_disable_irq(CXD56_IRQ_USB_INT); } // Receive Set Address request, mcu port must also include status IN response From 0b6c031948458da2ebb510e9e12c418b88325d59 Mon Sep 17 00:00:00 2001 From: hathach Date: Tue, 8 Oct 2019 15:49:37 +0700 Subject: [PATCH 12/32] Update README.md --- README.md | 1 + 1 file changed, 1 insertion(+) diff --git a/README.md b/README.md index b82a88955..f2c8805b3 100644 --- a/README.md +++ b/README.md @@ -28,6 +28,7 @@ The stack supports the following MCUs - **Nordic:** nRF52840 - **NXP:** LPC Series: 11Uxx, 13xx, 175x_6x, 177x_8x, 18xx, 40xx, 43xx, 51Uxx - **MicroChip:** SAMD21, SAMD51 (device only) +- **Sony:** CXD56 - **ST:** STM32 series: L0, F0, F1, F2, F3, F4, F7, H7 (device only) [Here is the list of supported Boards](docs/boards.md) that can be used with provided examples. From b3a5bb3247dfac081a01ccb22498ee2f50e365b4 Mon Sep 17 00:00:00 2001 From: hathach Date: Tue, 8 Oct 2019 15:52:00 +0700 Subject: [PATCH 13/32] Update boards.md --- docs/boards.md | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/docs/boards.md b/docs/boards.md index 0b38cf568..892236eca 100644 --- a/docs/boards.md +++ b/docs/boards.md @@ -39,6 +39,10 @@ This code base already had supported for a handful of following boards - [LPCXpresso 54114](https://www.nxp.com/design/microcontrollers-developer-resources/lpcxpresso-boards/lpcxpresso54114-board:OM13089) - [LPCXpresso 55s69 EVK](https://www.nxp.com/products/processors-and-microcontrollers/arm-microcontrollers/general-purpose-mcus/lpc5500-cortex-m33/lpcxpresso55s69-development-board:LPC55S69-EVK) +### Sony + +- [Sony Spresense CXD5602](https://developer.sony.com/develop/spresense) + ### ST STM32 - Adafruit Feather STM32F405 From d9ef34276b8f83be0a0645273fa54f8efca961b9 Mon Sep 17 00:00:00 2001 From: hathach Date: Fri, 11 Oct 2019 11:26:19 +0700 Subject: [PATCH 14/32] update doc --- README.md | 2 +- hw/mcu/ti | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/README.md b/README.md index f2c8805b3..9609f315e 100644 --- a/README.md +++ b/README.md @@ -26,7 +26,7 @@ TinyUSB is an open-source cross-platform USB Host/Device stack for embedded syst The stack supports the following MCUs - **Nordic:** nRF52840 -- **NXP:** LPC Series: 11Uxx, 13xx, 175x_6x, 177x_8x, 18xx, 40xx, 43xx, 51Uxx +- **NXP:** LPC Series: 11Uxx, 13xx, 175x_6x, 177x_8x, 18xx, 40xx, 43xx, 51Uxx, 54xxx, 55xx - **MicroChip:** SAMD21, SAMD51 (device only) - **Sony:** CXD56 - **ST:** STM32 series: L0, F0, F1, F2, F3, F4, F7, H7 (device only) diff --git a/hw/mcu/ti b/hw/mcu/ti index 14fd86b9a..ed52d354c 160000 --- a/hw/mcu/ti +++ b/hw/mcu/ti @@ -1 +1 @@ -Subproject commit 14fd86b9a69d7fef42d1045ef88fd8bcabe1be49 +Subproject commit ed52d354c99e25a5e9db2376eb5e7058c81c3ebd From 195d0f5a147fb83ae3685b9558bdaeb0bd83f8f2 Mon Sep 17 00:00:00 2001 From: hathach Date: Sat, 12 Oct 2019 00:00:08 +0700 Subject: [PATCH 15/32] adding log support with uart started with pca10056 --- examples/make.mk | 1 + hw/bsp/board.c | 58 ++++++++ hw/bsp/board.h | 2 +- hw/bsp/ea4357/ea4357.c | 2 +- hw/bsp/lpcxpresso1769/lpcxpresso1769.c | 2 +- hw/bsp/mbed1768/mbed1768.c | 2 +- hw/bsp/mcb1800/mcb1800.c | 2 +- hw/bsp/ngx4330/ngx4330.c | 2 +- hw/bsp/pca10056/board.mk | 1 + hw/bsp/pca10056/pca10056.c | 31 ++++- hw/bsp/printf_retarget.c | 183 ------------------------- hw/mcu/nordic/nrfx_log.h | 135 ++++++++++++++++++ src/common/tusb_compiler.h | 7 +- 13 files changed, 233 insertions(+), 195 deletions(-) create mode 100644 hw/bsp/board.c delete mode 100644 hw/bsp/printf_retarget.c create mode 100644 hw/mcu/nordic/nrfx_log.h diff --git a/examples/make.mk b/examples/make.mk index 699cc43d6..552483965 100644 --- a/examples/make.mk +++ b/examples/make.mk @@ -46,6 +46,7 @@ BUILD = _build/build-$(BOARD) include $(TOP)/hw/bsp/$(BOARD)/board.mk # Include all source C in board folder +SRC_C += hw/bsp/board.c SRC_C += $(subst $(TOP)/,,$(wildcard $(TOP)/hw/bsp/$(BOARD)/*.c)) # Compiler Flags diff --git a/hw/bsp/board.c b/hw/bsp/board.c new file mode 100644 index 000000000..16e713de5 --- /dev/null +++ b/hw/bsp/board.c @@ -0,0 +1,58 @@ +/* + * The MIT License (MIT) + * + * Copyright (c) 2018, hathach (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" + +//--------------------------------------------------------------------+ +// MACRO TYPEDEF CONSTANT ENUM DECLARATION +//--------------------------------------------------------------------+ + +//#if CFG_PRINTF_TARGET == PRINTF_TARGET_UART +// #define retarget_getchar board_uart_getchar +// #define retarget_putchar board_uart_putchar +//#elif CFG_PRINTF_TARGET == PRINTF_TARGET_SWO +// volatile int32_t ITM_RxBuffer; // keil variable to read from SWO +// #define retarget_getchar ITM_ReceiveChar +// #define retarget_putchar ITM_SendChar +//#else +// #error Target is not implemented yet +//#endif + +//------------- IMPLEMENTATION -------------// + +// newlib read()/write() retarget + +TU_ATTR_USED int _write (int fhdl, const void *buf, size_t count) +{ + (void) fhdl; + return board_uart_write(buf, count); +} + +TU_ATTR_USED int _read (int fhdl, char *buf, size_t count) +{ + (void) fhdl; + return board_uart_read((uint8_t*) buf, count); +} diff --git a/hw/bsp/board.h b/hw/bsp/board.h index 15e3a2511..e0455b80d 100644 --- a/hw/bsp/board.h +++ b/hw/bsp/board.h @@ -42,7 +42,7 @@ #include "tusb.h" -#define CFG_UART_BAUDRATE 115200 +#define CFG_BOARD_UART_BAUDRATE 115200 //--------------------------------------------------------------------+ // Board Porting API diff --git a/hw/bsp/ea4357/ea4357.c b/hw/bsp/ea4357/ea4357.c index 2164d3e09..df80815d8 100644 --- a/hw/bsp/ea4357/ea4357.c +++ b/hw/bsp/ea4357/ea4357.c @@ -134,7 +134,7 @@ void board_init(void) UART_CFG_Type UARTConfigStruct; UART_ConfigStructInit(&UARTConfigStruct); - UARTConfigStruct.Baud_rate = CFG_UART_BAUDRATE; + UARTConfigStruct.Baud_rate = CFG_BOARD_UART_BAUDRATE; UARTConfigStruct.Clock_Speed = 0; UART_Init(BOARD_UART_PORT, &UARTConfigStruct); diff --git a/hw/bsp/lpcxpresso1769/lpcxpresso1769.c b/hw/bsp/lpcxpresso1769/lpcxpresso1769.c index bc6b1da7e..13b8fc9ff 100644 --- a/hw/bsp/lpcxpresso1769/lpcxpresso1769.c +++ b/hw/bsp/lpcxpresso1769/lpcxpresso1769.c @@ -116,7 +116,7 @@ void board_init(void) UART_CFG_Type UARTConfigStruct; UART_ConfigStructInit(&UARTConfigStruct); - UARTConfigStruct.Baud_rate = CFG_UART_BAUDRATE; + UARTConfigStruct.Baud_rate = CFG_BOARD_UART_BAUDRATE; UART_Init(BOARD_UART_PORT, &UARTConfigStruct); UART_TxCmd(BOARD_UART_PORT, ENABLE); // Enable UART Transmit diff --git a/hw/bsp/mbed1768/mbed1768.c b/hw/bsp/mbed1768/mbed1768.c index 05fb4ef35..647334a42 100644 --- a/hw/bsp/mbed1768/mbed1768.c +++ b/hw/bsp/mbed1768/mbed1768.c @@ -108,7 +108,7 @@ void board_init(void) UART_CFG_Type UARTConfigStruct; UART_ConfigStructInit(&UARTConfigStruct); - UARTConfigStruct.Baud_rate = CFG_UART_BAUDRATE; + UARTConfigStruct.Baud_rate = CFG_BOARD_UART_BAUDRATE; UART_Init(BOARD_UART_PORT, &UARTConfigStruct); UART_TxCmd(BOARD_UART_PORT, ENABLE); // Enable UART Transmit diff --git a/hw/bsp/mcb1800/mcb1800.c b/hw/bsp/mcb1800/mcb1800.c index 6f1ef4244..44f5b11bb 100644 --- a/hw/bsp/mcb1800/mcb1800.c +++ b/hw/bsp/mcb1800/mcb1800.c @@ -118,7 +118,7 @@ void board_init(void) UART_CFG_Type UARTConfigStruct; UART_ConfigStructInit(&UARTConfigStruct); - UARTConfigStruct.Baud_rate = CFG_UART_BAUDRATE; + UARTConfigStruct.Baud_rate = CFG_BOARD_UART_BAUDRATE; UARTConfigStruct.Clock_Speed = 0; UART_Init(BOARD_UART_PORT, &UARTConfigStruct); diff --git a/hw/bsp/ngx4330/ngx4330.c b/hw/bsp/ngx4330/ngx4330.c index 0e39ea711..609b4dac6 100644 --- a/hw/bsp/ngx4330/ngx4330.c +++ b/hw/bsp/ngx4330/ngx4330.c @@ -132,7 +132,7 @@ void board_init(void) UART_CFG_Type UARTConfigStruct; UART_ConfigStructInit(&UARTConfigStruct); - UARTConfigStruct.Baud_rate = CFG_UART_BAUDRATE; + UARTConfigStruct.Baud_rate = CFG_BOARD_UART_BAUDRATE; UARTConfigStruct.Clock_Speed = 0; UART_Init(BOARD_UART_PORT, &UARTConfigStruct); diff --git a/hw/bsp/pca10056/board.mk b/hw/bsp/pca10056/board.mk index c0616abee..3cd3e51c6 100644 --- a/hw/bsp/pca10056/board.mk +++ b/hw/bsp/pca10056/board.mk @@ -24,6 +24,7 @@ LDFLAGS += -L$(TOP)/hw/mcu/nordic/nrfx/mdk SRC_C += \ hw/mcu/nordic/nrfx/drivers/src/nrfx_power.c \ + hw/mcu/nordic/nrfx/drivers/src/nrfx_uart.c \ hw/mcu/nordic/nrfx/mdk/system_nrf52840.c \ INC += \ diff --git a/hw/bsp/pca10056/pca10056.c b/hw/bsp/pca10056/pca10056.c index 57426732c..78d9cc2cd 100644 --- a/hw/bsp/pca10056/pca10056.c +++ b/hw/bsp/pca10056/pca10056.c @@ -29,6 +29,7 @@ #include "nrfx.h" #include "nrfx/hal/nrf_gpio.h" #include "nrfx/drivers/include/nrfx_power.h" +#include "nrfx/drivers/include/nrfx_uart.h" #ifdef SOFTDEVICE_PRESENT #include "nrf_sdm.h" @@ -44,6 +45,12 @@ #define BUTTON_PIN 11 #define BUTTON_STATE_ACTIVE 0 +#define UART_RX_PIN 8 +#define UART_TX_PIN 6 + +static nrfx_uart_t _uart_id = NRFX_UART_INSTANCE(0); +//static void uart_handler(nrfx_uart_event_t const * p_event, void* p_context); + // tinyusb function that handles power event (detected, ready, removed) // We must call it within SD's SOC event handler, or set it as power event handler if SD is not enabled. extern void tusb_hal_nrf_power_event(uint32_t event); @@ -69,6 +76,21 @@ void board_init(void) SysTick_Config(SystemCoreClock/1000); #endif + // UART + nrfx_uart_config_t uart_cfg = + { + .pseltxd = UART_TX_PIN, + .pselrxd = UART_RX_PIN, + .pselcts = NRF_UART_PSEL_DISCONNECTED, + .pselrts = NRF_UART_PSEL_DISCONNECTED, + .p_context = NULL, + .hwfc = NRF_UART_HWFC_DISABLED, + .parity = NRF_UART_PARITY_EXCLUDED, + .baudrate = NRF_UART_BAUDRATE_115200 // CFG_BOARD_UART_BAUDRATE + }; + + nrfx_uart_init(&_uart_id, &uart_cfg, NULL); //uart_handler); + #if TUSB_OPT_DEVICE_ENABLED // Priorities 0, 1, 4 (nRF52) are reserved for SoftDevice // 2 is highest for application @@ -124,6 +146,11 @@ uint32_t board_button_read(void) return BUTTON_STATE_ACTIVE == nrf_gpio_pin_read(BUTTON_PIN); } +//static void uart_handler(nrfx_uart_event_t const * p_event, void* p_context) +//{ +// +//} + int board_uart_read(uint8_t* buf, int len) { (void) buf; @@ -133,9 +160,7 @@ int board_uart_read(uint8_t* buf, int len) int board_uart_write(void const * buf, int len) { - (void) buf; - (void) len; - return 0; + return (NRFX_SUCCESS == nrfx_uart_tx(&_uart_id, (uint8_t const*) buf, (size_t) len)) ? len : 0; } #if CFG_TUSB_OS == OPT_OS_NONE diff --git a/hw/bsp/printf_retarget.c b/hw/bsp/printf_retarget.c deleted file mode 100644 index 707a1e099..000000000 --- a/hw/bsp/printf_retarget.c +++ /dev/null @@ -1,183 +0,0 @@ -/* - * The MIT License (MIT) - * - * Copyright (c) 2019 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" - -#if CFG_PRINTF_TARGET != PRINTF_TARGET_SEMIHOST - -#if CFG_PRINTF_TARGET == PRINTF_TARGET_UART - #define retarget_getchar() board_uart_getchar() - #define retarget_putchar(c) board_uart_putchar(c); -#elif CFG_PRINTF_TARGET == PRINTF_TARGET_SWO - volatile int32_t ITM_RxBuffer; // keil variable to read from SWO - #define retarget_getchar() ITM_ReceiveChar() - #define retarget_putchar(c) ITM_SendChar(c) -#else - #error Target is not implemented yet -#endif - -//--------------------------------------------------------------------+ -// LPCXPRESSO / RED SUITE -//--------------------------------------------------------------------+ -#if defined __CODE_RED - -#if CFG_PRINTF_TARGET == PRINTF_TARGET_SWO - #error author does not know how to retarget SWO with lpcxpresso/red-suite -#endif - -// Called by bottom level of printf routine within RedLib C library to write -// a character. With the default semihosting stub, this would write the character -// to the debugger console window . But this version writes -// the character to the UART. -int __sys_write (int iFileHandle, char *buf, int length) -{ - (void) iFileHandle; - - for (int i=0; i -#include -#include "__libc.h" - -int printf(const char *fmt,...) { - char buffer[128]; - va_list args; - va_start (args, fmt); - int n = vsnprintf(buffer, sizeof(buffer), fmt, args); - - for(int i=0; i < n; i++) - { - retarget_putchar( buffer[i] ); - } - - va_end(args); - return n; -} - -int __putchar(int ch, __printf_tag_ptr ctx) -{ - (void)ctx; - retarget_putchar( (uint8_t) ch ); - return 1; -} - -int __getchar() -{ - return retarget_getchar(); -} - -//--------------------------------------------------------------------+ -// KEIL -//--------------------------------------------------------------------+ -#elif defined __CC_ARM // keil - -struct __FILE { - uint32_t handle; -}; - -void _ttywrch(int ch) -{ - if ( ch == '\n' ) retarget_putchar('\r'); - - retarget_putchar(ch); -} - -int fgetc(FILE *f) -{ - return retarget_getchar(); -} - -int fputc(int ch, FILE *f) -{ - _ttywrch(ch); - return ch; -} - -//--------------------------------------------------------------------+ -// IAR -//--------------------------------------------------------------------+ -#elif defined __ICCARM__ // TODO could not able to retarget to UART with IAR - -#if CFG_PRINTF_TARGET == PRINTF_TARGET_UART -#include - -size_t __write(int handle, const unsigned char *buf, size_t length) -{ - /* Check for the command to flush all handles */ - if (handle == -1) return 0; - - /* Check for stdout and stderr (only necessary if FILE descriptors are enabled.) */ - if (handle != 1 && handle != 2) return -1; - - for (size_t i=0; i Date: Fri, 18 Oct 2019 16:38:02 +0700 Subject: [PATCH 16/32] clean up tusb_verify --- src/common/tusb_verify.h | 51 ++++++++++++---------------------------- src/osal/osal.h | 3 --- 2 files changed, 15 insertions(+), 39 deletions(-) diff --git a/src/common/tusb_verify.h b/src/common/tusb_verify.h index fae0c88ae..e59481352 100644 --- a/src/common/tusb_verify.h +++ b/src/common/tusb_verify.h @@ -107,20 +107,6 @@ if ( !(_cond) ) { _handler; return _ret; } \ } while(0) -/*------------- Generator for TU_VERIFY_ERR and TU_VERIFY_ERR_HDLR -------------*/ -#define TU_VERIFY_ERR_DEF2(_error, _handler) do \ -{ \ - uint32_t _err = (uint32_t)(_error); \ - if ( 0 != _err ) { _MESS_ERR(_err); _handler; return _err; } \ -} while(0) - -#define TU_VERIFY_ERR_DEF3(_error, _handler, _ret) do \ -{ \ - uint32_t _err = (uint32_t)(_error); \ - if ( 0 != _err ) { _MESS_ERR(_err); _handler; return _ret; } \ -} while(0) - - /*------------------------------------------------------------------*/ /* TU_VERIFY * - TU_VERIFY_1ARGS : return false if failed @@ -142,28 +128,6 @@ #define TU_VERIFY_HDLR(...) GET_4TH_ARG(__VA_ARGS__, TU_VERIFY_HDLR_3ARGS, TU_VERIFY_HDLR_2ARGS,UNUSED)(__VA_ARGS__) - -/*------------------------------------------------------------------*/ -/* TU_VERIFY STATUS - * - TU_VERIFY_ERR_1ARGS : return status of condition if failed - * - TU_VERIFY_ERR_2ARGS : return provided status code if failed - *------------------------------------------------------------------*/ -#define TU_VERIFY_ERR_1ARGS(_error) TU_VERIFY_ERR_DEF2(_error, ) -#define TU_VERIFY_ERR_2ARGS(_error, _ret) TU_VERIFY_ERR_DEF3(_error, ,_ret) - -#define TU_VERIFY_ERR(...) GET_3RD_ARG(__VA_ARGS__, TU_VERIFY_ERR_2ARGS, TU_VERIFY_ERR_1ARGS,UNUSED)(__VA_ARGS__) - -/*------------------------------------------------------------------*/ -/* TU_VERIFY STATUS WITH HANDLER - * - TU_VERIFY_ERR_HDLR_2ARGS : execute handler, return status if failed - * - TU_VERIFY_ERR_HDLR_3ARGS : execute handler, return provided error if failed - *------------------------------------------------------------------*/ -#define TU_VERIFY_ERR_HDLR_2ARGS(_error, _handler) TU_VERIFY_ERR_DEF2(_error, _handler) -#define TU_VERIFY_ERR_HDLR_3ARGS(_error, _handler, _ret) TU_VERIFY_ERR_DEF3(_error, _handler, _ret) - -#define TU_VERIFY_ERR_HDLR(...) GET_4TH_ARG(__VA_ARGS__, TU_VERIFY_ERR_HDLR_3ARGS, TU_VERIFY_ERR_HDLR_2ARGS,UNUSED)(__VA_ARGS__) - - /*------------------------------------------------------------------*/ /* ASSERT * basically TU_VERIFY with TU_BREAKPOINT() as handler @@ -175,6 +139,21 @@ #define TU_ASSERT(...) GET_3RD_ARG(__VA_ARGS__, ASSERT_2ARGS, ASSERT_1ARGS,UNUSED)(__VA_ARGS__) +// TODO remove TU_ASSERT_ERR() later + +/*------------- Generator for TU_VERIFY_ERR and TU_VERIFY_ERR_HDLR -------------*/ +#define TU_VERIFY_ERR_DEF2(_error, _handler) do \ +{ \ + uint32_t _err = (uint32_t)(_error); \ + if ( 0 != _err ) { _MESS_ERR(_err); _handler; return _err; } \ +} while(0) + +#define TU_VERIFY_ERR_DEF3(_error, _handler, _ret) do \ +{ \ + uint32_t _err = (uint32_t)(_error); \ + if ( 0 != _err ) { _MESS_ERR(_err); _handler; return _ret; } \ +} while(0) + /*------------------------------------------------------------------*/ /* ASSERT Error * basically TU_VERIFY Error with TU_BREAKPOINT() as handler diff --git a/src/osal/osal.h b/src/osal/osal.h index ea655d4f1..6b1d668a4 100644 --- a/src/osal/osal.h +++ b/src/osal/osal.h @@ -86,9 +86,6 @@ static inline bool osal_queue_send(osal_queue_t const qhdl, void const * data, b #define STASK_RETURN(_error) return _error; #define STASK_INVOKE(_subtask, _status) (_status) = _subtask - -// Sub Task Assert -#define STASK_ASSERT_ERR(_err) TU_VERIFY_ERR(_err) #define STASK_ASSERT(_cond) TU_VERIFY(_cond, TUSB_ERROR_OSAL_TASK_FAILED) #endif From 558b4dbde3b9c5e575de08399bad94ae2737d697 Mon Sep 17 00:00:00 2001 From: hathach Date: Fri, 18 Oct 2019 17:50:29 +0700 Subject: [PATCH 17/32] change DEBUG optimization option from O0 to Og add uart write to board test example --- examples/device/board_test/src/main.c | 9 +++++++++ examples/make.mk | 2 +- hw/bsp/board.h | 4 ++-- hw/bsp/pca10056/pca10056.c | 1 + 4 files changed, 13 insertions(+), 3 deletions(-) diff --git a/examples/device/board_test/src/main.c b/examples/device/board_test/src/main.c index 0126110ed..16aad95f8 100644 --- a/examples/device/board_test/src/main.c +++ b/examples/device/board_test/src/main.c @@ -42,6 +42,8 @@ enum { BLINK_UNPRESSED = 1000 }; +#define HELLO_STR "Hello from TinyUSB\n" + int main(void) { board_init(); @@ -49,13 +51,20 @@ int main(void) uint32_t start_ms = 0; bool led_state = false; + while (1) { uint32_t interval_ms = board_button_read() ? BLINK_PRESSED : BLINK_UNPRESSED; + // uart echo +// uint8_t ch; +// if ( board_uart_read(&ch, 1) ) board_uart_write(&ch, 1); + // Blink every interval ms if ( !(board_millis() - start_ms < interval_ms) ) { + board_uart_write(HELLO_STR, strlen(HELLO_STR)); + start_ms = board_millis(); board_led_write(led_state); diff --git a/examples/make.mk b/examples/make.mk index 552483965..b736b8776 100644 --- a/examples/make.mk +++ b/examples/make.mk @@ -79,7 +79,7 @@ CFLAGS += \ # Debugging/Optimization ifeq ($(DEBUG), 1) - CFLAGS += -O0 -ggdb -DCFG_TUSB_DEBUG=1 + CFLAGS += -Og -ggdb -DCFG_TUSB_DEBUG=2 else ifneq ($(BOARD), spresense) CFLAGS += -flto -Os diff --git a/hw/bsp/board.h b/hw/bsp/board.h index e0455b80d..4c5716d96 100644 --- a/hw/bsp/board.h +++ b/hw/bsp/board.h @@ -107,10 +107,10 @@ static inline void board_delay(uint32_t ms) } } -static inline int8_t board_uart_getchar(void) +static inline int board_uart_getchar(void) { uint8_t c; - return board_uart_read(&c, 1) ? c : (-1); + return board_uart_read(&c, 1) ? (int) c : (-1); } static inline int board_uart_putchar(uint8_t c) diff --git a/hw/bsp/pca10056/pca10056.c b/hw/bsp/pca10056/pca10056.c index 78d9cc2cd..2eaed0255 100644 --- a/hw/bsp/pca10056/pca10056.c +++ b/hw/bsp/pca10056/pca10056.c @@ -156,6 +156,7 @@ int board_uart_read(uint8_t* buf, int len) (void) buf; (void) len; return 0; +// return NRFX_SUCCESS == nrfx_uart_rx(&_uart_id, buf, (size_t) len) ? len : 0; } int board_uart_write(void const * buf, int len) From 2f3f23fd94c07b26015139b6ac3aced26218efea Mon Sep 17 00:00:00 2001 From: hathach Date: Fri, 18 Oct 2019 18:30:09 +0700 Subject: [PATCH 18/32] change to use nrfx uarte --- examples/device/board_test/src/main.c | 1 - hw/bsp/pca10056/board.mk | 2 +- hw/bsp/pca10056/pca10056.c | 21 +- hw/mcu/nordic/nrfx_config.h | 877 +------------------------- 4 files changed, 16 insertions(+), 885 deletions(-) diff --git a/examples/device/board_test/src/main.c b/examples/device/board_test/src/main.c index 16aad95f8..865821745 100644 --- a/examples/device/board_test/src/main.c +++ b/examples/device/board_test/src/main.c @@ -51,7 +51,6 @@ int main(void) uint32_t start_ms = 0; bool led_state = false; - while (1) { uint32_t interval_ms = board_button_read() ? BLINK_PRESSED : BLINK_UNPRESSED; diff --git a/hw/bsp/pca10056/board.mk b/hw/bsp/pca10056/board.mk index 3cd3e51c6..abe0d642c 100644 --- a/hw/bsp/pca10056/board.mk +++ b/hw/bsp/pca10056/board.mk @@ -24,7 +24,7 @@ LDFLAGS += -L$(TOP)/hw/mcu/nordic/nrfx/mdk SRC_C += \ hw/mcu/nordic/nrfx/drivers/src/nrfx_power.c \ - hw/mcu/nordic/nrfx/drivers/src/nrfx_uart.c \ + hw/mcu/nordic/nrfx/drivers/src/nrfx_uarte.c \ hw/mcu/nordic/nrfx/mdk/system_nrf52840.c \ INC += \ diff --git a/hw/bsp/pca10056/pca10056.c b/hw/bsp/pca10056/pca10056.c index 2eaed0255..fa7d6fc71 100644 --- a/hw/bsp/pca10056/pca10056.c +++ b/hw/bsp/pca10056/pca10056.c @@ -29,7 +29,7 @@ #include "nrfx.h" #include "nrfx/hal/nrf_gpio.h" #include "nrfx/drivers/include/nrfx_power.h" -#include "nrfx/drivers/include/nrfx_uart.h" +#include "nrfx/drivers/include/nrfx_uarte.h" #ifdef SOFTDEVICE_PRESENT #include "nrf_sdm.h" @@ -48,7 +48,7 @@ #define UART_RX_PIN 8 #define UART_TX_PIN 6 -static nrfx_uart_t _uart_id = NRFX_UART_INSTANCE(0); +static nrfx_uarte_t _uart_id = NRFX_UARTE_INSTANCE(0); //static void uart_handler(nrfx_uart_event_t const * p_event, void* p_context); // tinyusb function that handles power event (detected, ready, removed) @@ -77,19 +77,20 @@ void board_init(void) #endif // UART - nrfx_uart_config_t uart_cfg = + nrfx_uarte_config_t uart_cfg = { .pseltxd = UART_TX_PIN, .pselrxd = UART_RX_PIN, - .pselcts = NRF_UART_PSEL_DISCONNECTED, - .pselrts = NRF_UART_PSEL_DISCONNECTED, + .pselcts = NRF_UARTE_PSEL_DISCONNECTED, + .pselrts = NRF_UARTE_PSEL_DISCONNECTED, .p_context = NULL, - .hwfc = NRF_UART_HWFC_DISABLED, - .parity = NRF_UART_PARITY_EXCLUDED, - .baudrate = NRF_UART_BAUDRATE_115200 // CFG_BOARD_UART_BAUDRATE + .hwfc = NRF_UARTE_HWFC_DISABLED, + .parity = NRF_UARTE_PARITY_EXCLUDED, + .baudrate = NRF_UARTE_BAUDRATE_115200, // CFG_BOARD_UART_BAUDRATE + .interrupt_priority = 7 }; - nrfx_uart_init(&_uart_id, &uart_cfg, NULL); //uart_handler); + nrfx_uarte_init(&_uart_id, &uart_cfg, NULL); //uart_handler); #if TUSB_OPT_DEVICE_ENABLED // Priorities 0, 1, 4 (nRF52) are reserved for SoftDevice @@ -161,7 +162,7 @@ int board_uart_read(uint8_t* buf, int len) int board_uart_write(void const * buf, int len) { - return (NRFX_SUCCESS == nrfx_uart_tx(&_uart_id, (uint8_t const*) buf, (size_t) len)) ? len : 0; + return (NRFX_SUCCESS == nrfx_uarte_tx(&_uart_id, (uint8_t const*) buf, (size_t) len)) ? len : 0; } #if CFG_TUSB_OS == OPT_OS_NONE diff --git a/hw/mcu/nordic/nrfx_config.h b/hw/mcu/nordic/nrfx_config.h index 7c8b90781..8f9aeffe5 100644 --- a/hw/mcu/nordic/nrfx_config.h +++ b/hw/mcu/nordic/nrfx_config.h @@ -1,879 +1,10 @@ #ifndef NRFX_CONFIG_H__ #define NRFX_CONFIG_H__ -#define NRFX_PRS_ENABLED 0 -#define NRFX_CLOCK_ENABLED 0 +#define NRFX_POWER_ENABLED 1 +#define NRFX_POWER_CONFIG_IRQ_PRIORITY 7 -// NRFX_POWER_ENABLED - nrfx_power - POWER peripheral driver -//========================================================== -#ifndef NRFX_POWER_ENABLED -#define NRFX_POWER_ENABLED 1 -#endif -// NRFX_POWER_CONFIG_IRQ_PRIORITY - Interrupt priority - -// <0=> 0 (highest) -// <1=> 1 -// <2=> 2 -// <3=> 3 -// <4=> 4 -// <5=> 5 -// <6=> 6 -// <7=> 7 - -#ifndef NRFX_POWER_CONFIG_IRQ_PRIORITY -#define NRFX_POWER_CONFIG_IRQ_PRIORITY 7 -#endif - -// NRFX_POWER_CONFIG_DEFAULT_DCDCEN - The default configuration of main DCDC regulator - - -// This settings means only that components for DCDC regulator are installed and it can be enabled. - -#ifndef NRFX_POWER_CONFIG_DEFAULT_DCDCEN -#define NRFX_POWER_CONFIG_DEFAULT_DCDCEN 0 -#endif - -// NRFX_POWER_CONFIG_DEFAULT_DCDCENHV - The default configuration of High Voltage DCDC regulator - - -// This settings means only that components for DCDC regulator are installed and it can be enabled. - -#ifndef NRFX_POWER_CONFIG_DEFAULT_DCDCENHV -#define NRFX_POWER_CONFIG_DEFAULT_DCDCENHV 0 -#endif - -// - - -// NRFX_QSPI_ENABLED - nrfx_qspi - QSPI peripheral driver -//========================================================== -#ifndef NRFX_QSPI_ENABLED -#define NRFX_QSPI_ENABLED 1 -#endif -// NRFX_QSPI_CONFIG_SCK_DELAY - tSHSL, tWHSL and tSHWL in number of 16 MHz periods (62.5 ns). <0-255> - - -#ifndef NRFX_QSPI_CONFIG_SCK_DELAY -#define NRFX_QSPI_CONFIG_SCK_DELAY 1 -#endif - -// NRFX_QSPI_CONFIG_XIP_OFFSET - Address offset in the external memory for Execute in Place operation. -#ifndef NRFX_QSPI_CONFIG_XIP_OFFSET -#define NRFX_QSPI_CONFIG_XIP_OFFSET 0 -#endif - -// NRFX_QSPI_CONFIG_READOC - Number of data lines and opcode used for reading. - -// <0=> FastRead -// <1=> Read2O -// <2=> Read2IO -// <3=> Read4O -// <4=> Read4IO - -#ifndef NRFX_QSPI_CONFIG_READOC -#define NRFX_QSPI_CONFIG_READOC 0 -#endif - -// NRFX_QSPI_CONFIG_WRITEOC - Number of data lines and opcode used for writing. - -// <0=> PP -// <1=> PP2O -// <2=> PP4O -// <3=> PP4IO - -#ifndef NRFX_QSPI_CONFIG_WRITEOC -#define NRFX_QSPI_CONFIG_WRITEOC 0 -#endif - -// NRFX_QSPI_CONFIG_ADDRMODE - Addressing mode. - -// <0=> 24bit -// <1=> 32bit - -#ifndef NRFX_QSPI_CONFIG_ADDRMODE -#define NRFX_QSPI_CONFIG_ADDRMODE 0 -#endif - -// NRFX_QSPI_CONFIG_MODE - SPI mode. - -// <0=> Mode 0 -// <1=> Mode 1 - -#ifndef NRFX_QSPI_CONFIG_MODE -#define NRFX_QSPI_CONFIG_MODE 0 -#endif - -// NRFX_QSPI_CONFIG_FREQUENCY - Frequency divider. - -// <0=> 32MHz/1 -// <1=> 32MHz/2 -// <2=> 32MHz/3 -// <3=> 32MHz/4 -// <4=> 32MHz/5 -// <5=> 32MHz/6 -// <6=> 32MHz/7 -// <7=> 32MHz/8 -// <8=> 32MHz/9 -// <9=> 32MHz/10 -// <10=> 32MHz/11 -// <11=> 32MHz/12 -// <12=> 32MHz/13 -// <13=> 32MHz/14 -// <14=> 32MHz/15 -// <15=> 32MHz/16 - -#ifndef NRFX_QSPI_CONFIG_FREQUENCY -#define NRFX_QSPI_CONFIG_FREQUENCY 15 -#endif - -// NRFX_QSPI_PIN_SCK - SCK pin value. -#ifndef NRFX_QSPI_PIN_SCK -#define NRFX_QSPI_PIN_SCK NRF_QSPI_PIN_NOT_CONNECTED -#endif - -// NRFX_QSPI_PIN_CSN - CSN pin value. -#ifndef NRFX_QSPI_PIN_CSN -#define NRFX_QSPI_PIN_CSN NRF_QSPI_PIN_NOT_CONNECTED -#endif - -// NRFX_QSPI_PIN_IO0 - IO0 pin value. -#ifndef NRFX_QSPI_PIN_IO0 -#define NRFX_QSPI_PIN_IO0 NRF_QSPI_PIN_NOT_CONNECTED -#endif - -// NRFX_QSPI_PIN_IO1 - IO1 pin value. -#ifndef NRFX_QSPI_PIN_IO1 -#define NRFX_QSPI_PIN_IO1 NRF_QSPI_PIN_NOT_CONNECTED -#endif - -// NRFX_QSPI_PIN_IO2 - IO2 pin value. -#ifndef NRFX_QSPI_PIN_IO2 -#define NRFX_QSPI_PIN_IO2 NRF_QSPI_PIN_NOT_CONNECTED -#endif - -// NRFX_QSPI_PIN_IO3 - IO3 pin value. -#ifndef NRFX_QSPI_PIN_IO3 -#define NRFX_QSPI_PIN_IO3 NRF_QSPI_PIN_NOT_CONNECTED -#endif - -// NRFX_QSPI_CONFIG_IRQ_PRIORITY - Interrupt priority - -// <0=> 0 (highest) -// <1=> 1 -// <2=> 2 -// <3=> 3 -// <4=> 4 -// <5=> 5 -// <6=> 6 -// <7=> 7 - -#ifndef NRFX_QSPI_CONFIG_IRQ_PRIORITY -#define NRFX_QSPI_CONFIG_IRQ_PRIORITY 7 -#endif - -// - -// NRFX_RNG_ENABLED - nrfx_rng - RNG peripheral driver -//========================================================== -#ifndef NRFX_RNG_ENABLED -#define NRFX_RNG_ENABLED 1 -#endif -// NRFX_RNG_CONFIG_ERROR_CORRECTION - Error correction - - -#ifndef NRFX_RNG_CONFIG_ERROR_CORRECTION -#define NRFX_RNG_CONFIG_ERROR_CORRECTION 1 -#endif - -// NRFX_RNG_CONFIG_IRQ_PRIORITY - Interrupt priority - -// <0=> 0 (highest) -// <1=> 1 -// <2=> 2 -// <3=> 3 -// <4=> 4 -// <5=> 5 -// <6=> 6 -// <7=> 7 - -#ifndef NRFX_RNG_CONFIG_IRQ_PRIORITY -#define NRFX_RNG_CONFIG_IRQ_PRIORITY 7 -#endif - -// NRFX_RNG_CONFIG_LOG_ENABLED - Enables logging in the module. -//========================================================== -#ifndef NRFX_RNG_CONFIG_LOG_ENABLED -#define NRFX_RNG_CONFIG_LOG_ENABLED 0 -#endif -// NRFX_RNG_CONFIG_LOG_LEVEL - Default Severity level - -// <0=> Off -// <1=> Error -// <2=> Warning -// <3=> Info -// <4=> Debug - -#ifndef NRFX_RNG_CONFIG_LOG_LEVEL -#define NRFX_RNG_CONFIG_LOG_LEVEL 3 -#endif - -// NRFX_RNG_CONFIG_INFO_COLOR - ANSI escape code prefix. - -// <0=> Default -// <1=> Black -// <2=> Red -// <3=> Green -// <4=> Yellow -// <5=> Blue -// <6=> Magenta -// <7=> Cyan -// <8=> White - -#ifndef NRFX_RNG_CONFIG_INFO_COLOR -#define NRFX_RNG_CONFIG_INFO_COLOR 0 -#endif - -// NRFX_RNG_CONFIG_DEBUG_COLOR - ANSI escape code prefix. - -// <0=> Default -// <1=> Black -// <2=> Red -// <3=> Green -// <4=> Yellow -// <5=> Blue -// <6=> Magenta -// <7=> Cyan -// <8=> White - -#ifndef NRFX_RNG_CONFIG_DEBUG_COLOR -#define NRFX_RNG_CONFIG_DEBUG_COLOR 0 -#endif - -// - -// - -// NRFX_RTC_ENABLED - nrfx_rtc - RTC peripheral driver -//========================================================== -#ifndef NRFX_RTC_ENABLED -#define NRFX_RTC_ENABLED 1 -#endif -// NRFX_RTC0_ENABLED - Enable RTC0 instance - - -#ifndef NRFX_RTC0_ENABLED -#define NRFX_RTC0_ENABLED 1 -#endif - -// NRFX_RTC1_ENABLED - Enable RTC1 instance - - -#ifndef NRFX_RTC1_ENABLED -#define NRFX_RTC1_ENABLED 1 -#endif - -// NRFX_RTC2_ENABLED - Enable RTC2 instance - - -#ifndef NRFX_RTC2_ENABLED -#define NRFX_RTC2_ENABLED 1 -#endif - -// NRFX_RTC_MAXIMUM_LATENCY_US - Maximum possible time[us] in highest priority interrupt -#ifndef NRFX_RTC_MAXIMUM_LATENCY_US -#define NRFX_RTC_MAXIMUM_LATENCY_US 2000 -#endif - -// NRFX_RTC_DEFAULT_CONFIG_FREQUENCY - Frequency <16-32768> - - -#ifndef NRFX_RTC_DEFAULT_CONFIG_FREQUENCY -#define NRFX_RTC_DEFAULT_CONFIG_FREQUENCY 32768 -#endif - -// NRFX_RTC_DEFAULT_CONFIG_RELIABLE - Ensures safe compare event triggering - - -#ifndef NRFX_RTC_DEFAULT_CONFIG_RELIABLE -#define NRFX_RTC_DEFAULT_CONFIG_RELIABLE 0 -#endif - -// NRFX_RTC_DEFAULT_CONFIG_IRQ_PRIORITY - Interrupt priority - -// <0=> 0 (highest) -// <1=> 1 -// <2=> 2 -// <3=> 3 -// <4=> 4 -// <5=> 5 -// <6=> 6 -// <7=> 7 - -#ifndef NRFX_RTC_DEFAULT_CONFIG_IRQ_PRIORITY -#define NRFX_RTC_DEFAULT_CONFIG_IRQ_PRIORITY 7 -#endif - -// NRFX_RTC_CONFIG_LOG_ENABLED - Enables logging in the module. -//========================================================== -#ifndef NRFX_RTC_CONFIG_LOG_ENABLED -#define NRFX_RTC_CONFIG_LOG_ENABLED 0 -#endif -// NRFX_RTC_CONFIG_LOG_LEVEL - Default Severity level - -// <0=> Off -// <1=> Error -// <2=> Warning -// <3=> Info -// <4=> Debug - -#ifndef NRFX_RTC_CONFIG_LOG_LEVEL -#define NRFX_RTC_CONFIG_LOG_LEVEL 3 -#endif - -// NRFX_RTC_CONFIG_INFO_COLOR - ANSI escape code prefix. - -// <0=> Default -// <1=> Black -// <2=> Red -// <3=> Green -// <4=> Yellow -// <5=> Blue -// <6=> Magenta -// <7=> Cyan -// <8=> White - -#ifndef NRFX_RTC_CONFIG_INFO_COLOR -#define NRFX_RTC_CONFIG_INFO_COLOR 0 -#endif - -// NRFX_RTC_CONFIG_DEBUG_COLOR - ANSI escape code prefix. - -// <0=> Default -// <1=> Black -// <2=> Red -// <3=> Green -// <4=> Yellow -// <5=> Blue -// <6=> Magenta -// <7=> Cyan -// <8=> White - -#ifndef NRFX_RTC_CONFIG_DEBUG_COLOR -#define NRFX_RTC_CONFIG_DEBUG_COLOR 0 -#endif - -// - -// - - -// NRFX_SWI_ENABLED - nrfx_swi - SWI/EGU peripheral allocator -//========================================================== -#ifndef NRFX_SWI_ENABLED -#define NRFX_SWI_ENABLED 1 -#endif -// NRFX_EGU_ENABLED - Enable EGU support - - -#ifndef NRFX_EGU_ENABLED -#define NRFX_EGU_ENABLED 0 -#endif - -// NRFX_SWI0_DISABLED - Exclude SWI0 from being utilized by the driver - - -#ifndef NRFX_SWI0_DISABLED -#define NRFX_SWI0_DISABLED 0 -#endif - -// NRFX_SWI1_DISABLED - Exclude SWI1 from being utilized by the driver - - -#ifndef NRFX_SWI1_DISABLED -#define NRFX_SWI1_DISABLED 0 -#endif - -// NRFX_SWI2_DISABLED - Exclude SWI2 from being utilized by the driver - - -#ifndef NRFX_SWI2_DISABLED -#define NRFX_SWI2_DISABLED 0 -#endif - -// NRFX_SWI3_DISABLED - Exclude SWI3 from being utilized by the driver - - -#ifndef NRFX_SWI3_DISABLED -#define NRFX_SWI3_DISABLED 0 -#endif - -// NRFX_SWI4_DISABLED - Exclude SWI4 from being utilized by the driver - - -#ifndef NRFX_SWI4_DISABLED -#define NRFX_SWI4_DISABLED 0 -#endif - -// NRFX_SWI5_DISABLED - Exclude SWI5 from being utilized by the driver - - -#ifndef NRFX_SWI5_DISABLED -#define NRFX_SWI5_DISABLED 0 -#endif - -// NRFX_SWI_CONFIG_LOG_ENABLED - Enables logging in the module. -//========================================================== -#ifndef NRFX_SWI_CONFIG_LOG_ENABLED -#define NRFX_SWI_CONFIG_LOG_ENABLED 0 -#endif -// NRFX_SWI_CONFIG_LOG_LEVEL - Default Severity level - -// <0=> Off -// <1=> Error -// <2=> Warning -// <3=> Info -// <4=> Debug - -#ifndef NRFX_SWI_CONFIG_LOG_LEVEL -#define NRFX_SWI_CONFIG_LOG_LEVEL 3 -#endif - -// NRFX_SWI_CONFIG_INFO_COLOR - ANSI escape code prefix. - -// <0=> Default -// <1=> Black -// <2=> Red -// <3=> Green -// <4=> Yellow -// <5=> Blue -// <6=> Magenta -// <7=> Cyan -// <8=> White - -#ifndef NRFX_SWI_CONFIG_INFO_COLOR -#define NRFX_SWI_CONFIG_INFO_COLOR 0 -#endif - -// NRFX_SWI_CONFIG_DEBUG_COLOR - ANSI escape code prefix. - -// <0=> Default -// <1=> Black -// <2=> Red -// <3=> Green -// <4=> Yellow -// <5=> Blue -// <6=> Magenta -// <7=> Cyan -// <8=> White - -#ifndef NRFX_SWI_CONFIG_DEBUG_COLOR -#define NRFX_SWI_CONFIG_DEBUG_COLOR 0 -#endif - -// - -// - -// NRFX_SYSTICK_ENABLED - nrfx_systick - ARM(R) SysTick driver - - -#ifndef NRFX_SYSTICK_ENABLED -#define NRFX_SYSTICK_ENABLED 1 -#endif - -// NRFX_TIMER_ENABLED - nrfx_timer - TIMER periperal driver -//========================================================== -#ifndef NRFX_TIMER_ENABLED -#define NRFX_TIMER_ENABLED 1 -#endif -// NRFX_TIMER0_ENABLED - Enable TIMER0 instance - - -#ifndef NRFX_TIMER0_ENABLED -#define NRFX_TIMER0_ENABLED 1 -#endif - -// NRFX_TIMER1_ENABLED - Enable TIMER1 instance - - -#ifndef NRFX_TIMER1_ENABLED -#define NRFX_TIMER1_ENABLED 1 -#endif - -// NRFX_TIMER2_ENABLED - Enable TIMER2 instance - - -#ifndef NRFX_TIMER2_ENABLED -#define NRFX_TIMER2_ENABLED 1 -#endif - -// NRFX_TIMER3_ENABLED - Enable TIMER3 instance - - -#ifndef NRFX_TIMER3_ENABLED -#define NRFX_TIMER3_ENABLED 1 -#endif - -// NRFX_TIMER4_ENABLED - Enable TIMER4 instance - - -#ifndef NRFX_TIMER4_ENABLED -#define NRFX_TIMER4_ENABLED 1 -#endif - -// NRFX_TIMER_DEFAULT_CONFIG_FREQUENCY - Timer frequency if in Timer mode - -// <0=> 16 MHz -// <1=> 8 MHz -// <2=> 4 MHz -// <3=> 2 MHz -// <4=> 1 MHz -// <5=> 500 kHz -// <6=> 250 kHz -// <7=> 125 kHz -// <8=> 62.5 kHz -// <9=> 31.25 kHz - -#ifndef NRFX_TIMER_DEFAULT_CONFIG_FREQUENCY -#define NRFX_TIMER_DEFAULT_CONFIG_FREQUENCY 0 -#endif - -// NRFX_TIMER_DEFAULT_CONFIG_MODE - Timer mode or operation - -// <0=> Timer -// <1=> Counter - -#ifndef NRFX_TIMER_DEFAULT_CONFIG_MODE -#define NRFX_TIMER_DEFAULT_CONFIG_MODE 0 -#endif - -// NRFX_TIMER_DEFAULT_CONFIG_BIT_WIDTH - Timer counter bit width - -// <0=> 16 bit -// <1=> 8 bit -// <2=> 24 bit -// <3=> 32 bit - -#ifndef NRFX_TIMER_DEFAULT_CONFIG_BIT_WIDTH -#define NRFX_TIMER_DEFAULT_CONFIG_BIT_WIDTH 0 -#endif - -// NRFX_TIMER_DEFAULT_CONFIG_IRQ_PRIORITY - Interrupt priority - -// <0=> 0 (highest) -// <1=> 1 -// <2=> 2 -// <3=> 3 -// <4=> 4 -// <5=> 5 -// <6=> 6 -// <7=> 7 - -#ifndef NRFX_TIMER_DEFAULT_CONFIG_IRQ_PRIORITY -#define NRFX_TIMER_DEFAULT_CONFIG_IRQ_PRIORITY 7 -#endif - -// NRFX_TIMER_CONFIG_LOG_ENABLED - Enables logging in the module. -//========================================================== -#ifndef NRFX_TIMER_CONFIG_LOG_ENABLED -#define NRFX_TIMER_CONFIG_LOG_ENABLED 0 -#endif -// NRFX_TIMER_CONFIG_LOG_LEVEL - Default Severity level - -// <0=> Off -// <1=> Error -// <2=> Warning -// <3=> Info -// <4=> Debug - -#ifndef NRFX_TIMER_CONFIG_LOG_LEVEL -#define NRFX_TIMER_CONFIG_LOG_LEVEL 3 -#endif - -// NRFX_TIMER_CONFIG_INFO_COLOR - ANSI escape code prefix. - -// <0=> Default -// <1=> Black -// <2=> Red -// <3=> Green -// <4=> Yellow -// <5=> Blue -// <6=> Magenta -// <7=> Cyan -// <8=> White - -#ifndef NRFX_TIMER_CONFIG_INFO_COLOR -#define NRFX_TIMER_CONFIG_INFO_COLOR 0 -#endif - -// NRFX_TIMER_CONFIG_DEBUG_COLOR - ANSI escape code prefix. - -// <0=> Default -// <1=> Black -// <2=> Red -// <3=> Green -// <4=> Yellow -// <5=> Blue -// <6=> Magenta -// <7=> Cyan -// <8=> White - -#ifndef NRFX_TIMER_CONFIG_DEBUG_COLOR -#define NRFX_TIMER_CONFIG_DEBUG_COLOR 0 -#endif - -// - -// NRFX_UARTE_ENABLED - nrfx_uarte - UARTE peripheral driver -//========================================================== -#ifndef NRFX_UARTE_ENABLED -#define NRFX_UARTE_ENABLED 1 -#endif -// NRFX_UARTE0_ENABLED - Enable UARTE0 instance -#ifndef NRFX_UARTE0_ENABLED -#define NRFX_UARTE0_ENABLED 1 -#endif - -// NRFX_UARTE1_ENABLED - Enable UARTE1 instance -#ifndef NRFX_UARTE1_ENABLED -#define NRFX_UARTE1_ENABLED 1 -#endif - -// NRFX_UARTE_DEFAULT_CONFIG_HWFC - Hardware Flow Control - -// <0=> Disabled -// <1=> Enabled - -#ifndef NRFX_UARTE_DEFAULT_CONFIG_HWFC -#define NRFX_UARTE_DEFAULT_CONFIG_HWFC 0 -#endif - -// NRFX_UARTE_DEFAULT_CONFIG_PARITY - Parity - -// <0=> Excluded -// <14=> Included - -#ifndef NRFX_UARTE_DEFAULT_CONFIG_PARITY -#define NRFX_UARTE_DEFAULT_CONFIG_PARITY 0 -#endif - -// NRFX_UARTE_DEFAULT_CONFIG_BAUDRATE - Default Baudrate - -// <323584=> 1200 baud -// <643072=> 2400 baud -// <1290240=> 4800 baud -// <2576384=> 9600 baud -// <3862528=> 14400 baud -// <5152768=> 19200 baud -// <7716864=> 28800 baud -// <8388608=> 31250 baud -// <10289152=> 38400 baud -// <15007744=> 56000 baud -// <15400960=> 57600 baud -// <20615168=> 76800 baud -// <30801920=> 115200 baud -// <61865984=> 230400 baud -// <67108864=> 250000 baud -// <121634816=> 460800 baud -// <251658240=> 921600 baud -// <268435456=> 1000000 baud - -#ifndef NRFX_UARTE_DEFAULT_CONFIG_BAUDRATE -#define NRFX_UARTE_DEFAULT_CONFIG_BAUDRATE 30801920 -#endif - -// NRFX_UARTE_DEFAULT_CONFIG_IRQ_PRIORITY - Interrupt priority - -// <0=> 0 (highest) -// <1=> 1 -// <2=> 2 -// <3=> 3 -// <4=> 4 -// <5=> 5 -// <6=> 6 -// <7=> 7 - -#ifndef NRFX_UARTE_DEFAULT_CONFIG_IRQ_PRIORITY -#define NRFX_UARTE_DEFAULT_CONFIG_IRQ_PRIORITY 7 -#endif - -// NRFX_UARTE_CONFIG_LOG_ENABLED - Enables logging in the module. -//========================================================== -#ifndef NRFX_UARTE_CONFIG_LOG_ENABLED -#define NRFX_UARTE_CONFIG_LOG_ENABLED 0 -#endif -// NRFX_UARTE_CONFIG_LOG_LEVEL - Default Severity level - -// <0=> Off -// <1=> Error -// <2=> Warning -// <3=> Info -// <4=> Debug - -#ifndef NRFX_UARTE_CONFIG_LOG_LEVEL -#define NRFX_UARTE_CONFIG_LOG_LEVEL 3 -#endif - -// NRFX_UARTE_CONFIG_INFO_COLOR - ANSI escape code prefix. - -// <0=> Default -// <1=> Black -// <2=> Red -// <3=> Green -// <4=> Yellow -// <5=> Blue -// <6=> Magenta -// <7=> Cyan -// <8=> White - -#ifndef NRFX_UARTE_CONFIG_INFO_COLOR -#define NRFX_UARTE_CONFIG_INFO_COLOR 0 -#endif - -// NRFX_UARTE_CONFIG_DEBUG_COLOR - ANSI escape code prefix. - -// <0=> Default -// <1=> Black -// <2=> Red -// <3=> Green -// <4=> Yellow -// <5=> Blue -// <6=> Magenta -// <7=> Cyan -// <8=> White - -#ifndef NRFX_UARTE_CONFIG_DEBUG_COLOR -#define NRFX_UARTE_CONFIG_DEBUG_COLOR 0 -#endif - -// - -// - -// NRFX_UART_ENABLED - nrfx_uart - UART peripheral driver -//========================================================== -#ifndef NRFX_UART_ENABLED -#define NRFX_UART_ENABLED 1 -#endif -// NRFX_UART0_ENABLED - Enable UART0 instance -#ifndef NRFX_UART0_ENABLED -#define NRFX_UART0_ENABLED 1 -#endif - -// NRFX_UART_DEFAULT_CONFIG_HWFC - Hardware Flow Control - -// <0=> Disabled -// <1=> Enabled - -#ifndef NRFX_UART_DEFAULT_CONFIG_HWFC -#define NRFX_UART_DEFAULT_CONFIG_HWFC 0 -#endif - -// NRFX_UART_DEFAULT_CONFIG_PARITY - Parity - -// <0=> Excluded -// <14=> Included - -#ifndef NRFX_UART_DEFAULT_CONFIG_PARITY -#define NRFX_UART_DEFAULT_CONFIG_PARITY 0 -#endif - -// NRFX_UART_DEFAULT_CONFIG_BAUDRATE - Default Baudrate - -// <323584=> 1200 baud -// <643072=> 2400 baud -// <1290240=> 4800 baud -// <2576384=> 9600 baud -// <3866624=> 14400 baud -// <5152768=> 19200 baud -// <7729152=> 28800 baud -// <8388608=> 31250 baud -// <10309632=> 38400 baud -// <15007744=> 56000 baud -// <15462400=> 57600 baud -// <20615168=> 76800 baud -// <30924800=> 115200 baud -// <61845504=> 230400 baud -// <67108864=> 250000 baud -// <123695104=> 460800 baud -// <247386112=> 921600 baud -// <268435456=> 1000000 baud - -#ifndef NRFX_UART_DEFAULT_CONFIG_BAUDRATE -#define NRFX_UART_DEFAULT_CONFIG_BAUDRATE 30924800 -#endif - -// NRFX_UART_DEFAULT_CONFIG_IRQ_PRIORITY - Interrupt priority - -// <0=> 0 (highest) -// <1=> 1 -// <2=> 2 -// <3=> 3 -// <4=> 4 -// <5=> 5 -// <6=> 6 -// <7=> 7 - -#ifndef NRFX_UART_DEFAULT_CONFIG_IRQ_PRIORITY -#define NRFX_UART_DEFAULT_CONFIG_IRQ_PRIORITY 7 -#endif - -// NRFX_UART_CONFIG_LOG_ENABLED - Enables logging in the module. -//========================================================== -#ifndef NRFX_UART_CONFIG_LOG_ENABLED -#define NRFX_UART_CONFIG_LOG_ENABLED 0 -#endif -// NRFX_UART_CONFIG_LOG_LEVEL - Default Severity level - -// <0=> Off -// <1=> Error -// <2=> Warning -// <3=> Info -// <4=> Debug - -#ifndef NRFX_UART_CONFIG_LOG_LEVEL -#define NRFX_UART_CONFIG_LOG_LEVEL 3 -#endif - -// NRFX_UART_CONFIG_INFO_COLOR - ANSI escape code prefix. - -// <0=> Default -// <1=> Black -// <2=> Red -// <3=> Green -// <4=> Yellow -// <5=> Blue -// <6=> Magenta -// <7=> Cyan -// <8=> White - -#ifndef NRFX_UART_CONFIG_INFO_COLOR -#define NRFX_UART_CONFIG_INFO_COLOR 0 -#endif - -// NRFX_UART_CONFIG_DEBUG_COLOR - ANSI escape code prefix. - -// <0=> Default -// <1=> Black -// <2=> Red -// <3=> Green -// <4=> Yellow -// <5=> Blue -// <6=> Magenta -// <7=> Cyan -// <8=> White - -#ifndef NRFX_UART_CONFIG_DEBUG_COLOR -#define NRFX_UART_CONFIG_DEBUG_COLOR 0 -#endif - -// - - -// - -// - -// +#define NRFX_UARTE_ENABLED 1 +#define NRFX_UARTE0_ENABLED 1 #endif // NRFX_CONFIG_H__ From 78bf82291ed61f9d13022618a29f7311a111fda1 Mon Sep 17 00:00:00 2001 From: hathach Date: Sat, 19 Oct 2019 18:19:59 +0700 Subject: [PATCH 19/32] add uart support for stm32f4nucleo board (via stlink cdc) --- hw/bsp/stm32f767nucleo/board.mk | 1 + hw/bsp/stm32f767nucleo/stm32f767nucleo.c | 46 ++++++++++++++++++--- hw/bsp/stm32f767nucleo/stm32f7xx_hal_conf.h | 4 +- 3 files changed, 43 insertions(+), 8 deletions(-) diff --git a/hw/bsp/stm32f767nucleo/board.mk b/hw/bsp/stm32f767nucleo/board.mk index 65690cb2f..46023334c 100644 --- a/hw/bsp/stm32f767nucleo/board.mk +++ b/hw/bsp/stm32f767nucleo/board.mk @@ -25,6 +25,7 @@ SRC_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 += \ diff --git a/hw/bsp/stm32f767nucleo/stm32f767nucleo.c b/hw/bsp/stm32f767nucleo/stm32f767nucleo.c index 07412fd8e..381692fa4 100644 --- a/hw/bsp/stm32f767nucleo/stm32f767nucleo.c +++ b/hw/bsp/stm32f767nucleo/stm32f767nucleo.c @@ -38,6 +38,24 @@ #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 +} + /** * @brief System Clock Configuration * The system Clock is configured as follow : @@ -109,13 +127,13 @@ void board_init(void) #endif SystemClock_Config(); - SystemCoreClockUpdate(); + all_rcc_clk_enable(); + GPIO_InitTypeDef GPIO_InitStruct; // LED - __HAL_RCC_GPIOB_CLK_ENABLE(); GPIO_InitStruct.Pin = LED_PIN; GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_PP; GPIO_InitStruct.Pull = GPIO_PULLUP; @@ -123,16 +141,32 @@ void board_init(void) HAL_GPIO_Init(LED_PORT, &GPIO_InitStruct); // Button - __HAL_RCC_GPIOC_CLK_ENABLE(); 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 FS GPIOs */ /* Configure DM DP Pins */ - __HAL_RCC_GPIOA_CLK_ENABLE(); GPIO_InitStruct.Pin = (GPIO_PIN_11 | GPIO_PIN_12); GPIO_InitStruct.Mode = GPIO_MODE_AF_PP; GPIO_InitStruct.Pull = GPIO_NOPULL; @@ -155,7 +189,6 @@ void board_init(void) /* Enable USB FS Clocks */ __HAL_RCC_USB_OTG_FS_CLK_ENABLE(); - } //--------------------------------------------------------------------+ @@ -180,7 +213,8 @@ 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); +// (void) buf; (void) len; return 0; } diff --git a/hw/bsp/stm32f767nucleo/stm32f7xx_hal_conf.h b/hw/bsp/stm32f767nucleo/stm32f7xx_hal_conf.h index 44093d69c..234191b00 100644 --- a/hw/bsp/stm32f767nucleo/stm32f7xx_hal_conf.h +++ b/hw/bsp/stm32f767nucleo/stm32f7xx_hal_conf.h @@ -41,7 +41,7 @@ /* #define HAL_CRYP_MODULE_ENABLED */ /* #define HAL_DAC_MODULE_ENABLED */ /* #define HAL_DCMI_MODULE_ENABLED */ -/* #define HAL_DMA_MODULE_ENABLED */ +#define HAL_DMA_MODULE_ENABLED /* #define HAL_DMA2D_MODULE_ENABLED */ /* #define HAL_ETH_MODULE_ENABLED */ #define HAL_FLASH_MODULE_ENABLED @@ -66,7 +66,7 @@ /* #define HAL_SPDIFRX_MODULE_ENABLED */ /* #define HAL_SPI_MODULE_ENABLED */ /* #define HAL_TIM_MODULE_ENABLED */ -/* #define HAL_UART_MODULE_ENABLED */ +#define HAL_UART_MODULE_ENABLED /* #define HAL_USART_MODULE_ENABLED */ /* #define HAL_IRDA_MODULE_ENABLED */ /* #define HAL_SMARTCARD_MODULE_ENABLED */ From 661515a8072f2b8ccd601c58120ea87b96158e76 Mon Sep 17 00:00:00 2001 From: hathach Date: Wed, 23 Oct 2019 21:18:46 +0700 Subject: [PATCH 20/32] adding debug log function --- README.md | 5 +- hw/bsp/stm32f767nucleo/stm32f767nucleo.c | 3 +- src/common/tusb_common.h | 44 ++++++++++++- src/device/dcd.h | 7 ++- src/device/usbd.c | 67 +++++++++++++------- src/tusb.c | 80 +++++++++++++++++++++++- 6 files changed, 174 insertions(+), 32 deletions(-) diff --git a/README.md b/README.md index 9609f315e..02fb8257c 100644 --- a/README.md +++ b/README.md @@ -4,7 +4,7 @@ [![Build Status](https://travis-ci.org/hathach/tinyusb.svg?branch=master)](https://travis-ci.org/hathach/tinyusb) [![License](https://img.shields.io/badge/license-MIT-brightgreen.svg)](https://opensource.org/licenses/MIT) -TinyUSB is an open-source cross-platform USB Host/Device stack for embedded system. It is designed to be memory-safe with no dynamic allocation and thread-safe with all interrupt events are deferred then handled in the stack's task function. +TinyUSB is an open-source cross-platform USB Host/Device stack for embedded system, designed to be memory-safe with no dynamic allocation and thread-safe with all interrupt events are deferred then handled in the non-ISR task function. ![tinyusb](https://user-images.githubusercontent.com/249515/49858616-f60c9700-fe27-11e8-8627-e76936352ff7.png) @@ -54,7 +54,7 @@ Support multiple device configurations by dynamically changing usb descriptors. ## OS Abtraction layer -TinyUSB is completely thread-safe by pushing all ISR events into a central queue, then process it later in the non-ISR context. It also uses semphore/mutex to access shared resource such as CDC FIFO. Therefore the stack needs to use some of OS's basic APIs. Following OSes are already supported out of the box. +TinyUSB is completely thread-safe by pushing all ISR events into a central queue, then process it later in the non-ISR context task function. It also uses semphore/mutex to access shared resource such as CDC FIFO. Therefore the stack needs to use some of OS's basic APIs. Following OSes are already supported out of the box. - **No OS** : Disabling USB IRQ is used as way to provide mutex - **FreeRTOS** @@ -84,6 +84,7 @@ TinyUSB is currently used by these other projects: * [Adafruit nRF52 Bootloader](https://github.com/adafruit/Adafruit_nRF52_Bootloader) * [Adafruit SAMD Arduino](https://github.com/adafruit/ArduinoCore-samd) * [CircuitPython](https://github.com/adafruit/circuitpython) +* [MicroPython](https://github.com/micropython/micropython) * [TinyUSB Arduino Library](https://github.com/adafruit/Adafruit_TinyUSB_Arduino) Let's me know if your project also uses TinyUSB and want to share. diff --git a/hw/bsp/stm32f767nucleo/stm32f767nucleo.c b/hw/bsp/stm32f767nucleo/stm32f767nucleo.c index 381692fa4..13966438f 100644 --- a/hw/bsp/stm32f767nucleo/stm32f767nucleo.c +++ b/hw/bsp/stm32f767nucleo/stm32f767nucleo.c @@ -214,8 +214,7 @@ int board_uart_read(uint8_t* buf, int len) int board_uart_write(void const * buf, int len) { HAL_UART_Transmit(&UartHandle, (uint8_t*) buf, len, 0xffff); -// (void) buf; (void) len; - return 0; + return len; } #if CFG_TUSB_OS == OPT_OS_NONE diff --git a/src/common/tusb_common.h b/src/common/tusb_common.h index 57c6e2fcf..59e1fe7fd 100644 --- a/src/common/tusb_common.h +++ b/src/common/tusb_common.h @@ -35,7 +35,7 @@ extern "C" { #endif - //--------------------------------------------------------------------+ +//--------------------------------------------------------------------+ // Macros Helper //--------------------------------------------------------------------+ #define TU_ARRAY_SIZE(_arr) ( sizeof(_arr) / sizeof(_arr[0]) ) @@ -58,7 +58,7 @@ #define TU_BIT(n) (1U << (n)) //--------------------------------------------------------------------+ -// INCLUDES +// Includes //--------------------------------------------------------------------+ // Standard Headers @@ -77,7 +77,7 @@ #include "tusb_types.h" //--------------------------------------------------------------------+ -// INLINE FUNCTION +// Inline Functions //--------------------------------------------------------------------+ #define tu_memclr(buffer, size) memset((buffer), 0, (size)) #define tu_varclr(_var) tu_memclr(_var, sizeof(*(_var))) @@ -203,6 +203,44 @@ static inline bool tu_bit_test (uint32_t value, uint8_t n) { return (value & + TU_BIN8(dlsb)) #endif +//--------------------------------------------------------------------+ +// Debug Function +//--------------------------------------------------------------------+ + +// CFG_TUSB_DEBUG for debugging +// 0 : no debug +// 1 : print when there is error +// 2 : print out log +#if CFG_TUSB_DEBUG + +void tu_print_mem(void const *buf, uint8_t size, uint16_t count); + +#ifndef tu_printf + #define tu_printf printf +#endif + +// Log with debug level 1 +#define TU_LOG1 tu_printf +#define TU_LOG1_MEM tu_print_mem + +// Log with debug level 2 +#if CFG_TUSB_DEBUG > 1 + #define TU_LOG2 TU_LOG1 + #define TU_LOG2_MEM TU_LOG1_MEM +#endif + +#endif // CFG_TUSB_DEBUG + +#ifndef TU_LOG1 + #define TU_LOG1(...) + #define TU_LOG1_MEM(...) +#endif + +#ifndef TU_LOG2 + #define TU_LOG2(...) + #define TU_LOG2_MEM(...) +#endif + #ifdef __cplusplus } #endif diff --git a/src/device/dcd.h b/src/device/dcd.h index bef062fb1..c417ee4be 100644 --- a/src/device/dcd.h +++ b/src/device/dcd.h @@ -39,7 +39,8 @@ typedef enum { - DCD_EVENT_BUS_RESET = 1, + DCD_EVENT_INVALID = 0, + DCD_EVENT_BUS_RESET, DCD_EVENT_UNPLUGGED, DCD_EVENT_SOF, DCD_EVENT_SUSPEND, // TODO LPM Sleep L1 support @@ -49,7 +50,9 @@ typedef enum DCD_EVENT_XFER_COMPLETE, // Not an DCD event, just a convenient way to defer ISR function - USBD_EVENT_FUNC_CALL + USBD_EVENT_FUNC_CALL, + + DCD_EVENT_COUNT } dcd_eventid_t; typedef struct TU_ATTR_ALIGNED(4) diff --git a/src/device/usbd.c b/src/device/usbd.c index 14e56a9b7..e7871fc03 100644 --- a/src/device/usbd.c +++ b/src/device/usbd.c @@ -192,6 +192,25 @@ void usbd_control_reset (uint8_t rhport); bool usbd_control_xfer_cb (uint8_t rhport, uint8_t ep_addr, xfer_result_t event, uint32_t xferred_bytes); void usbd_control_set_complete_callback( bool (*fp) (uint8_t, tusb_control_request_t const * ) ); + +//--------------------------------------------------------------------+ +// Debugging +//--------------------------------------------------------------------+ +#if CFG_TUSB_DEBUG +static char const* const _usbd_event_str[DCD_EVENT_COUNT] = +{ + "INVALID" , + "BUS_RESET" , + "UNPLUGGED" , + "SOF" , + "SUSPEND" , + "RESUME" , + "SETUP_RECEIVED" , + "XFER_COMPLETE" , + "FUNC_CALL" +}; +#endif + //--------------------------------------------------------------------+ // Application API //--------------------------------------------------------------------+ @@ -218,6 +237,8 @@ bool tud_remote_wakeup(void) //--------------------------------------------------------------------+ bool usbd_init (void) { + TU_LOG2("USBD Init\r\n"); + tu_varclr(&_usbd_dev); // Init device queue & task @@ -279,6 +300,8 @@ void tud_task (void) if ( !osal_queue_receive(_usbd_q, &event) ) return; + TU_LOG2("USBD: event %s\r\n", event.event_id < DCD_EVENT_COUNT ? _usbd_event_str[event.event_id] : "CORRUPTED"); + switch ( event.event_id ) { case DCD_EVENT_BUS_RESET: @@ -293,6 +316,8 @@ void tud_task (void) break; case DCD_EVENT_SETUP_RECEIVED: + TU_LOG2_MEM(&event.setup_received, 1, 8); + // Mark as connected after receiving 1st setup packet. // But it is easier to set it every time instead of wasting time to check then set _usbd_dev.connected = 1; @@ -307,29 +332,29 @@ void tud_task (void) break; case DCD_EVENT_XFER_COMPLETE: - // Only handle xfer callback in ready state - // if (_usbd_dev.connected && !_usbd_dev.suspended) + { + // Invoke the class callback associated with the endpoint address + uint8_t const ep_addr = event.xfer_complete.ep_addr; + uint8_t const epnum = tu_edpt_number(ep_addr); + uint8_t const ep_dir = tu_edpt_dir(ep_addr); + + TU_LOG2("Endpoint: 0x%02X, Bytes: %ld\r\n", ep_addr, event.xfer_complete.len); + + _usbd_dev.ep_status[epnum][ep_dir].busy = false; + + if ( 0 == epnum ) { - // Invoke the class callback associated with the endpoint address - uint8_t const ep_addr = event.xfer_complete.ep_addr; - uint8_t const epnum = tu_edpt_number(ep_addr); - uint8_t const ep_dir = tu_edpt_dir(ep_addr); - - _usbd_dev.ep_status[epnum][ep_dir].busy = false; - - if ( 0 == epnum ) - { - // control transfer DATA stage callback - usbd_control_xfer_cb(event.rhport, ep_addr, event.xfer_complete.result, event.xfer_complete.len); - } - else - { - uint8_t const drv_id = _usbd_dev.ep2drv[epnum][ep_dir]; - TU_ASSERT(drv_id < USBD_CLASS_DRIVER_COUNT,); - - usbd_class_drivers[drv_id].xfer_cb(event.rhport, ep_addr, event.xfer_complete.result, event.xfer_complete.len); - } + // control transfer DATA stage callback + usbd_control_xfer_cb(event.rhport, ep_addr, event.xfer_complete.result, event.xfer_complete.len); } + else + { + uint8_t const drv_id = _usbd_dev.ep2drv[epnum][ep_dir]; + TU_ASSERT(drv_id < USBD_CLASS_DRIVER_COUNT,); + + usbd_class_drivers[drv_id].xfer_cb(event.rhport, ep_addr, event.xfer_complete.result, event.xfer_complete.len); + } + } break; case DCD_EVENT_SUSPEND: diff --git a/src/tusb.c b/src/tusb.c index 0f8eedd57..97e3371db 100644 --- a/src/tusb.c +++ b/src/tusb.c @@ -43,11 +43,11 @@ bool tusb_init(void) if (_initialized) return true; #if TUSB_OPT_HOST_ENABLED - TU_VERIFY( usbh_init() ); // init host stack + TU_ASSERT( usbh_init() ); // init host stack #endif #if TUSB_OPT_DEVICE_ENABLED - TU_VERIFY ( usbd_init() ); // init device stack + TU_ASSERT ( usbd_init() ); // init device stack #endif _initialized = true; @@ -64,7 +64,83 @@ bool tusb_inited(void) /* Debug *------------------------------------------------------------------*/ #if CFG_TUSB_DEBUG +#include + char const* const tusb_strerr[TUSB_ERROR_COUNT] = { ERROR_TABLE(ERROR_STRING) }; + +static void dump_str_line(uint8_t const* buf, uint16_t count) +{ + // each line is 16 bytes + for(int i=0; i Date: Thu, 24 Oct 2019 12:00:06 +0700 Subject: [PATCH 21/32] adding more log --- examples/device/cdc_msc/src/main.c | 1 - src/device/usbd.c | 67 +++++++++++++++++++++++++++--- src/tusb.c | 8 ++-- 3 files changed, 65 insertions(+), 11 deletions(-) diff --git a/examples/device/cdc_msc/src/main.c b/examples/device/cdc_msc/src/main.c index c6ed4a922..e1b9ab113 100644 --- a/examples/device/cdc_msc/src/main.c +++ b/examples/device/cdc_msc/src/main.c @@ -55,7 +55,6 @@ void cdc_task(void); int main(void) { board_init(); - tusb_init(); while (1) diff --git a/src/device/usbd.c b/src/device/usbd.c index e7871fc03..f2becab95 100644 --- a/src/device/usbd.c +++ b/src/device/usbd.c @@ -196,7 +196,7 @@ void usbd_control_set_complete_callback( bool (*fp) (uint8_t, tusb_control_reque //--------------------------------------------------------------------+ // Debugging //--------------------------------------------------------------------+ -#if CFG_TUSB_DEBUG +#if CFG_TUSB_DEBUG > 1 static char const* const _usbd_event_str[DCD_EVENT_COUNT] = { "INVALID" , @@ -209,6 +209,47 @@ static char const* const _usbd_event_str[DCD_EVENT_COUNT] = "XFER_COMPLETE" , "FUNC_CALL" }; + +// must be same driver order as usbd_class_drivers[] +static char const* const _usbd_driver_str[USBD_CLASS_DRIVER_COUNT] = +{ + #if CFG_TUD_CDC + "CDC", + #endif + #if CFG_TUD_MSC + "MSC", + #endif + #if CFG_TUD_HID + "HID", + #endif + #if CFG_TUD_MIDI + "MIDI", + #endif + #if CFG_TUD_VENDOR + "Vendor", + #endif + #if CFG_TUD_USBTMC + "USBTMC" + #endif +}; + +static char const* const _tusb_std_request_str[] = +{ + "Get Status" , + "Clear Feature" , + "Reserved" , + "Set Feature" , + "Reserved" , + "Set Address" , + "Get Descriptor" , + "Set Descriptor" , + "Get Configuration" , + "Set Configuration" , + "Get Interface" , + "Set Interface" , + "Synch Frame" +}; + #endif //--------------------------------------------------------------------+ @@ -237,7 +278,7 @@ bool tud_remote_wakeup(void) //--------------------------------------------------------------------+ bool usbd_init (void) { - TU_LOG2("USBD Init\r\n"); + TU_LOG2("USBD init\r\n"); tu_varclr(&_usbd_dev); @@ -246,7 +287,11 @@ bool usbd_init (void) TU_ASSERT(_usbd_q != NULL); // Init class drivers - for (uint8_t i = 0; i < USBD_CLASS_DRIVER_COUNT; i++) usbd_class_drivers[i].init(); + for (uint8_t i = 0; i < USBD_CLASS_DRIVER_COUNT; i++) + { + TU_LOG2("%s init\r\n", _usbd_driver_str[i]); + usbd_class_drivers[i].init(); + } // Init device controller driver dcd_init(TUD_OPT_RHPORT); @@ -316,6 +361,7 @@ void tud_task (void) break; case DCD_EVENT_SETUP_RECEIVED: + TU_LOG2(" "); TU_LOG2_MEM(&event.setup_received, 1, 8); // Mark as connected after receiving 1st setup packet. @@ -338,7 +384,7 @@ void tud_task (void) uint8_t const epnum = tu_edpt_number(ep_addr); uint8_t const ep_dir = tu_edpt_dir(ep_addr); - TU_LOG2("Endpoint: 0x%02X, Bytes: %ld\r\n", ep_addr, event.xfer_complete.len); + TU_LOG2(" Endpoint: 0x%02X, Bytes: %ld\r\n", ep_addr, event.xfer_complete.len); _usbd_dev.ep_status[epnum][ep_dir].busy = false; @@ -352,6 +398,7 @@ void tud_task (void) uint8_t const drv_id = _usbd_dev.ep2drv[epnum][ep_dir]; TU_ASSERT(drv_id < USBD_CLASS_DRIVER_COUNT,); + TU_LOG2(" %s xfer callback\r\n", _usbd_driver_str[drv_id]); usbd_class_drivers[drv_id].xfer_cb(event.rhport, ep_addr, event.xfer_complete.result, event.xfer_complete.len); } } @@ -407,6 +454,13 @@ static bool process_control_request(uint8_t rhport, tusb_control_request_t const return tud_vendor_control_request_cb(rhport, p_request); } +#if CFG_TUSB_DEBUG > 1 + if (TUSB_REQ_TYPE_STANDARD == p_request->bmRequestType_bit.type && p_request->bRequest <= TUSB_REQ_SYNCH_FRAME) + { + TU_LOG2(" %s\r\n", _tusb_std_request_str[p_request->bRequest]); + } +#endif + switch ( p_request->bmRequestType_bit.recipient ) { //------------- Device Requests e.g in enumeration -------------// @@ -519,6 +573,7 @@ static bool process_control_request(uint8_t rhport, tusb_control_request_t const // GET HID REPORT DESCRIPTOR falls into this case // stall control endpoint if driver return false usbd_control_set_complete_callback(usbd_class_drivers[drvid].control_complete); + TU_LOG2(" %s control request\r\n", _usbd_driver_str[drvid]); TU_ASSERT(usbd_class_drivers[drvid].control_request != NULL && usbd_class_drivers[drvid].control_request(rhport, p_request)); break; @@ -528,6 +583,7 @@ static bool process_control_request(uint8_t rhport, tusb_control_request_t const // forward to class driver: "non-STD request to Interface" // stall control endpoint if driver return false usbd_control_set_complete_callback(usbd_class_drivers[drvid].control_complete); + TU_LOG2(" %s control request\r\n", _usbd_driver_str[drvid]); TU_ASSERT(usbd_class_drivers[drvid].control_request != NULL && usbd_class_drivers[drvid].control_request(rhport, p_request)); } @@ -595,7 +651,7 @@ static bool process_control_request(uint8_t rhport, tusb_control_request_t const // For std-type requests: non-std request codes are already discarded. // must not call tud_control_status(), and return value will have no effect // class driver is invoked last, so that EP already has EP stall cleared (in event of clear feature EP halt) - + TU_LOG2(" %s control request\r\n", _usbd_driver_str[drv_id]); if ( usbd_class_drivers[drv_id].control_request && usbd_class_drivers[drv_id].control_request(rhport, p_request)) { @@ -652,6 +708,7 @@ static bool process_set_config(uint8_t rhport, uint8_t cfg_num) _usbd_dev.itf2drv[desc_itf->bInterfaceNumber] = drv_id; uint16_t itf_len=0; + TU_LOG2(" %s open\r\n", _usbd_driver_str[drv_id]); TU_ASSERT( usbd_class_drivers[drv_id].open(rhport, desc_itf, &itf_len) ); TU_ASSERT( itf_len >= sizeof(tusb_desc_interface_t) ); diff --git a/src/tusb.c b/src/tusb.c index 97e3371db..271b35f1e 100644 --- a/src/tusb.c +++ b/src/tusb.c @@ -85,7 +85,7 @@ void tu_print_mem(void const *buf, uint8_t size, uint16_t count) { if ( !buf || !count ) { - tu_printf("NULL\n"); + tu_printf("NULL\r\n"); return; } @@ -107,7 +107,7 @@ void tu_print_mem(void const *buf, uint8_t size, uint16_t count) { tu_printf(" | "); dump_str_line(buf8-16, 16); - tu_printf("\n"); + tu_printf("\r\n"); } // print offset or absolute address @@ -136,9 +136,7 @@ void tu_print_mem(void const *buf, uint8_t size, uint16_t count) tu_printf(" | "); dump_str_line(buf8-nback, nback); - tu_printf("\n"); - - tu_printf("\n"); + tu_printf("\r\n"); } #endif From 33e3bf001cbf5ab69fd15eec3b75a835bf810bdc Mon Sep 17 00:00:00 2001 From: hathach Date: Thu, 24 Oct 2019 12:07:37 +0700 Subject: [PATCH 22/32] update boards doc --- docs/boards.md | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/docs/boards.md b/docs/boards.md index 892236eca..608cbf4eb 100644 --- a/docs/boards.md +++ b/docs/boards.md @@ -1,9 +1,9 @@ # Boards The board support code is only used for self-contained examples and testing. It is not used when TinyUSB is part of a larger project. It is responsible for getting the MCU started and the USB peripheral clocked with minimal of on-board devices -- One LED for status -- One Button to get input from user -- One UART optionally, mostly for host examples +- One LED : for status +- One Button : to get input from user +- One UART : optional for device, but required for host examples ## Supported Boards From 6f952a8e84acfbc962cf3d37ed72bddefebaf58b Mon Sep 17 00:00:00 2001 From: hathach Date: Thu, 24 Oct 2019 12:20:06 +0700 Subject: [PATCH 23/32] fix missing board uart read/write() --- .../circuitplayground_bluefruit.c | 6 ++---- .../circuitplayground_express.c | 12 ++++++++++++ hw/bsp/ea4088qs/ea4088qs.c | 6 ++---- hw/bsp/ea4357/ea4357.c | 6 ++---- hw/bsp/feather_m0_express/feather_m0_express.c | 12 ++++++++++++ hw/bsp/feather_m4_express/feather_m4_express.c | 12 ++++++++++++ .../feather_nrf52840_express.c | 6 ++---- hw/bsp/feather_stm32f405/feather_stm32f405.c | 12 ++++++++++++ hw/bsp/lpcxpresso11u37/lpcxpresso11u37.c | 6 ++---- hw/bsp/lpcxpresso11u68/lpcxpresso11u68.c | 6 ++---- hw/bsp/lpcxpresso1347/lpcxpresso1347.c | 6 ++---- hw/bsp/lpcxpresso1549/lpcxpresso1549.c | 6 ++---- hw/bsp/lpcxpresso1769/lpcxpresso1769.c | 6 ++---- hw/bsp/lpcxpresso51u68/lpcxpresso51u68.c | 6 ++---- hw/bsp/lpcxpresso54114/lpcxpresso54114.c | 6 ++---- hw/bsp/lpcxpresso55s69/lpcxpresso55s69.c | 6 ++---- hw/bsp/mbed1768/mbed1768.c | 6 ++---- hw/bsp/mcb1800/mcb1800.c | 11 ++++------- hw/bsp/metro_m0_express/metro_m0_express.c | 12 ++++++++++++ hw/bsp/metro_m4_express/metro_m4_express.c | 12 ++++++++++++ hw/bsp/ngx4330/ngx4330.c | 6 ++---- hw/bsp/pca10056/pca10056.c | 3 +-- hw/bsp/pca10059/pca10059.c | 6 ++---- hw/bsp/pyboardv11/pyboardv11.c | 12 ++++++++++++ hw/bsp/stm32f070rbnucleo/stm32f070rbnucleo.c | 12 ++++++++++++ hw/bsp/stm32f072disco/stm32f072disco.c | 12 ++++++++++++ hw/bsp/stm32f103bluepill/stm32f103bluepill.c | 12 ++++++++++++ hw/bsp/stm32f207nucleo/stm32f207nucleo.c | 12 ++++++++++++ hw/bsp/stm32f303disco/stm32f303disco.c | 12 ++++++++++++ hw/bsp/stm32f407disco/stm32f407disco.c | 12 ++++++++++++ hw/bsp/stm32f411disco/stm32f411disco.c | 12 ++++++++++++ hw/bsp/stm32f412disco/stm32f412disco.c | 12 ++++++++++++ hw/bsp/stm32l0538disco/stm32l0538disco.c | 12 ++++++++++++ hw/bsp/stm32l476disco/stm32l476disco.c | 12 ++++++++++++ 34 files changed, 239 insertions(+), 69 deletions(-) diff --git a/hw/bsp/circuitplayground_bluefruit/circuitplayground_bluefruit.c b/hw/bsp/circuitplayground_bluefruit/circuitplayground_bluefruit.c index 59085fe97..30742ab9f 100644 --- a/hw/bsp/circuitplayground_bluefruit/circuitplayground_bluefruit.c +++ b/hw/bsp/circuitplayground_bluefruit/circuitplayground_bluefruit.c @@ -125,15 +125,13 @@ uint32_t board_button_read(void) int board_uart_read(uint8_t* buf, int len) { - (void) buf; - (void) len; + (void) buf; (void) len; return 0; } int board_uart_write(void const * buf, int len) { - (void) buf; - (void) len; + (void) buf; (void) len; return 0; } diff --git a/hw/bsp/circuitplayground_express/circuitplayground_express.c b/hw/bsp/circuitplayground_express/circuitplayground_express.c index 355e15d39..6ca584eb3 100644 --- a/hw/bsp/circuitplayground_express/circuitplayground_express.c +++ b/hw/bsp/circuitplayground_express/circuitplayground_express.c @@ -116,6 +116,18 @@ uint32_t board_button_read(void) return gpio_get_pin_level(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) +{ + (void) buf; (void) len; + return 0; +} + #if CFG_TUSB_OS == OPT_OS_NONE volatile uint32_t system_ticks = 0; void SysTick_Handler (void) diff --git a/hw/bsp/ea4088qs/ea4088qs.c b/hw/bsp/ea4088qs/ea4088qs.c index 4e9f930d2..8adb61fda 100644 --- a/hw/bsp/ea4088qs/ea4088qs.c +++ b/hw/bsp/ea4088qs/ea4088qs.c @@ -131,16 +131,14 @@ uint32_t board_button_read(void) int board_uart_read(uint8_t* buf, int len) { //return UART_ReceiveByte(BOARD_UART_PORT); - (void) buf; - (void) len; + (void) buf; (void) len; return 0; } int board_uart_write(void const * buf, int len) { //UART_Send(BOARD_UART_PORT, &c, 1, BLOCKING); - (void) buf; - (void) len; + (void) buf; (void) len; return 0; } diff --git a/hw/bsp/ea4357/ea4357.c b/hw/bsp/ea4357/ea4357.c index df80815d8..c276f10d3 100644 --- a/hw/bsp/ea4357/ea4357.c +++ b/hw/bsp/ea4357/ea4357.c @@ -254,16 +254,14 @@ uint32_t board_button_read(void) int board_uart_read(uint8_t* buf, int len) { //return UART_ReceiveByte(BOARD_UART_PORT); - (void) buf; - (void) len; + (void) buf; (void) len; return 0; } int board_uart_write(void const * buf, int len) { //UART_Send(BOARD_UART_PORT, &c, 1, BLOCKING); - (void) buf; - (void) len; + (void) buf; (void) len; return 0; } diff --git a/hw/bsp/feather_m0_express/feather_m0_express.c b/hw/bsp/feather_m0_express/feather_m0_express.c index 17576bb5a..35505add9 100644 --- a/hw/bsp/feather_m0_express/feather_m0_express.c +++ b/hw/bsp/feather_m0_express/feather_m0_express.c @@ -116,6 +116,18 @@ uint32_t board_button_read(void) return gpio_get_pin_level(BUTTON_PIN) ? 0 : 1; } +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) diff --git a/hw/bsp/feather_m4_express/feather_m4_express.c b/hw/bsp/feather_m4_express/feather_m4_express.c index a368b3038..fccd0d3af 100644 --- a/hw/bsp/feather_m4_express/feather_m4_express.c +++ b/hw/bsp/feather_m4_express/feather_m4_express.c @@ -105,6 +105,18 @@ uint32_t board_button_read(void) return gpio_get_pin_level(BUTTON_PIN) ? 0 : 1; } +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; diff --git a/hw/bsp/feather_nrf52840_express/feather_nrf52840_express.c b/hw/bsp/feather_nrf52840_express/feather_nrf52840_express.c index ed3954c82..24cc3cf2f 100644 --- a/hw/bsp/feather_nrf52840_express/feather_nrf52840_express.c +++ b/hw/bsp/feather_nrf52840_express/feather_nrf52840_express.c @@ -125,15 +125,13 @@ uint32_t board_button_read(void) int board_uart_read(uint8_t* buf, int len) { - (void) buf; - (void) len; + (void) buf; (void) len; return 0; } int board_uart_write(void const * buf, int len) { - (void) buf; - (void) len; + (void) buf; (void) len; return 0; } diff --git a/hw/bsp/feather_stm32f405/feather_stm32f405.c b/hw/bsp/feather_stm32f405/feather_stm32f405.c index 02c33a0a8..0bc40ece0 100644 --- a/hw/bsp/feather_stm32f405/feather_stm32f405.c +++ b/hw/bsp/feather_stm32f405/feather_stm32f405.c @@ -172,6 +172,18 @@ 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) +{ + (void) buf; (void) len; + return 0; +} + #if CFG_TUSB_OS == OPT_OS_NONE volatile uint32_t system_ticks = 0; void SysTick_Handler (void) diff --git a/hw/bsp/lpcxpresso11u37/lpcxpresso11u37.c b/hw/bsp/lpcxpresso11u37/lpcxpresso11u37.c index f7fc16ec2..546dd3d13 100644 --- a/hw/bsp/lpcxpresso11u37/lpcxpresso11u37.c +++ b/hw/bsp/lpcxpresso11u37/lpcxpresso11u37.c @@ -173,15 +173,13 @@ uint32_t board_button_read(void) int board_uart_read(uint8_t* buf, int len) { - (void) buf; - (void) len; + (void) buf; (void) len; return 0; } int board_uart_write(void const * buf, int len) { - (void) buf; - (void) len; + (void) buf; (void) len; return 0; } diff --git a/hw/bsp/lpcxpresso11u68/lpcxpresso11u68.c b/hw/bsp/lpcxpresso11u68/lpcxpresso11u68.c index 4f0194972..d062de7c3 100644 --- a/hw/bsp/lpcxpresso11u68/lpcxpresso11u68.c +++ b/hw/bsp/lpcxpresso11u68/lpcxpresso11u68.c @@ -100,15 +100,13 @@ uint32_t board_button_read(void) int board_uart_read(uint8_t* buf, int len) { - (void) buf; - (void) len; + (void) buf; (void) len; return 0; } int board_uart_write(void const * buf, int len) { - (void) buf; - (void) len; + (void) buf; (void) len; return 0; } diff --git a/hw/bsp/lpcxpresso1347/lpcxpresso1347.c b/hw/bsp/lpcxpresso1347/lpcxpresso1347.c index d389eb798..cc1a8deae 100644 --- a/hw/bsp/lpcxpresso1347/lpcxpresso1347.c +++ b/hw/bsp/lpcxpresso1347/lpcxpresso1347.c @@ -130,14 +130,12 @@ uint32_t board_button_read(void) int board_uart_read(uint8_t* buf, int len) { - (void) buf; - (void) len; + (void) buf; (void) len; return 0; } int board_uart_write(void const * buf, int len) { - (void) buf; - (void) len; + (void) buf; (void) len; return 0; } diff --git a/hw/bsp/lpcxpresso1549/lpcxpresso1549.c b/hw/bsp/lpcxpresso1549/lpcxpresso1549.c index e10e24020..5f806d851 100644 --- a/hw/bsp/lpcxpresso1549/lpcxpresso1549.c +++ b/hw/bsp/lpcxpresso1549/lpcxpresso1549.c @@ -113,14 +113,12 @@ uint32_t board_button_read(void) int board_uart_read(uint8_t* buf, int len) { - (void) buf; - (void) len; + (void) buf; (void) len; return 0; } int board_uart_write(void const * buf, int len) { - (void) buf; - (void) len; + (void) buf; (void) len; return 0; } diff --git a/hw/bsp/lpcxpresso1769/lpcxpresso1769.c b/hw/bsp/lpcxpresso1769/lpcxpresso1769.c index 13b8fc9ff..e2d5f6cf2 100644 --- a/hw/bsp/lpcxpresso1769/lpcxpresso1769.c +++ b/hw/bsp/lpcxpresso1769/lpcxpresso1769.c @@ -160,16 +160,14 @@ uint32_t board_button_read(void) int board_uart_read(uint8_t* buf, int len) { // return UART_ReceiveByte(BOARD_UART_PORT); - (void) buf; - (void) len; + (void) buf; (void) len; return 0; } int board_uart_write(void const * buf, int len) { // UART_Send(BOARD_UART_PORT, &c, 1, BLOCKING); - (void) buf; - (void) len; + (void) buf; (void) len; return 0; } diff --git a/hw/bsp/lpcxpresso51u68/lpcxpresso51u68.c b/hw/bsp/lpcxpresso51u68/lpcxpresso51u68.c index df915a720..11b190b92 100644 --- a/hw/bsp/lpcxpresso51u68/lpcxpresso51u68.c +++ b/hw/bsp/lpcxpresso51u68/lpcxpresso51u68.c @@ -144,15 +144,13 @@ uint32_t board_button_read(void) int board_uart_read(uint8_t* buf, int len) { - (void) buf; - (void) len; + (void) buf; (void) len; return 0; } int board_uart_write(void const * buf, int len) { - (void) buf; - (void) len; + (void) buf; (void) len; return 0; } diff --git a/hw/bsp/lpcxpresso54114/lpcxpresso54114.c b/hw/bsp/lpcxpresso54114/lpcxpresso54114.c index 090c1a95e..d86af58c8 100644 --- a/hw/bsp/lpcxpresso54114/lpcxpresso54114.c +++ b/hw/bsp/lpcxpresso54114/lpcxpresso54114.c @@ -145,15 +145,13 @@ uint32_t board_button_read(void) int board_uart_read(uint8_t* buf, int len) { - (void) buf; - (void) len; + (void) buf; (void) len; return 0; } int board_uart_write(void const * buf, int len) { - (void) buf; - (void) len; + (void) buf; (void) len; return 0; } diff --git a/hw/bsp/lpcxpresso55s69/lpcxpresso55s69.c b/hw/bsp/lpcxpresso55s69/lpcxpresso55s69.c index 41e3028f1..e595634a7 100644 --- a/hw/bsp/lpcxpresso55s69/lpcxpresso55s69.c +++ b/hw/bsp/lpcxpresso55s69/lpcxpresso55s69.c @@ -187,15 +187,13 @@ uint32_t board_button_read(void) int board_uart_read(uint8_t* buf, int len) { - (void) buf; - (void) len; + (void) buf; (void) len; return 0; } int board_uart_write(void const * buf, int len) { - (void) buf; - (void) len; + (void) buf; (void) len; return 0; } diff --git a/hw/bsp/mbed1768/mbed1768.c b/hw/bsp/mbed1768/mbed1768.c index 647334a42..9f1ed12ef 100644 --- a/hw/bsp/mbed1768/mbed1768.c +++ b/hw/bsp/mbed1768/mbed1768.c @@ -152,16 +152,14 @@ uint32_t board_button_read(void) int board_uart_read(uint8_t* buf, int len) { // return UART_ReceiveByte(BOARD_UART_PORT); - (void) buf; - (void) len; + (void) buf; (void) len; return 0; } int board_uart_write(void const * buf, int len) { // UART_Send(BOARD_UART_PORT, &c, 1, BLOCKING); - (void) buf; - (void) len; + (void) buf; (void) len; return 0; } diff --git a/hw/bsp/mcb1800/mcb1800.c b/hw/bsp/mcb1800/mcb1800.c index 44f5b11bb..deb17f113 100644 --- a/hw/bsp/mcb1800/mcb1800.c +++ b/hw/bsp/mcb1800/mcb1800.c @@ -28,14 +28,13 @@ #include "../board.h" // PD_10 -#define LED_PORT 6 -#define LED_PIN 24 +#define LED_PORT 6 +#define LED_PIN 24 // P4_0 #define BUTTON_PORT 2 #define BUTTON_PIN 0 - //--------------------------------------------------------------------+ // MACRO TYPEDEF CONSTANT ENUM DECLARATION //--------------------------------------------------------------------+ @@ -191,16 +190,14 @@ uint32_t board_button_read(void) int board_uart_read(uint8_t* buf, int len) { //return UART_ReceiveByte(BOARD_UART_PORT); - (void) buf; - (void) len; + (void) buf; (void) len; return 0; } int board_uart_write(void const * buf, int len) { //UART_Send(BOARD_UART_PORT, &c, 1, BLOCKING); - (void) buf; - (void) len; + (void) buf; (void) len; return 0; } diff --git a/hw/bsp/metro_m0_express/metro_m0_express.c b/hw/bsp/metro_m0_express/metro_m0_express.c index 17576bb5a..35505add9 100644 --- a/hw/bsp/metro_m0_express/metro_m0_express.c +++ b/hw/bsp/metro_m0_express/metro_m0_express.c @@ -116,6 +116,18 @@ uint32_t board_button_read(void) return gpio_get_pin_level(BUTTON_PIN) ? 0 : 1; } +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) diff --git a/hw/bsp/metro_m4_express/metro_m4_express.c b/hw/bsp/metro_m4_express/metro_m4_express.c index 583a4dfe6..08559e57c 100644 --- a/hw/bsp/metro_m4_express/metro_m4_express.c +++ b/hw/bsp/metro_m4_express/metro_m4_express.c @@ -105,6 +105,18 @@ uint32_t board_button_read(void) return gpio_get_pin_level(BUTTON_PIN) ? 0 : 1; } +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; diff --git a/hw/bsp/ngx4330/ngx4330.c b/hw/bsp/ngx4330/ngx4330.c index 609b4dac6..669180026 100644 --- a/hw/bsp/ngx4330/ngx4330.c +++ b/hw/bsp/ngx4330/ngx4330.c @@ -236,16 +236,14 @@ uint32_t board_button_read(void) int board_uart_read(uint8_t* buf, int len) { //return UART_ReceiveByte(BOARD_UART_PORT); - (void) buf; - (void) len; + (void) buf; (void) len; return 0; } int board_uart_write(void const * buf, int len) { //UART_Send(BOARD_UART_PORT, &c, 1, BLOCKING); - (void) buf; - (void) len; + (void) buf; (void) len; return 0; } diff --git a/hw/bsp/pca10056/pca10056.c b/hw/bsp/pca10056/pca10056.c index fa7d6fc71..31fd5e9be 100644 --- a/hw/bsp/pca10056/pca10056.c +++ b/hw/bsp/pca10056/pca10056.c @@ -154,8 +154,7 @@ uint32_t board_button_read(void) int board_uart_read(uint8_t* buf, int len) { - (void) buf; - (void) len; + (void) buf; (void) len; return 0; // return NRFX_SUCCESS == nrfx_uart_rx(&_uart_id, buf, (size_t) len) ? len : 0; } diff --git a/hw/bsp/pca10059/pca10059.c b/hw/bsp/pca10059/pca10059.c index b18c1d231..69246f4a6 100644 --- a/hw/bsp/pca10059/pca10059.c +++ b/hw/bsp/pca10059/pca10059.c @@ -123,15 +123,13 @@ uint32_t board_button_read(void) int board_uart_read(uint8_t* buf, int len) { - (void) buf; - (void) len; + (void) buf; (void) len; return 0; } int board_uart_write(void const * buf, int len) { - (void) buf; - (void) len; + (void) buf; (void) len; return 0; } diff --git a/hw/bsp/pyboardv11/pyboardv11.c b/hw/bsp/pyboardv11/pyboardv11.c index 85c0eb58f..2d4c732cc 100644 --- a/hw/bsp/pyboardv11/pyboardv11.c +++ b/hw/bsp/pyboardv11/pyboardv11.c @@ -174,6 +174,18 @@ 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) +{ + (void) buf; (void) len; + return 0; +} + #if CFG_TUSB_OS == OPT_OS_NONE volatile uint32_t system_ticks = 0; void SysTick_Handler (void) diff --git a/hw/bsp/stm32f070rbnucleo/stm32f070rbnucleo.c b/hw/bsp/stm32f070rbnucleo/stm32f070rbnucleo.c index 6ee73bcc2..e51eda927 100644 --- a/hw/bsp/stm32f070rbnucleo/stm32f070rbnucleo.c +++ b/hw/bsp/stm32f070rbnucleo/stm32f070rbnucleo.c @@ -109,6 +109,18 @@ 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) +{ + (void) buf; (void) len; + return 0; +} + #if CFG_TUSB_OS == OPT_OS_NONE volatile uint32_t system_ticks = 0; void SysTick_Handler (void) diff --git a/hw/bsp/stm32f072disco/stm32f072disco.c b/hw/bsp/stm32f072disco/stm32f072disco.c index 2faa00db9..46cb09490 100644 --- a/hw/bsp/stm32f072disco/stm32f072disco.c +++ b/hw/bsp/stm32f072disco/stm32f072disco.c @@ -131,6 +131,18 @@ 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) +{ + (void) buf; (void) len; + return 0; +} + #if CFG_TUSB_OS == OPT_OS_NONE volatile uint32_t system_ticks = 0; void SysTick_Handler (void) diff --git a/hw/bsp/stm32f103bluepill/stm32f103bluepill.c b/hw/bsp/stm32f103bluepill/stm32f103bluepill.c index aade44d35..24c898c84 100644 --- a/hw/bsp/stm32f103bluepill/stm32f103bluepill.c +++ b/hw/bsp/stm32f103bluepill/stm32f103bluepill.c @@ -139,6 +139,18 @@ 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) +{ + (void) buf; (void) len; + return 0; +} + #if CFG_TUSB_OS == OPT_OS_NONE volatile uint32_t system_ticks = 0; void SysTick_Handler (void) diff --git a/hw/bsp/stm32f207nucleo/stm32f207nucleo.c b/hw/bsp/stm32f207nucleo/stm32f207nucleo.c index c313ed9f5..de0b4753b 100644 --- a/hw/bsp/stm32f207nucleo/stm32f207nucleo.c +++ b/hw/bsp/stm32f207nucleo/stm32f207nucleo.c @@ -152,6 +152,18 @@ 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) +{ + (void) buf; (void) len; + return 0; +} + #if CFG_TUSB_OS == OPT_OS_NONE volatile uint32_t system_ticks = 0; void SysTick_Handler (void) diff --git a/hw/bsp/stm32f303disco/stm32f303disco.c b/hw/bsp/stm32f303disco/stm32f303disco.c index ae369ed5b..d6d97a531 100644 --- a/hw/bsp/stm32f303disco/stm32f303disco.c +++ b/hw/bsp/stm32f303disco/stm32f303disco.c @@ -143,6 +143,18 @@ 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) +{ + (void) buf; (void) len; + return 0; +} + #if CFG_TUSB_OS == OPT_OS_NONE volatile uint32_t system_ticks = 0; void SysTick_Handler (void) diff --git a/hw/bsp/stm32f407disco/stm32f407disco.c b/hw/bsp/stm32f407disco/stm32f407disco.c index 16cec3e9a..b80c5c1b3 100644 --- a/hw/bsp/stm32f407disco/stm32f407disco.c +++ b/hw/bsp/stm32f407disco/stm32f407disco.c @@ -169,6 +169,18 @@ 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) +{ + (void) buf; (void) len; + return 0; +} + #if CFG_TUSB_OS == OPT_OS_NONE volatile uint32_t system_ticks = 0; void SysTick_Handler (void) diff --git a/hw/bsp/stm32f411disco/stm32f411disco.c b/hw/bsp/stm32f411disco/stm32f411disco.c index ce8753432..d8d79d2f0 100644 --- a/hw/bsp/stm32f411disco/stm32f411disco.c +++ b/hw/bsp/stm32f411disco/stm32f411disco.c @@ -168,6 +168,18 @@ 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) +{ + (void) buf; (void) len; + return 0; +} + #if CFG_TUSB_OS == OPT_OS_NONE volatile uint32_t system_ticks = 0; void SysTick_Handler (void) diff --git a/hw/bsp/stm32f412disco/stm32f412disco.c b/hw/bsp/stm32f412disco/stm32f412disco.c index 0a3ae7365..8d93013c1 100644 --- a/hw/bsp/stm32f412disco/stm32f412disco.c +++ b/hw/bsp/stm32f412disco/stm32f412disco.c @@ -195,6 +195,18 @@ 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) +{ + (void) buf; (void) len; + return 0; +} + #if CFG_TUSB_OS == OPT_OS_NONE volatile uint32_t system_ticks = 0; void SysTick_Handler (void) diff --git a/hw/bsp/stm32l0538disco/stm32l0538disco.c b/hw/bsp/stm32l0538disco/stm32l0538disco.c index a3daaf0d2..6b0222ea0 100644 --- a/hw/bsp/stm32l0538disco/stm32l0538disco.c +++ b/hw/bsp/stm32l0538disco/stm32l0538disco.c @@ -161,6 +161,18 @@ 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) +{ + (void) buf; (void) len; + return 0; +} + #if CFG_TUSB_OS == OPT_OS_NONE volatile uint32_t system_ticks = 0; void SysTick_Handler (void) diff --git a/hw/bsp/stm32l476disco/stm32l476disco.c b/hw/bsp/stm32l476disco/stm32l476disco.c index 8e01814c6..a4cad68bb 100644 --- a/hw/bsp/stm32l476disco/stm32l476disco.c +++ b/hw/bsp/stm32l476disco/stm32l476disco.c @@ -182,6 +182,18 @@ 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) +{ + (void) buf; (void) len; + return 0; +} + #if CFG_TUSB_OS == OPT_OS_NONE volatile uint32_t system_ticks = 0; void SysTick_Handler (void) From ec4ecfa817d6af9d35cf814d6d8d57e8bf71c605 Mon Sep 17 00:00:00 2001 From: Sylvain Munaut Date: Thu, 24 Oct 2019 00:42:42 +0200 Subject: [PATCH 24/32] Add support for DFU Runtime class for devices This is really just a few descriptors and then answering to the request from the host to reboot into DFU mode. That latter part is delegated to the app since this is platform specific. Signed-off-by: Sylvain Munaut --- src/class/dfu/dfu_rt_device.c | 120 ++++++++++++++++++++++++++++++++++ src/class/dfu/dfu_rt_device.h | 77 ++++++++++++++++++++++ src/common/tusb_types.h | 2 + src/device/usbd.c | 14 ++++ src/device/usbd.h | 15 +++++ src/tusb.h | 4 ++ src/tusb_option.h | 4 ++ 7 files changed, 236 insertions(+) create mode 100644 src/class/dfu/dfu_rt_device.c create mode 100644 src/class/dfu/dfu_rt_device.h diff --git a/src/class/dfu/dfu_rt_device.c b/src/class/dfu/dfu_rt_device.c new file mode 100644 index 000000000..59adae7ef --- /dev/null +++ b/src/class/dfu/dfu_rt_device.c @@ -0,0 +1,120 @@ +/* + * The MIT License (MIT) + * + * Copyright (c) 2019 Sylvain Munaut + * + * 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 "tusb_option.h" + +#if (TUSB_OPT_DEVICE_ENABLED && CFG_TUD_DFU_RT) + +#include "dfu_rt_device.h" +#include "device/usbd_pvt.h" + +//--------------------------------------------------------------------+ +// MACRO CONSTANT TYPEDEF +//--------------------------------------------------------------------+ +typedef enum { + DFU_REQUEST_DETACH = 0, + DFU_REQUEST_DNLOAD = 1, + DFU_REQUEST_UPLOAD = 2, + DFU_REQUEST_GETSTATUS = 3, + DFU_REQUEST_CLRSTATUS = 4, + DFU_REQUEST_GETSTATE = 5, + DFU_REQUEST_ABORT = 6, +} dfu_requests_t; + +//--------------------------------------------------------------------+ +// USBD Driver API +//--------------------------------------------------------------------+ +void dfu_rtd_init(void) +{ +} + +void dfu_rtd_reset(uint8_t rhport) +{ + (void) rhport; +} + +bool dfu_rtd_open(uint8_t rhport, tusb_desc_interface_t const * itf_desc, uint16_t *p_length) +{ + (void) rhport; + + // Ensure this is DFU Runtime + TU_ASSERT(itf_desc->bInterfaceSubClass == TUD_DFU_APP_SUBCLASS); + TU_ASSERT(itf_desc->bInterfaceProtocol == DFU_PROTOCOL_RT); + + uint8_t const * p_desc = tu_desc_next( itf_desc ); + (*p_length) = sizeof(tusb_desc_interface_t); + + if ( TUSB_DESC_FUNCTIONAL == tu_desc_type(p_desc) ) + { + (*p_length) += p_desc[DESC_OFFSET_LEN]; + p_desc = tu_desc_next(p_desc); + } + + return true; +} + +bool dfu_rtd_control_complete(uint8_t rhport, tusb_control_request_t const * request) +{ + (void) rhport; + + //------------- Class Specific Request -------------// + TU_VERIFY(request->bmRequestType_bit.type == TUSB_REQ_TYPE_CLASS); + TU_VERIFY(request->bmRequestType_bit.recipient == TUSB_REQ_RCPT_INTERFACE); + + return true; +} + +bool dfu_rtd_control_request(uint8_t rhport, tusb_control_request_t const * request) +{ + (void) rhport; + + //------------- Class Specific Request -------------// + TU_ASSERT(request->bmRequestType_bit.type == TUSB_REQ_TYPE_CLASS); + TU_ASSERT(request->bmRequestType_bit.recipient == TUSB_REQ_RCPT_INTERFACE); + + switch ( request->bRequest ) + { + case DFU_REQUEST_DETACH: + tud_control_status(rhport, request); + tud_dfu_rt_reboot_to_dfu(); + break; + + default: return false; // stall unsupported request + } + + return true; +} + +bool dfu_rtd_xfer_cb(uint8_t rhport, uint8_t ep_addr, xfer_result_t result, uint32_t xferred_bytes) +{ + (void) rhport; + (void) ep_addr; + (void) result; + (void) xferred_bytes; + return true; +} + +#endif diff --git a/src/class/dfu/dfu_rt_device.h b/src/class/dfu/dfu_rt_device.h new file mode 100644 index 000000000..4348a0f3a --- /dev/null +++ b/src/class/dfu/dfu_rt_device.h @@ -0,0 +1,77 @@ +/* + * The MIT License (MIT) + * + * Copyright (c) 2019 Sylvain Munaut + * + * Permission is hereby granted, free of charge, to any person obtaining a copy + * of this software and associated documentation files (the "Software"), to deal + * in the Software without restriction, including without limitation the rights + * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell + * copies of the Software, and to permit persons to whom the Software is + * furnished to do so, subject to the following conditions: + * + * The above copyright notice and this permission notice shall be included in + * all copies or substantial portions of the Software. + * + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR + * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, + * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE + * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER + * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, + * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN + * THE SOFTWARE. + * + * This file is part of the TinyUSB stack. + */ + +#ifndef _TUSB_DFU_RT_DEVICE_H_ +#define _TUSB_DFU_RT_DEVICE_H_ + +#include "common/tusb_common.h" +#include "device/usbd.h" + +#ifdef __cplusplus + extern "C" { +#endif + + +//--------------------------------------------------------------------+ +// Common Definitions +//--------------------------------------------------------------------+ + +// DFU Protocol +typedef enum +{ + DFU_PROTOCOL_RT = 1, + DFU_PROTOCOL_DFU = 2, +} dfu_protocol_type_t; + +// DFU Descriptor Type +typedef enum +{ + DFU_DESC_FUNCTIONAL = 0x21, +} dfu_descriptor_type_t; + + +//--------------------------------------------------------------------+ +// Application Callback API (weak is optional) +//--------------------------------------------------------------------+ + +// Invoked when received new data +TU_ATTR_WEAK void tud_dfu_rt_reboot_to_dfu(void); + +//--------------------------------------------------------------------+ +// Internal Class Driver API +//--------------------------------------------------------------------+ +void dfu_rtd_init(void); +void dfu_rtd_reset(uint8_t rhport); +bool dfu_rtd_open(uint8_t rhport, tusb_desc_interface_t const * itf_desc, uint16_t *p_length); +bool dfu_rtd_control_request(uint8_t rhport, tusb_control_request_t const * request); +bool dfu_rtd_control_complete(uint8_t rhport, tusb_control_request_t const * request); +bool dfu_rtd_xfer_cb(uint8_t rhport, uint8_t ep_addr, xfer_result_t event, uint32_t xferred_bytes); + +#ifdef __cplusplus + } +#endif + +#endif /* _TUSB_DFU_RT_DEVICE_H_ */ diff --git a/src/common/tusb_types.h b/src/common/tusb_types.h index ad42baad7..737b17f76 100644 --- a/src/common/tusb_types.h +++ b/src/common/tusb_types.h @@ -86,6 +86,8 @@ typedef enum TUSB_DESC_BOS = 0x0F, TUSB_DESC_DEVICE_CAPABILITY = 0x10, + TUSB_DESC_FUNCTIONAL = 0x21, + // Class Specific Descriptor TUSB_DESC_CS_DEVICE = 0x21, TUSB_DESC_CS_CONFIGURATION = 0x22, diff --git a/src/device/usbd.c b/src/device/usbd.c index 14e56a9b7..49f28da87 100644 --- a/src/device/usbd.c +++ b/src/device/usbd.c @@ -167,6 +167,20 @@ static usbd_class_driver_t const usbd_class_drivers[] = .sof = NULL }, #endif + + #if CFG_TUD_DFU_RT + { + .class_code = TUD_DFU_APP_CLASS, + //.subclass_code = TUD_DFU_APP_SUBCLASS + .init = dfu_rtd_init, + .reset = dfu_rtd_reset, + .open = dfu_rtd_open, + .control_request = dfu_rtd_control_request, + .control_complete = dfu_rtd_control_complete, + .xfer_cb = dfu_rtd_xfer_cb, + .sof = NULL + }, + #endif }; enum { USBD_CLASS_DRIVER_COUNT = TU_ARRAY_SIZE(usbd_class_drivers) }; diff --git a/src/device/usbd.h b/src/device/usbd.h index f0887f0db..0ad126e94 100644 --- a/src/device/usbd.h +++ b/src/device/usbd.h @@ -304,6 +304,21 @@ TU_ATTR_WEAK bool tud_vendor_control_complete_cb(uint8_t rhport, tusb_control_re /* Endpoint In */\ 7, TUSB_DESC_ENDPOINT, _epin, TUSB_XFER_BULK, U16_TO_U8S_LE(_epsize), 0 +//------------- DFU Runtime -------------// +#define TUD_DFU_APP_CLASS (TUSB_CLASS_APPLICATION_SPECIFIC) +#define TUD_DFU_APP_SUBCLASS 0x01u + +// Length of template descriptr: 18 bytes +#define TUD_DFU_RT_DESC_LEN (9 + 9) + +// DFU runtime descriptor +// Interface number, string index, attributes, detach timeout, transfer size +#define TUD_DFU_RT_DESCRIPTOR(_itfnum, _stridx, _attr, _timeout, _xfer_size) \ + /* Interface */ \ + 9, TUSB_DESC_INTERFACE, _itfnum, 0, 0, TUD_DFU_APP_CLASS, TUD_DFU_APP_SUBCLASS, DFU_PROTOCOL_RT, _stridx, \ + /* Function */ \ + 9, DFU_DESC_FUNCTIONAL, _attr, U16_TO_U8S_LE(_timeout), U16_TO_U8S_LE(_xfer_size), U16_TO_U8S_LE(0x0101) + #ifdef __cplusplus } diff --git a/src/tusb.h b/src/tusb.h index 1a6ff0b10..bf4ad5730 100644 --- a/src/tusb.h +++ b/src/tusb.h @@ -87,6 +87,10 @@ #if CFG_TUD_USBTMC #include "class/usbtmc/usbtmc_device.h" #endif + + #if CFG_TUD_DFU_RT + #include "class/dfu/dfu_rt_device.h" + #endif #endif diff --git a/src/tusb_option.h b/src/tusb_option.h index 6178b2cf9..fc509ae76 100644 --- a/src/tusb_option.h +++ b/src/tusb_option.h @@ -188,6 +188,10 @@ #define CFG_TUD_USBTMC 0 #endif +#ifndef CFG_TUD_DFU_RT + #define CFG_TUD_DFU_RT 0 +#endif + //-------------------------------------------------------------------- // HOST OPTIONS From 03f1a6d9262f27270633b8faaab7b3bdf8437cee Mon Sep 17 00:00:00 2001 From: Sylvain Munaut Date: Mon, 28 Oct 2019 14:38:50 +0100 Subject: [PATCH 25/32] Add example of usage for the DFU Runtime support Signed-off-by: Sylvain Munaut --- examples/device/dfu_rt/Makefile | 12 + examples/device/dfu_rt/src/main.c | 151 ++++++++++++ examples/device/dfu_rt/src/main.h | 5 + examples/device/dfu_rt/src/tusb_config.h | 64 ++++++ examples/device/dfu_rt/src/usb_descriptors.c | 229 +++++++++++++++++++ examples/rules.mk | 1 + 6 files changed, 462 insertions(+) create mode 100644 examples/device/dfu_rt/Makefile create mode 100644 examples/device/dfu_rt/src/main.c create mode 100644 examples/device/dfu_rt/src/main.h create mode 100644 examples/device/dfu_rt/src/tusb_config.h create mode 100644 examples/device/dfu_rt/src/usb_descriptors.c diff --git a/examples/device/dfu_rt/Makefile b/examples/device/dfu_rt/Makefile new file mode 100644 index 000000000..69b633fea --- /dev/null +++ b/examples/device/dfu_rt/Makefile @@ -0,0 +1,12 @@ +include ../../../tools/top.mk +include ../../make.mk + +INC += \ + src \ + $(TOP)/hw \ + +# Example source +EXAMPLE_SOURCE += $(wildcard src/*.c) +SRC_C += $(addprefix $(CURRENT_PATH)/, $(EXAMPLE_SOURCE)) + +include ../../rules.mk diff --git a/examples/device/dfu_rt/src/main.c b/examples/device/dfu_rt/src/main.c new file mode 100644 index 000000000..666d89649 --- /dev/null +++ b/examples/device/dfu_rt/src/main.c @@ -0,0 +1,151 @@ +/* + * The MIT License (MIT) + * + * Copyright (c) 2019 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. + * + */ + +#include +#include +#include + +#include "bsp/board.h" +#include "tusb.h" + +//--------------------------------------------------------------------+ +// MACRO CONSTANT TYPEDEF PROTYPES +//--------------------------------------------------------------------+ + +/* Blink pattern + * - 1000 ms : device should reboot + * - 250 ms : device not mounted + * - 0 ms : device mounted + * - 2500 ms : device is suspended + */ +enum { + BLINK_DFU_MODE = 1000, + BLINK_NOT_MOUNTED = 250, + BLINK_MOUNTED = 0, + BLINK_SUSPENDED = 2500, +}; + +static uint32_t blink_interval_ms = BLINK_NOT_MOUNTED; + +void led_blinking_task(void); + +/*------------- MAIN -------------*/ +int main(void) +{ + board_init(); + + tusb_init(); + + while (1) + { + tud_task(); // tinyusb device task + led_blinking_task(); + } + + return 0; +} + +//--------------------------------------------------------------------+ +// Device callbacks +//--------------------------------------------------------------------+ + +// Invoked when device is mounted +void tud_mount_cb(void) +{ + blink_interval_ms = BLINK_MOUNTED; +} + +// Invoked when device is unmounted +void tud_umount_cb(void) +{ + blink_interval_ms = BLINK_NOT_MOUNTED; +} + +// Invoked when usb bus is suspended +// remote_wakeup_en : if host allow us to perform remote wakeup +// Within 7ms, device must draw an average of current less than 2.5 mA from bus +void tud_suspend_cb(bool remote_wakeup_en) +{ + (void) remote_wakeup_en; + blink_interval_ms = BLINK_SUSPENDED; +} + +// Invoked when usb bus is resumed +void tud_resume_cb(void) +{ + blink_interval_ms = BLINK_MOUNTED; +} + +// Invoked on DFU_DETACH request to reboot to the bootloader +void tud_dfu_rt_reboot_to_dfu(void) +{ + blink_interval_ms = BLINK_DFU_MODE; +} + + +//--------------------------------------------------------------------+ +// BLINKING TASK + Indicator pulse +//--------------------------------------------------------------------+ + + +volatile uint8_t doPulse = false; +// called from USB context +void led_indicator_pulse(void) { + doPulse = true; +} + +void led_blinking_task(void) +{ + static uint32_t start_ms = 0; + static bool led_state = false; + if(blink_interval_ms == BLINK_MOUNTED) // Mounted + { + if(doPulse) + { + led_state = true; + board_led_write(true); + start_ms = board_millis(); + doPulse = false; + } + else if (led_state == true) + { + if ( board_millis() - start_ms < 750) //Spec says blink must be between 500 and 1000 ms. + { + return; // not enough time + } + led_state = false; + board_led_write(false); + } + } + else + { + // Blink every interval ms + if ( board_millis() - start_ms < blink_interval_ms) return; // not enough time + start_ms += blink_interval_ms; + + board_led_write(led_state); + led_state = 1 - led_state; // toggle + } +} diff --git a/examples/device/dfu_rt/src/main.h b/examples/device/dfu_rt/src/main.h new file mode 100644 index 000000000..673247ec7 --- /dev/null +++ b/examples/device/dfu_rt/src/main.h @@ -0,0 +1,5 @@ +#ifndef MAIN_H +#define MAIN_H +void led_indicator_pulse(void); + +#endif diff --git a/examples/device/dfu_rt/src/tusb_config.h b/examples/device/dfu_rt/src/tusb_config.h new file mode 100644 index 000000000..b4f7a5562 --- /dev/null +++ b/examples/device/dfu_rt/src/tusb_config.h @@ -0,0 +1,64 @@ +/* + * tusb_config.h + * + * Created on: Oct 28, 2019 + * Author: Sylvain Munaut + */ + +#ifndef TUSB_CONFIG_H_ +#define TUSB_CONFIG_H_ + +#ifdef __cplusplus + extern "C" { +#endif + +//-------------------------------------------------------------------- +// COMMON CONFIGURATION +//-------------------------------------------------------------------- + +// defined by compiler flags for flexibility +#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 +#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 +// #define CFG_TUSB_DEBUG 0 + +/* USB DMA on some MCUs can only access a specific SRAM region with restriction on alignment. + * Tinyusb use follows macros to declare transferring memory so that they can be put + * into those specific section. + * e.g + * - CFG_TUSB_MEM SECTION : __attribute__ (( section(".usb_ram") )) + * - CFG_TUSB_MEM_ALIGN : __attribute__ ((aligned(4))) + */ +#ifndef CFG_TUSB_MEM_SECTION +#define CFG_TUSB_MEM_SECTION +#endif + +#ifndef CFG_TUSB_MEM_ALIGN +#define CFG_TUSB_MEM_ALIGN __attribute__ ((aligned(4))) +#endif + +//-------------------------------------------------------------------- +// DEVICE CONFIGURATION +//-------------------------------------------------------------------- + +#define CFG_TUD_ENDPOINT0_SIZE 64 + +//------------- CLASS -------------// + +#define CFG_TUD_DFU_RT 1 + +#ifdef __cplusplus + } +#endif + +#endif /* TUSB_CONFIG_H_ */ diff --git a/examples/device/dfu_rt/src/usb_descriptors.c b/examples/device/dfu_rt/src/usb_descriptors.c new file mode 100644 index 000000000..0c7081245 --- /dev/null +++ b/examples/device/dfu_rt/src/usb_descriptors.c @@ -0,0 +1,229 @@ +/* + * The MIT License (MIT) + * + * Copyright (c) 2019 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. + * + */ + +#include "tusb.h" +#include "class/dfu/dfu_rt_device.h" + +/* A combination of interfaces must have a unique product id, since PC will save device driver after the first plug. + * Same VID/PID with different interface e.g MSC (first), then CDC (later) will possibly cause system error on PC. + * + * Auto ProductID layout's Bitmap: + * [MSB] HID | MSC | CDC [LSB] + */ +#define _PID_MAP(itf, n) ( (CFG_TUD_##itf) << (n) ) +#define USB_PID (0x4000 | _PID_MAP(CDC, 0) | _PID_MAP(MSC, 1) | _PID_MAP(HID, 2) | \ + _PID_MAP(MIDI, 3) | _PID_MAP(VENDOR, 4) ) + +//--------------------------------------------------------------------+ +// Device Descriptors +//--------------------------------------------------------------------+ +tusb_desc_device_t const desc_device = +{ + .bLength = sizeof(tusb_desc_device_t), + .bDescriptorType = TUSB_DESC_DEVICE, + .bcdUSB = 0x0200, + + #if CFG_TUD_CDC + // Use Interface Association Descriptor (IAD) for CDC + // As required by USB Specs IAD's subclass must be common class (2) and protocol must be IAD (1) + .bDeviceClass = TUSB_CLASS_MISC, + .bDeviceSubClass = MISC_SUBCLASS_COMMON, + .bDeviceProtocol = MISC_PROTOCOL_IAD, + #else + .bDeviceClass = 0x00, + .bDeviceSubClass = 0x00, + .bDeviceProtocol = 0x00, + #endif + + .bMaxPacketSize0 = CFG_TUD_ENDPOINT0_SIZE, + + .idVendor = 0xCafe, + .idProduct = USB_PID, + .bcdDevice = 0x0100, + + .iManufacturer = 0x01, + .iProduct = 0x02, + .iSerialNumber = 0x03, + + .bNumConfigurations = 0x01 +}; + +// Invoked when received GET DEVICE DESCRIPTOR +// Application return pointer to descriptor +uint8_t const * tud_descriptor_device_cb(void) +{ + return (uint8_t const *) &desc_device; +} + +//--------------------------------------------------------------------+ +// HID Report Descriptor +//--------------------------------------------------------------------+ +#if CFG_TUD_HID + +uint8_t const desc_hid_report[] = +{ + TUD_HID_REPORT_DESC_KEYBOARD( HID_REPORT_ID(REPORT_ID_KEYBOARD), ), + TUD_HID_REPORT_DESC_MOUSE ( HID_REPORT_ID(REPORT_ID_MOUSE), ) +}; + +// Invoked when received GET HID REPORT DESCRIPTOR +// Application return pointer to descriptor +// Descriptor contents must exist long enough for transfer to complete +uint8_t const * tud_hid_descriptor_report_cb(void) +{ + return desc_hid_report; +} + +#endif + +//--------------------------------------------------------------------+ +// Configuration Descriptor +//--------------------------------------------------------------------+ + +enum +{ +#if CFG_TUD_CDC + ITF_NUM_CDC = 0, + ITF_NUM_CDC_DATA, +#endif + +#if CFG_TUD_MSC + ITF_NUM_MSC, +#endif + +#if CFG_TUD_HID + ITF_NUM_HID, +#endif + +#if CFG_TUD_DFU_RT + ITF_NUM_DFU_RT, +#endif + + ITF_NUM_TOTAL +}; + + +#define CONFIG_TOTAL_LEN (TUD_CONFIG_DESC_LEN + CFG_TUD_CDC*TUD_CDC_DESC_LEN + CFG_TUD_MSC*TUD_MSC_DESC_LEN + \ + CFG_TUD_HID*TUD_HID_DESC_LEN + (CFG_TUD_DFU_RT)*TUD_DFU_RT_DESC_LEN) + +#if CFG_TUSB_MCU == OPT_MCU_LPC175X_6X || CFG_TUSB_MCU == OPT_MCU_LPC177X_8X || CFG_TUSB_MCU == OPT_MCU_LPC40XX + // LPC 17xx and 40xx endpoint type (bulk/interrupt/iso) are fixed by its number + // 0 control, 1 In, 2 Bulk, 3 Iso, 4 In etc ... + // Note: since CDC EP ( 1 & 2), HID (4) are spot-on, thus we only need to force + // endpoint number for MSC to 5 + #define EPNUM_MSC 0x05 +#else + #define EPNUM_MSC 0x03 +#endif + + +uint8_t const desc_configuration[] = +{ + // Interface count, string index, total length, attribute, power in mA + TUD_CONFIG_DESCRIPTOR(ITF_NUM_TOTAL, 0, CONFIG_TOTAL_LEN, TUSB_DESC_CONFIG_ATT_REMOTE_WAKEUP, 100), + +#if CFG_TUD_CDC + // Interface number, string index, EP notification address and size, EP data address (out, in) and size. + TUD_CDC_DESCRIPTOR(ITF_NUM_CDC, 1, 0x81, 8, 0x02, 0x82, 64), +#endif + +#if CFG_TUD_MSC + // Interface number, string index, EP Out & EP In address, EP size + TUD_MSC_DESCRIPTOR(ITF_NUM_MSC, 5, EPNUM_MSC, 0x80 | EPNUM_MSC, (CFG_TUSB_RHPORT0_MODE & OPT_MODE_HIGH_SPEED) ? 512 : 64), +#endif + +#if CFG_TUD_HID + // Interface number, string index, protocol, report descriptor len, EP In address, size & polling interval + TUD_HID_DESCRIPTOR(ITF_NUM_HID, 6, HID_PROTOCOL_NONE, sizeof(desc_hid_report), 0x84, 16, 10), +#endif + +#if CFG_TUD_DFU_RT + // Interface number, string index, attributes, detach timeout, transfer size */ + TUD_DFU_RT_DESCRIPTOR(ITF_NUM_DFU_RT, 7, 0x0d, 1000, 4096), +#endif +}; + + +// Invoked when received GET CONFIGURATION DESCRIPTOR +// Application return pointer to descriptor +// Descriptor contents must exist long enough for transfer to complete +uint8_t const * tud_descriptor_configuration_cb(uint8_t index) +{ + (void) index; // for multiple configurations + return desc_configuration; +} + +//--------------------------------------------------------------------+ +// String Descriptors +//--------------------------------------------------------------------+ + +// array of pointer to string descriptors +char const* string_desc_arr [] = +{ + (const char[]) { 0x09, 0x04 }, // 0: is supported language is English (0x0409) + "TinyUSB", // 1: Manufacturer + "TinyUSB Device", // 2: Product + "123456", // 3: Serials, should use chip ID + "TinyUSB DFU runtime", // 4: DFU runtime +}; + +static uint16_t _desc_str[32]; + +// Invoked when received GET STRING DESCRIPTOR request +// Application return pointer to descriptor, whose contents must exist long enough for transfer to complete +uint16_t const* tud_descriptor_string_cb(uint8_t index) +{ + size_t chr_count; + + if ( index == 0) + { + memcpy(&_desc_str[1], string_desc_arr[0], 2); + chr_count = 1; + } + else + { + // Convert ASCII string into UTF-16 + + if ( !(index < sizeof(string_desc_arr)/sizeof(string_desc_arr[0])) ) return NULL; + + const char* str = string_desc_arr[index]; + + // Cap at max char + chr_count = strlen(str); + if ( chr_count > 31 ) { + chr_count = 31; + } + + for(uint8_t i=0; i Date: Wed, 30 Oct 2019 11:35:25 +0700 Subject: [PATCH 26/32] move dcd event helper to be dcd.h as inline function --- src/device/dcd.h | 47 +++++++++++++++++++++++++++++++++++++++-------- src/device/usbd.c | 28 ---------------------------- 2 files changed, 39 insertions(+), 36 deletions(-) diff --git a/src/device/dcd.h b/src/device/dcd.h index c417ee4be..444b4a6f9 100644 --- a/src/device/dcd.h +++ b/src/device/dcd.h @@ -79,7 +79,7 @@ typedef struct TU_ATTR_ALIGNED(4) }; } dcd_event_t; -TU_VERIFY_STATIC(sizeof(dcd_event_t) <= 12, "size is not correct"); +//TU_VERIFY_STATIC(sizeof(dcd_event_t) <= 12, "size is not correct"); /*------------------------------------------------------------------*/ /* Device API @@ -119,20 +119,51 @@ void dcd_edpt_stall (uint8_t rhport, uint8_t ep_addr); // clear stall, data toggle is also reset to DATA0 void dcd_edpt_clear_stall (uint8_t rhport, uint8_t ep_addr); -/*------------------------------------------------------------------*/ -/* Event Function - * Called by DCD to notify device stack - *------------------------------------------------------------------*/ +//--------------------------------------------------------------------+ +// Event API +//--------------------------------------------------------------------+ + +// Called by DCD to notify device stack void dcd_event_handler(dcd_event_t const * event, bool in_isr); // helper to send bus signal event -void dcd_event_bus_signal (uint8_t rhport, dcd_eventid_t eid, bool in_isr); +static inline void dcd_event_bus_signal (uint8_t rhport, dcd_eventid_t eid, bool in_isr); // helper to send setup received -void dcd_event_setup_received(uint8_t rhport, uint8_t const * setup, bool in_isr); +static inline void dcd_event_setup_received(uint8_t rhport, uint8_t const * setup, bool in_isr); // helper to send transfer complete event -void dcd_event_xfer_complete (uint8_t rhport, uint8_t ep_addr, uint32_t xferred_bytes, uint8_t result, bool in_isr); +static inline void dcd_event_xfer_complete (uint8_t rhport, uint8_t ep_addr, uint32_t xferred_bytes, uint8_t result, bool in_isr); + + +//--------------------------------------------------------------------+ +// Inline helper +//--------------------------------------------------------------------+ + +static inline 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_handler(&event, in_isr); +} + +static inline void dcd_event_setup_received(uint8_t rhport, uint8_t const * setup, bool in_isr) +{ + dcd_event_t event = { .rhport = rhport, .event_id = DCD_EVENT_SETUP_RECEIVED }; + memcpy(&event.setup_received, setup, 8); + + dcd_event_handler(&event, in_isr); +} + +static inline void dcd_event_xfer_complete (uint8_t rhport, uint8_t ep_addr, uint32_t xferred_bytes, uint8_t result, bool in_isr) +{ + dcd_event_t event = { .rhport = rhport, .event_id = DCD_EVENT_XFER_COMPLETE }; + + event.xfer_complete.ep_addr = ep_addr; + event.xfer_complete.len = xferred_bytes; + event.xfer_complete.result = result; + + dcd_event_handler(&event, in_isr); +} #ifdef __cplusplus } diff --git a/src/device/usbd.c b/src/device/usbd.c index f2becab95..3e6bf68c9 100644 --- a/src/device/usbd.c +++ b/src/device/usbd.c @@ -870,34 +870,6 @@ void dcd_event_handler(dcd_event_t const * event, bool in_isr) } } -// helper to send bus signal event -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_handler(&event, in_isr); -} - -// helper to send setup received -void dcd_event_setup_received(uint8_t rhport, uint8_t const * setup, bool in_isr) -{ - dcd_event_t event = { .rhport = rhport, .event_id = DCD_EVENT_SETUP_RECEIVED }; - memcpy(&event.setup_received, setup, 8); - - dcd_event_handler(&event, in_isr); -} - -// helper to send transfer complete event -void dcd_event_xfer_complete (uint8_t rhport, uint8_t ep_addr, uint32_t xferred_bytes, uint8_t result, bool in_isr) -{ - dcd_event_t event = { .rhport = rhport, .event_id = DCD_EVENT_XFER_COMPLETE }; - - event.xfer_complete.ep_addr = ep_addr; - event.xfer_complete.len = xferred_bytes; - event.xfer_complete.result = result; - - dcd_event_handler(&event, in_isr); -} - //--------------------------------------------------------------------+ // Helper //--------------------------------------------------------------------+ From 16665672a45c4f85cb2e1a47873825f2b48fcf1a Mon Sep 17 00:00:00 2001 From: hathach Date: Wed, 30 Oct 2019 12:24:07 +0700 Subject: [PATCH 27/32] initally adding test_usbd.c --- src/device/dcd.h | 2 +- test/project.yml | 5 ++- test/test/support/tusb_config.h | 11 +++--- test/test/test_usbd.c | 68 +++++++++++++++++++++++++++++++++ 4 files changed, 77 insertions(+), 9 deletions(-) create mode 100644 test/test/test_usbd.c diff --git a/src/device/dcd.h b/src/device/dcd.h index 444b4a6f9..9fa98c669 100644 --- a/src/device/dcd.h +++ b/src/device/dcd.h @@ -124,7 +124,7 @@ void dcd_edpt_clear_stall (uint8_t rhport, uint8_t ep_addr); //--------------------------------------------------------------------+ // Called by DCD to notify device stack -void dcd_event_handler(dcd_event_t const * event, bool in_isr); +extern void dcd_event_handler(dcd_event_t const * event, bool in_isr); // helper to send bus signal event static inline void dcd_event_bus_signal (uint8_t rhport, dcd_eventid_t eid, bool in_isr); diff --git a/test/project.yml b/test/project.yml index 403aa0119..cf29c3b04 100644 --- a/test/project.yml +++ b/test/project.yml @@ -9,6 +9,7 @@ :use_exceptions: TRUE :use_test_preprocessor: TRUE :use_auxiliary_dependencies: TRUE + :use_deep_dependencies: TRUE :build_root: _build # :release_build: TRUE :test_file_prefix: test_ @@ -41,10 +42,10 @@ :commmon: &common_defines [] :test: - *common_defines - - TEST + - _TEST_ :test_preprocess: - *common_defines - - TEST + - _TEST_ :cmock: :mock_prefix: mock_ diff --git a/test/test/support/tusb_config.h b/test/test/support/tusb_config.h index b82a09a23..bfe5bf9e9 100644 --- a/test/test/support/tusb_config.h +++ b/test/test/support/tusb_config.h @@ -73,12 +73,11 @@ #define CFG_TUD_ENDOINT0_SIZE 64 //------------- CLASS -------------// -#define CFG_TUD_CDC 1 -#define CFG_TUD_MSC 1 -#define CFG_TUD_HID 1 - -#define CFG_TUD_MIDI 1 -#define CFG_TUD_VENDOR 1 +#define CFG_TUD_CDC 0 +#define CFG_TUD_MSC 0 +#define CFG_TUD_HID 0 +#define CFG_TUD_MIDI 0 +#define CFG_TUD_VENDOR 0 //------------- CDC -------------// diff --git a/test/test/test_usbd.c b/test/test/test_usbd.c new file mode 100644 index 000000000..8c29ee853 --- /dev/null +++ b/test/test/test_usbd.c @@ -0,0 +1,68 @@ +/* + * The MIT License (MIT) + * + * Copyright (c) 2019 hathach for Adafruit Industries + * + * 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. + */ + +#include "unity.h" + +// Files to test +#include "tusb_fifo.h" +#include "tusb.h" +#include "usbd.h" +TEST_FILE("usbd_control.c") + +// Mock File +#include "mock_dcd.h" + +//--------------------------------------------------------------------+ +// MACRO TYPEDEF CONSTANT ENUM DECLARATION +//--------------------------------------------------------------------+ + +uint8_t const * tud_descriptor_device_cb(void) +{ + return NULL; +} + +uint8_t const * tud_descriptor_configuration_cb(uint8_t index) +{ + return NULL; +} + +uint16_t const* tud_descriptor_string_cb(uint8_t index) +{ + return NULL; +} + +//------------- IMPLEMENTATION -------------// +void setUp(void) +{ + +} + +void tearDown(void) +{ +} + +void test_ok(void) +{ + +} From 8f2e70756b582f75d47257c8f116449babb5059d Mon Sep 17 00:00:00 2001 From: hathach Date: Wed, 30 Oct 2019 16:19:47 +0700 Subject: [PATCH 28/32] added firs usbd test with get device descriptor --- test/project.yml | 1 + test/test/{ => test_usbd}/test_usbd.c | 61 +++++++++++++++++++++++++-- 2 files changed, 58 insertions(+), 4 deletions(-) rename test/test/{ => test_usbd}/test_usbd.c (50%) diff --git a/test/project.yml b/test/project.yml index cf29c3b04..8ceaf63ce 100644 --- a/test/project.yml +++ b/test/project.yml @@ -54,6 +54,7 @@ :plugins: - :ignore - :callback + - :array :treat_as: uint8: HEX8 uint16: HEX16 diff --git a/test/test/test_usbd.c b/test/test/test_usbd/test_usbd.c similarity index 50% rename from test/test/test_usbd.c rename to test/test/test_usbd/test_usbd.c index 8c29ee853..fe8adf5d8 100644 --- a/test/test/test_usbd.c +++ b/test/test/test_usbd/test_usbd.c @@ -29,6 +29,7 @@ #include "tusb.h" #include "usbd.h" TEST_FILE("usbd_control.c") +//TEST_FILE("usb_descriptors.c") // Mock File #include "mock_dcd.h" @@ -37,13 +38,41 @@ TEST_FILE("usbd_control.c") // MACRO TYPEDEF CONSTANT ENUM DECLARATION //--------------------------------------------------------------------+ +uint8_t const rhport = 0; + +tusb_desc_device_t const desc_device = +{ + .bLength = sizeof(tusb_desc_device_t), + .bDescriptorType = TUSB_DESC_DEVICE, + .bcdUSB = 0x0200, + + // Use Interface Association Descriptor (IAD) for CDC + // As required by USB Specs IAD's subclass must be common class (2) and protocol must be IAD (1) + .bDeviceClass = TUSB_CLASS_MISC, + .bDeviceSubClass = MISC_SUBCLASS_COMMON, + .bDeviceProtocol = MISC_PROTOCOL_IAD, + + .bMaxPacketSize0 = CFG_TUD_ENDPOINT0_SIZE, + + .idVendor = 0xCafe, + .idProduct = 0xCafe, + .bcdDevice = 0x0100, + + .iManufacturer = 0x01, + .iProduct = 0x02, + .iSerialNumber = 0x03, + + .bNumConfigurations = 0x01 +}; + uint8_t const * tud_descriptor_device_cb(void) { - return NULL; + return (uint8_t const *) &desc_device; } uint8_t const * tud_descriptor_configuration_cb(uint8_t index) { + TEST_FAIL(); return NULL; } @@ -52,17 +81,41 @@ uint16_t const* tud_descriptor_string_cb(uint8_t index) return NULL; } -//------------- IMPLEMENTATION -------------// void setUp(void) { - + dcd_init_Expect(rhport); + dcd_int_enable_Expect(rhport); + tusb_init(); } void tearDown(void) { } -void test_ok(void) +//--------------------------------------------------------------------+ +// +//--------------------------------------------------------------------+ +void test_usbd_get_device_descriptor(void) { + tusb_control_request_t request = + { + .bmRequestType = 0x80, + .bRequest = TUSB_REQ_GET_DESCRIPTOR, + .wValue = (TUSB_DESC_DEVICE << 8), + .wIndex = 0x0000, + .wLength = 64 + }; + dcd_int_disable_Expect(rhport); + dcd_int_enable_Expect(rhport); + dcd_event_setup_received(rhport, (uint8_t*) &request, false); + + dcd_int_disable_Expect(rhport); + dcd_int_enable_Expect(rhport); + + dcd_edpt_xfer_ExpectWithArrayAndReturn(rhport, 0x80, (uint8_t*)&desc_device, sizeof(tusb_desc_device_t), sizeof(tusb_desc_device_t), true); + + dcd_int_disable_Expect(rhport); + dcd_int_enable_Expect(rhport); + tud_task(); } From 58089934024c3869f90159641e2b569d663ce826 Mon Sep 17 00:00:00 2001 From: hathach Date: Wed, 30 Oct 2019 23:22:07 +0700 Subject: [PATCH 29/32] add 2nd test, but failed due to lack of tusb_teardown() --- test/test/test_usbd/test_usbd.c | 53 +++++++++++++++++++++------------ 1 file changed, 34 insertions(+), 19 deletions(-) diff --git a/test/test/test_usbd/test_usbd.c b/test/test/test_usbd/test_usbd.c index fe8adf5d8..0e746d371 100644 --- a/test/test/test_usbd/test_usbd.c +++ b/test/test/test_usbd/test_usbd.c @@ -65,9 +65,23 @@ tusb_desc_device_t const desc_device = .bNumConfigurations = 0x01 }; +tusb_control_request_t const req_get_desc_device = +{ + .bmRequestType = 0x80, + .bRequest = TUSB_REQ_GET_DESCRIPTOR, + .wValue = (TUSB_DESC_DEVICE << 8), + .wIndex = 0x0000, + .wLength = 64 +}; + +//--------------------------------------------------------------------+ +// +//--------------------------------------------------------------------+ +uint8_t const * ptr_desc_device; + uint8_t const * tud_descriptor_device_cb(void) { - return (uint8_t const *) &desc_device; + return ptr_desc_device; } uint8_t const * tud_descriptor_configuration_cb(uint8_t index) @@ -84,8 +98,13 @@ uint16_t const* tud_descriptor_string_cb(uint8_t index) void setUp(void) { dcd_init_Expect(rhport); - dcd_int_enable_Expect(rhport); + + dcd_int_disable_Ignore(); + dcd_int_enable_Ignore(); + tusb_init(); + + ptr_desc_device = (uint8_t const *) &desc_device; } void tearDown(void) @@ -97,25 +116,21 @@ void tearDown(void) //--------------------------------------------------------------------+ void test_usbd_get_device_descriptor(void) { - tusb_control_request_t request = - { - .bmRequestType = 0x80, - .bRequest = TUSB_REQ_GET_DESCRIPTOR, - .wValue = (TUSB_DESC_DEVICE << 8), - .wIndex = 0x0000, - .wLength = 64 - }; - - dcd_int_disable_Expect(rhport); - dcd_int_enable_Expect(rhport); - dcd_event_setup_received(rhport, (uint8_t*) &request, false); - - dcd_int_disable_Expect(rhport); - dcd_int_enable_Expect(rhport); + dcd_event_setup_received(rhport, (uint8_t*) &req_get_desc_device, false); dcd_edpt_xfer_ExpectWithArrayAndReturn(rhport, 0x80, (uint8_t*)&desc_device, sizeof(tusb_desc_device_t), sizeof(tusb_desc_device_t), true); - dcd_int_disable_Expect(rhport); - dcd_int_enable_Expect(rhport); tud_task(); } + +void test_usbd_get_device_descriptor_null(void) +{ + ptr_desc_device = NULL; + +// dcd_event_setup_received(rhport, (uint8_t*) &req_get_desc_device, false); +// +// dcd_edpt_stall_Expect(rhport, 0); +// dcd_edpt_stall_Expect(rhport, 0x80); +// +// tud_task(); +} From a0002cc709bd39049d3effbe9a59b62dc198f79d Mon Sep 17 00:00:00 2001 From: hathach Date: Wed, 30 Oct 2019 23:26:34 +0700 Subject: [PATCH 30/32] rename usbd_init() to tud_init() --- src/device/usbd.c | 2 +- src/device/usbd.h | 3 +++ src/device/usbd_pvt.h | 2 -- src/tusb.c | 2 +- 4 files changed, 5 insertions(+), 4 deletions(-) diff --git a/src/device/usbd.c b/src/device/usbd.c index 3e6bf68c9..62f6e9922 100644 --- a/src/device/usbd.c +++ b/src/device/usbd.c @@ -276,7 +276,7 @@ bool tud_remote_wakeup(void) //--------------------------------------------------------------------+ // USBD Task //--------------------------------------------------------------------+ -bool usbd_init (void) +bool tud_init (void) { TU_LOG2("USBD init\r\n"); diff --git a/src/device/usbd.h b/src/device/usbd.h index f0887f0db..e340215fe 100644 --- a/src/device/usbd.h +++ b/src/device/usbd.h @@ -41,6 +41,9 @@ // Application API //--------------------------------------------------------------------+ +// Init device stack +bool tud_init (void); + // Task function should be called in main/rtos loop void tud_task (void); diff --git a/src/device/usbd_pvt.h b/src/device/usbd_pvt.h index 892680142..b9947044b 100644 --- a/src/device/usbd_pvt.h +++ b/src/device/usbd_pvt.h @@ -33,8 +33,6 @@ extern "C" { #endif -bool usbd_init (void); - //--------------------------------------------------------------------+ // USBD Endpoint API //--------------------------------------------------------------------+ diff --git a/src/tusb.c b/src/tusb.c index 271b35f1e..7a1e73ec7 100644 --- a/src/tusb.c +++ b/src/tusb.c @@ -47,7 +47,7 @@ bool tusb_init(void) #endif #if TUSB_OPT_DEVICE_ENABLED - TU_ASSERT ( usbd_init() ); // init device stack + TU_ASSERT ( tud_init() ); // init device stack #endif _initialized = true; From 0653e1d1f5a82dc6713f4175fd12c62e353e4628 Mon Sep 17 00:00:00 2001 From: hathach Date: Wed, 30 Oct 2019 23:34:09 +0700 Subject: [PATCH 31/32] fix 2nd test when tud_descriptor_device_cb() return NULL --- test/test/test_usbd/test_usbd.c | 20 +++++++++++--------- 1 file changed, 11 insertions(+), 9 deletions(-) diff --git a/test/test/test_usbd/test_usbd.c b/test/test/test_usbd/test_usbd.c index 0e746d371..d4b3f806b 100644 --- a/test/test/test_usbd/test_usbd.c +++ b/test/test/test_usbd/test_usbd.c @@ -97,12 +97,14 @@ uint16_t const* tud_descriptor_string_cb(uint8_t index) void setUp(void) { - dcd_init_Expect(rhport); - dcd_int_disable_Ignore(); dcd_int_enable_Ignore(); - tusb_init(); + if ( !tusb_inited() ) + { + dcd_init_Expect(rhport); + tusb_init(); + } ptr_desc_device = (uint8_t const *) &desc_device; } @@ -127,10 +129,10 @@ void test_usbd_get_device_descriptor_null(void) { ptr_desc_device = NULL; -// dcd_event_setup_received(rhport, (uint8_t*) &req_get_desc_device, false); -// -// dcd_edpt_stall_Expect(rhport, 0); -// dcd_edpt_stall_Expect(rhport, 0x80); -// -// tud_task(); + dcd_event_setup_received(rhport, (uint8_t*) &req_get_desc_device, false); + + dcd_edpt_stall_Expect(rhport, 0); + dcd_edpt_stall_Expect(rhport, 0x80); + + tud_task(); } From e69d2a4a834b975f957fc5341fe4d08cf706adb6 Mon Sep 17 00:00:00 2001 From: hathach Date: Wed, 30 Oct 2019 23:41:42 +0700 Subject: [PATCH 32/32] move test_usbd around --- test/test/{test_usbd => device/usbd}/test_usbd.c | 0 1 file changed, 0 insertions(+), 0 deletions(-) rename test/test/{test_usbd => device/usbd}/test_usbd.c (100%) diff --git a/test/test/test_usbd/test_usbd.c b/test/test/device/usbd/test_usbd.c similarity index 100% rename from test/test/test_usbd/test_usbd.c rename to test/test/device/usbd/test_usbd.c