From e9092708439e32b8eb68ca8302bb409628364ace Mon Sep 17 00:00:00 2001 From: hathach Date: Fri, 19 Jul 2019 20:37:38 +0700 Subject: [PATCH 1/9] rename bsp of stm32 board --- examples/device/cdc_msc_hid/ses/stm32f4/stm32f4.emProject | 8 ++++---- .../STM32F303VCTx_FLASH.ld | 0 hw/bsp/{stm32f303disc => stm32f303disco}/board.mk | 4 ++-- .../board_stm32f303disco.c} | 0 .../stm32f3xx_hal_conf.h | 0 .../STM32F407VGTx_FLASH.ld | 0 hw/bsp/{stm32f407g_disc1 => stm32f407disco}/board.mk | 2 +- .../board_stm32f407disco.c} | 0 hw/mcu/st/README.md | 2 +- 9 files changed, 8 insertions(+), 8 deletions(-) rename hw/bsp/{stm32f303disc => stm32f303disco}/STM32F303VCTx_FLASH.ld (100%) rename hw/bsp/{stm32f303disc => stm32f303disco}/board.mk (93%) rename hw/bsp/{stm32f303disc/board_stm32f303disc.c => stm32f303disco/board_stm32f303disco.c} (100%) rename hw/bsp/{stm32f303disc => stm32f303disco}/stm32f3xx_hal_conf.h (100%) rename hw/bsp/{stm32f407g_disc1 => stm32f407disco}/STM32F407VGTx_FLASH.ld (100%) rename hw/bsp/{stm32f407g_disc1 => stm32f407disco}/board.mk (93%) rename hw/bsp/{stm32f407g_disc1/board_stm32f407g_disc1.c => stm32f407disco/board_stm32f407disco.c} (100%) diff --git a/examples/device/cdc_msc_hid/ses/stm32f4/stm32f4.emProject b/examples/device/cdc_msc_hid/ses/stm32f4/stm32f4.emProject index 83067fd0..6f6690d2 100644 --- a/examples/device/cdc_msc_hid/ses/stm32f4/stm32f4.emProject +++ b/examples/device/cdc_msc_hid/ses/stm32f4/stm32f4.emProject @@ -61,8 +61,8 @@ recurse="No" /> - - + + @@ -76,11 +76,11 @@ diff --git a/hw/bsp/stm32f303disc/STM32F303VCTx_FLASH.ld b/hw/bsp/stm32f303disco/STM32F303VCTx_FLASH.ld similarity index 100% rename from hw/bsp/stm32f303disc/STM32F303VCTx_FLASH.ld rename to hw/bsp/stm32f303disco/STM32F303VCTx_FLASH.ld diff --git a/hw/bsp/stm32f303disc/board.mk b/hw/bsp/stm32f303disco/board.mk similarity index 93% rename from hw/bsp/stm32f303disc/board.mk rename to hw/bsp/stm32f303disco/board.mk index 76922a46..7a493c24 100644 --- a/hw/bsp/stm32f303disc/board.mk +++ b/hw/bsp/stm32f303disco/board.mk @@ -10,7 +10,7 @@ CFLAGS += \ -nostdlib -nostartfiles # All source paths should be relative to the top level. -LD_FILE = hw/bsp/stm32f303disc/STM32F303VCTx_FLASH.ld +LD_FILE = hw/bsp/stm32f303disco/STM32F303VCTx_FLASH.ld SRC_C += \ hw/mcu/st/system-init/system_stm32f3xx.c \ @@ -23,7 +23,7 @@ SRC_S += \ hw/mcu/st/startup/stm32f3/startup_stm32f303xc.s INC += \ - $(TOP)/hw/bsp/stm32f303disc \ + $(TOP)/hw/bsp/stm32f303disco \ $(TOP)/hw/mcu/st/cmsis \ $(TOP)/hw/mcu/st/stm32lib/CMSIS/STM32F3xx/Include \ $(TOP)/hw/mcu/st/stm32lib/STM32F3xx_HAL_Driver/Inc diff --git a/hw/bsp/stm32f303disc/board_stm32f303disc.c b/hw/bsp/stm32f303disco/board_stm32f303disco.c similarity index 100% rename from hw/bsp/stm32f303disc/board_stm32f303disc.c rename to hw/bsp/stm32f303disco/board_stm32f303disco.c diff --git a/hw/bsp/stm32f303disc/stm32f3xx_hal_conf.h b/hw/bsp/stm32f303disco/stm32f3xx_hal_conf.h similarity index 100% rename from hw/bsp/stm32f303disc/stm32f3xx_hal_conf.h rename to hw/bsp/stm32f303disco/stm32f3xx_hal_conf.h diff --git a/hw/bsp/stm32f407g_disc1/STM32F407VGTx_FLASH.ld b/hw/bsp/stm32f407disco/STM32F407VGTx_FLASH.ld similarity index 100% rename from hw/bsp/stm32f407g_disc1/STM32F407VGTx_FLASH.ld rename to hw/bsp/stm32f407disco/STM32F407VGTx_FLASH.ld diff --git a/hw/bsp/stm32f407g_disc1/board.mk b/hw/bsp/stm32f407disco/board.mk similarity index 93% rename from hw/bsp/stm32f407g_disc1/board.mk rename to hw/bsp/stm32f407disco/board.mk index ab3043a4..18223399 100644 --- a/hw/bsp/stm32f407g_disc1/board.mk +++ b/hw/bsp/stm32f407disco/board.mk @@ -10,7 +10,7 @@ CFLAGS += \ -DCFG_TUSB_MCU=OPT_MCU_STM32F4 # All source paths should be relative to the top level. -LD_FILE = hw/bsp/stm32f407g_disc1/STM32F407VGTx_FLASH.ld +LD_FILE = hw/bsp/stm32f407disco/STM32F407VGTx_FLASH.ld SRC_C += \ hw/mcu/st/system-init/system_stm32f4xx.c diff --git a/hw/bsp/stm32f407g_disc1/board_stm32f407g_disc1.c b/hw/bsp/stm32f407disco/board_stm32f407disco.c similarity index 100% rename from hw/bsp/stm32f407g_disc1/board_stm32f407g_disc1.c rename to hw/bsp/stm32f407disco/board_stm32f407disco.c diff --git a/hw/mcu/st/README.md b/hw/mcu/st/README.md index 203e47c3..c1313d8d 100644 --- a/hw/mcu/st/README.md +++ b/hw/mcu/st/README.md @@ -47,6 +47,6 @@ these files in one place. * ARM-provided headers are stored in the [cmsis](cmsis) directory. * The linker script for the STM32F4-DISCOVERY board demo is supplied as part of TinyUSB's - [Board Support Packages](../../bsp/stm32f407g_disc1/STM32F407VGTx_FLASH.ld). + [Board Support Packages](../../bsp/stm32f407disco/STM32F407VGTx_FLASH.ld). The above files were extracted from a dummy stm32cube project in February 2019. From fa12a0e78685c2407a0961f794918b177e5d5e38 Mon Sep 17 00:00:00 2001 From: hathach Date: Fri, 19 Jul 2019 21:19:06 +0700 Subject: [PATCH 2/9] adding stm32f411 disco compile ok --- hw/bsp/stm32f411disco/STM32F411VETx_FLASH.ld | 169 +++++++++++++++++++ hw/bsp/stm32f411disco/board.mk | 41 +++++ hw/bsp/stm32f411disco/board_stm32f411disco.c | 132 +++++++++++++++ 3 files changed, 342 insertions(+) create mode 100644 hw/bsp/stm32f411disco/STM32F411VETx_FLASH.ld create mode 100644 hw/bsp/stm32f411disco/board.mk create mode 100644 hw/bsp/stm32f411disco/board_stm32f411disco.c diff --git a/hw/bsp/stm32f411disco/STM32F411VETx_FLASH.ld b/hw/bsp/stm32f411disco/STM32F411VETx_FLASH.ld new file mode 100644 index 00000000..3a0ce526 --- /dev/null +++ b/hw/bsp/stm32f411disco/STM32F411VETx_FLASH.ld @@ -0,0 +1,169 @@ +/* +***************************************************************************** +** + +** File : LinkerScript.ld +** +** Abstract : Linker script for STM32F411VETx Device with +** 512KByte FLASH, 128KByte RAM +** +** Set heap size, stack size and stack location according +** to application requirements. +** +** Set memory bank area and size if external memory is used. +** +** Target : STMicroelectronics STM32 +** +** +** Distribution: The file is distributed as is, without any warranty +** of any kind. +** +** (c)Copyright Ac6. +** You may use this file as-is or modify it according to the needs of your +** project. Distribution of this file (unmodified or modified) is not +** permitted. Ac6 permit registered System Workbench for MCU users the +** rights to distribute the assembled, compiled & linked contents of this +** file as part of an application binary file, provided that it is built +** using the System Workbench for MCU toolchain. +** +***************************************************************************** +*/ + +/* Entry Point */ +ENTRY(Reset_Handler) + +/* Highest address of the user mode stack */ +_estack = 0x20020000; /* end of RAM */ +/* Generate a link error if heap and stack don't fit into RAM */ +_Min_Heap_Size = 0x200;; /* required amount of heap */ +_Min_Stack_Size = 0x400;; /* required amount of stack */ + +/* Specify the memory areas */ +MEMORY +{ +FLASH (rx) : ORIGIN = 0x08000000, LENGTH = 512K +RAM (xrw) : ORIGIN = 0x20000000, LENGTH = 128K +} + +/* 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/stm32f411disco/board.mk b/hw/bsp/stm32f411disco/board.mk new file mode 100644 index 00000000..43783f58 --- /dev/null +++ b/hw/bsp/stm32f411disco/board.mk @@ -0,0 +1,41 @@ +CFLAGS += \ + -DHSE_VALUE=8000000 \ + -DSTM32F411xE \ + -mthumb \ + -mabi=aapcs-linux \ + -mcpu=cortex-m4 \ + -mfloat-abi=hard \ + -mfpu=fpv4-sp-d16 \ + -nostdlib -nostartfiles \ + -DCFG_TUSB_MCU=OPT_MCU_STM32F4 + +# All source paths should be relative to the top level. +LD_FILE = hw/bsp/stm32f411disco/STM32F411VETx_FLASH.ld + +SRC_C += \ + hw/mcu/st/system-init/system_stm32f4xx.c + +SRC_S += \ + hw/mcu/st/startup/stm32f4/startup_stm32f411xe.s + +INC += \ + $(TOP)/hw/mcu/st/stm32lib/CMSIS/STM32F4xx/Include \ + $(TOP)/hw/mcu/st/cmsis + +# For TinyUSB port source +VENDOR = st +CHIP_FAMILY = stm32f4 + +# For freeRTOS port source +FREERTOS_PORT = ARM_CM4F + +# For flash-jlink target +JLINK_DEVICE = stm32f407vg +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/stm32f411disco/board_stm32f411disco.c b/hw/bsp/stm32f411disco/board_stm32f411disco.c new file mode 100644 index 00000000..c5695733 --- /dev/null +++ b/hw/bsp/stm32f411disco/board_stm32f411disco.c @@ -0,0 +1,132 @@ +/* + * 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 "stm32f4xx.h" + +void board_init(void) +{ + // Init the LED on PD14 + RCC->AHB1ENR |= RCC_AHB1ENR_GPIODEN; + GPIOD->MODER |= GPIO_MODER_MODE14_0; + + // TODO Button + + // USB Clock init + // PLL input- 8 MHz (External oscillator clock; HSI clock tolerance isn't + // tight enough- 1%, need 0.25%) + // VCO input- 1 to 2 MHz (2 MHz, M = 4) + // VCO output- 100 to 432 MHz (144 MHz, N = 72) + // Main PLL out- <= 180 MHz (18 MHz, P = 3- divides by 8) + // USB PLL out- 48 MHz (Q = 3) + RCC->PLLCFGR = RCC_PLLCFGR_PLLSRC_HSE | (3 << RCC_PLLCFGR_PLLQ_Pos) | \ + (3 << RCC_PLLCFGR_PLLP_Pos) | (72 << RCC_PLLCFGR_PLLN_Pos) | \ + (4 << RCC_PLLCFGR_PLLM_Pos); + + // Wait for external clock to become ready + RCC->CR |= RCC_CR_HSEON; + while(!(RCC->CR & RCC_CR_HSERDY_Msk)); + + // Wait for PLL to become ready + RCC->CR |= RCC_CR_PLLON; + while(!(RCC->CR & RCC_CR_PLLRDY_Msk)); + + // Switch clocks! + RCC->CFGR |= RCC_CFGR_SW_1; + + // Notify runtime of frequency change. + 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 + + RCC->AHB2ENR |= RCC_AHB2ENR_OTGFSEN; + + // USB Pin Init + // PA9- VUSB, PA10- ID, PA11- DM, PA12- DP + // PC0- Power on + RCC->AHB1ENR |= RCC_AHB1ENR_GPIOAEN; + GPIOA->MODER |= GPIO_MODER_MODE9_1 | GPIO_MODER_MODE10_1 | \ + GPIO_MODER_MODE11_1 | GPIO_MODER_MODE12_1; + GPIOA->AFR[1] |= (10 << GPIO_AFRH_AFSEL9_Pos) | \ + (10 << GPIO_AFRH_AFSEL10_Pos) | (10 << GPIO_AFRH_AFSEL11_Pos) | \ + (10 << GPIO_AFRH_AFSEL12_Pos); + + // Pullup required on ID, despite the manual claiming there's an + // internal pullup already (page 1245, Rev 17) + GPIOA->PUPDR |= GPIO_PUPDR_PUPD10_0; +} + +//--------------------------------------------------------------------+ +// Board porting API +//--------------------------------------------------------------------+ + +void board_led_write(bool state) +{ + if (!state) { + GPIOD->BSRR = GPIO_BSRR_BR14; + } else { + GPIOD->BSRR = GPIO_BSRR_BS14; + } +} + +uint32_t board_button_read(void) +{ + // TODO implement + return 0; +} + + +#if CFG_TUSB_OS == OPT_OS_NONE +volatile uint32_t system_ticks = 0; +void SysTick_Handler (void) +{ + system_ticks++; +} + +uint32_t board_millis(void) +{ + return system_ticks; +} +#endif + +void HardFault_Handler (void) +{ + asm("bkpt"); +} + +// Required by __libc_init_array in startup code if we are compiling using +// -nostdlib/-nostartfiles. +void _init(void) +{ + +} From 6ec87071ed4329b9ff7a220176ed008885e81ebe Mon Sep 17 00:00:00 2001 From: hathach Date: Sat, 20 Jul 2019 22:38:46 +0700 Subject: [PATCH 3/9] able to flash and turn on LED --- hw/bsp/stm32f411disco/board.mk | 12 +- hw/bsp/stm32f411disco/board_stm32f411disco.c | 20 + hw/bsp/stm32f411disco/stm32f4xx_hal_conf.h | 394 +++++++++++++++++++ 3 files changed, 422 insertions(+), 4 deletions(-) create mode 100644 hw/bsp/stm32f411disco/stm32f4xx_hal_conf.h diff --git a/hw/bsp/stm32f411disco/board.mk b/hw/bsp/stm32f411disco/board.mk index 43783f58..6b0a0fa2 100644 --- a/hw/bsp/stm32f411disco/board.mk +++ b/hw/bsp/stm32f411disco/board.mk @@ -1,25 +1,29 @@ CFLAGS += \ -DHSE_VALUE=8000000 \ + -DCFG_TUSB_MCU=OPT_MCU_STM32F4 \ -DSTM32F411xE \ -mthumb \ -mabi=aapcs-linux \ -mcpu=cortex-m4 \ -mfloat-abi=hard \ -mfpu=fpv4-sp-d16 \ - -nostdlib -nostartfiles \ - -DCFG_TUSB_MCU=OPT_MCU_STM32F4 + -nostdlib -nostartfiles # All source paths should be relative to the top level. LD_FILE = hw/bsp/stm32f411disco/STM32F411VETx_FLASH.ld SRC_C += \ - hw/mcu/st/system-init/system_stm32f4xx.c + hw/mcu/st/system-init/system_stm32f4xx.c \ + hw/mcu/st/stm32lib/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_gpio.c \ + SRC_S += \ hw/mcu/st/startup/stm32f4/startup_stm32f411xe.s INC += \ + $(TOP)/hw/bsp/stm32f411disco \ $(TOP)/hw/mcu/st/stm32lib/CMSIS/STM32F4xx/Include \ + $(TOP)/hw/mcu/st/stm32lib/STM32F4xx_HAL_Driver/Inc \ $(TOP)/hw/mcu/st/cmsis # For TinyUSB port source @@ -30,7 +34,7 @@ CHIP_FAMILY = stm32f4 FREERTOS_PORT = ARM_CM4F # For flash-jlink target -JLINK_DEVICE = stm32f407vg +JLINK_DEVICE = stm32f41ve JLINK_IF = swd # Path to STM32 Cube Programmer CLI, should be added into system path diff --git a/hw/bsp/stm32f411disco/board_stm32f411disco.c b/hw/bsp/stm32f411disco/board_stm32f411disco.c index c5695733..3f5f9cf8 100644 --- a/hw/bsp/stm32f411disco/board_stm32f411disco.c +++ b/hw/bsp/stm32f411disco/board_stm32f411disco.c @@ -27,9 +27,28 @@ #include "../board.h" #include "stm32f4xx.h" +#include "stm32f4xx_hal_conf.h" + +#define LED_PORT GPIOD +#define LED_PIN GPIO_PIN_13 void board_init(void) { + /* Configure the GPIO_LED pin */ + __HAL_RCC_GPIOD_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_FAST; + + HAL_GPIO_Init(LED_PORT, &GPIO_InitStruct); + + HAL_GPIO_WritePin(LED_PORT, LED_PIN, GPIO_PIN_RESET); + + +#if 0 // Init the LED on PD14 RCC->AHB1ENR |= RCC_AHB1ENR_GPIODEN; GPIOD->MODER |= GPIO_MODER_MODE14_0; @@ -84,6 +103,7 @@ void board_init(void) // Pullup required on ID, despite the manual claiming there's an // internal pullup already (page 1245, Rev 17) GPIOA->PUPDR |= GPIO_PUPDR_PUPD10_0; +#endif } //--------------------------------------------------------------------+ diff --git a/hw/bsp/stm32f411disco/stm32f4xx_hal_conf.h b/hw/bsp/stm32f411disco/stm32f4xx_hal_conf.h new file mode 100644 index 00000000..d9a69004 --- /dev/null +++ b/hw/bsp/stm32f411disco/stm32f4xx_hal_conf.h @@ -0,0 +1,394 @@ +/** + ****************************************************************************** + * @file GPIO/GPIO_EXTI/Inc/stm32f4xx_hal_conf.h + * @author MCD Application Team + * @brief HAL configuration file + ****************************************************************************** + * @attention + * + *

© COPYRIGHT(c) 2017 STMicroelectronics

+ * + * Redistribution and use in source and binary forms, with or without modification, + * are permitted provided that the following conditions are met: + * 1. Redistributions of source code must retain the above copyright notice, + * this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * 3. Neither the name of STMicroelectronics nor the names of its contributors + * may be used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE + * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE + * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR + * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, + * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE + * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __STM32F4xx_HAL_CONF_H +#define __STM32F4xx_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_CRC_MODULE_ENABLED */ +/* #define HAL_CRYP_MODULE_ENABLED */ +/* #define HAL_DAC_MODULE_ENABLED */ +/* #define HAL_DCMI_MODULE_ENABLED */ +#define HAL_DMA_MODULE_ENABLED +/* #define HAL_DMA2D_MODULE_ENABLED */ +/* #define HAL_ETH_MODULE_ENABLED */ +#define HAL_FLASH_MODULE_ENABLED +/* #define HAL_NAND_MODULE_ENABLED */ +/* #define HAL_NOR_MODULE_ENABLED */ +/* #define HAL_PCCARD_MODULE_ENABLED */ +/* #define HAL_SRAM_MODULE_ENABLED */ +/* #define HAL_SDRAM_MODULE_ENABLED */ +/* #define HAL_HASH_MODULE_ENABLED */ +#define HAL_GPIO_MODULE_ENABLED +// #define HAL_I2C_MODULE_ENABLED +/* #define HAL_I2S_MODULE_ENABLED */ +/* #define HAL_IWDG_MODULE_ENABLED */ +/* #define HAL_LTDC_MODULE_ENABLED */ +#define HAL_PWR_MODULE_ENABLED +#define HAL_RCC_MODULE_ENABLED +/* #define HAL_RNG_MODULE_ENABLED */ +/* #define HAL_RTC_MODULE_ENABLED */ +/* #define HAL_SAI_MODULE_ENABLED */ +/* #define HAL_SD_MODULE_ENABLED */ +// #define HAL_SPI_MODULE_ENABLED +/* #define HAL_TIM_MODULE_ENABLED */ +/* #define HAL_UART_MODULE_ENABLED */ +/* #define HAL_USART_MODULE_ENABLED */ +/* #define HAL_IRDA_MODULE_ENABLED */ +/* #define HAL_SMARTCARD_MODULE_ENABLED */ +/* #define HAL_WWDG_MODULE_ENABLED */ +#define HAL_CORTEX_MODULE_ENABLED +/* #define HAL_PCD_MODULE_ENABLED */ +/* #define HAL_HCD_MODULE_ENABLED */ + + +/* ########################## HSE/HSI Values adaptation ##################### */ +/** + * @brief Adjust the value of External High Speed oscillator (HSE) used in your application. + * This value is used by the RCC HAL module to compute the system frequency + * (when HSE is used as system clock source, directly or through the PLL). + */ +#if !defined (HSE_VALUE) + #define HSE_VALUE (8000000U) /*!< Value of the External oscillator in Hz */ +#endif /* HSE_VALUE */ + +#if !defined (HSE_STARTUP_TIMEOUT) + #define HSE_STARTUP_TIMEOUT (100U) /*!< Time out for HSE start up, in ms */ +#endif /* HSE_STARTUP_TIMEOUT */ + +/** + * @brief Internal High Speed oscillator (HSI) value. + * This value is used by the RCC HAL module to compute the system frequency + * (when HSI is used as system clock source, directly or through the PLL). + */ +#if !defined (HSI_VALUE) + #define HSI_VALUE (16000000U) /*!< Value of the Internal oscillator in Hz*/ +#endif /* HSI_VALUE */ + +/** + * @brief Internal Low Speed oscillator (LSI) value. + */ +#if !defined (LSI_VALUE) + #define LSI_VALUE (32000U) +#endif /* LSI_VALUE */ /*!< Value of the Internal Low Speed oscillator in Hz + The real value may vary depending on the variations + in voltage and temperature. */ +/** + * @brief External Low Speed oscillator (LSE) value. + */ +#if !defined (LSE_VALUE) + #define LSE_VALUE (32768U) /*!< Value of the External Low Speed 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 */ + +/** + * @brief External clock source for I2S peripheral + * This value is used by the I2S HAL module to compute the I2S clock source + * frequency, this source is inserted directly through I2S_CKIN pad. + */ +#if !defined (EXTERNAL_CLOCK_VALUE) + #define EXTERNAL_CLOCK_VALUE (12288000U) /*!< Value of the External oscillator in Hz*/ +#endif /* EXTERNAL_CLOCK_VALUE */ + +/* Tip: To avoid modifying this file each time you need to use different HSE, + === you can define the HSE value in your toolchain compiler preprocessor. */ + +/* ########################### System Configuration ######################### */ +/** + * @brief This is the HAL system configuration section + */ +#define VDD_VALUE (3300U) /*!< Value of VDD in mv */ +#define TICK_INT_PRIORITY (0x0FU) /*!< tick interrupt priority */ +#define USE_RTOS 0U +#define PREFETCH_ENABLE 1U +#define INSTRUCTION_CACHE_ENABLE 1U +#define DATA_CACHE_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_CRYP_REGISTER_CALLBACKS 0U /* CRYP register callback disabled */ +#define USE_HAL_DAC_REGISTER_CALLBACKS 0U /* DAC register callback disabled */ +#define USE_HAL_DCMI_REGISTER_CALLBACKS 0U /* DCMI register callback disabled */ +#define USE_HAL_DFSDM_REGISTER_CALLBACKS 0U /* DFSDM register callback disabled */ +#define USE_HAL_DMA2D_REGISTER_CALLBACKS 0U /* DMA2D register callback disabled */ +#define USE_HAL_DSI_REGISTER_CALLBACKS 0U /* DSI register callback disabled */ +#define USE_HAL_ETH_REGISTER_CALLBACKS 0U /* ETH register callback disabled */ +#define USE_HAL_HASH_REGISTER_CALLBACKS 0U /* HASH register callback disabled */ +#define USE_HAL_HCD_REGISTER_CALLBACKS 0U /* HCD register callback disabled */ +#define USE_HAL_I2C_REGISTER_CALLBACKS 0U /* I2C register callback disabled */ +#define USE_HAL_FMPI2C_REGISTER_CALLBACKS 0U /* FMPI2C register callback disabled */ +#define USE_HAL_I2S_REGISTER_CALLBACKS 0U /* I2S register callback disabled */ +#define USE_HAL_IRDA_REGISTER_CALLBACKS 0U /* IRDA register callback disabled */ +#define USE_HAL_LPTIM_REGISTER_CALLBACKS 0U /* LPTIM register callback disabled */ +#define USE_HAL_LTDC_REGISTER_CALLBACKS 0U /* LTDC 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_QSPI_REGISTER_CALLBACKS 0U /* QSPI register callback disabled */ +#define USE_HAL_RNG_REGISTER_CALLBACKS 0U /* RNG register callback disabled */ +#define USE_HAL_RTC_REGISTER_CALLBACKS 0U /* RTC register callback disabled */ +#define USE_HAL_SAI_REGISTER_CALLBACKS 0U /* SAI register callback disabled */ +#define USE_HAL_SD_REGISTER_CALLBACKS 0U /* SD register callback disabled */ +#define USE_HAL_SMARTCARD_REGISTER_CALLBACKS 0U /* SMARTCARD register callback disabled */ +#define USE_HAL_SDRAM_REGISTER_CALLBACKS 0U /* SDRAM register callback disabled */ +#define USE_HAL_SRAM_REGISTER_CALLBACKS 0U /* SRAM register callback disabled */ +#define USE_HAL_SPDIFRX_REGISTER_CALLBACKS 0U /* SPDIFRX register callback disabled */ +#define USE_HAL_SMBUS_REGISTER_CALLBACKS 0U /* SMBUS register callback disabled */ +#define USE_HAL_SPI_REGISTER_CALLBACKS 0U /* SPI register callback disabled */ +#define USE_HAL_TIM_REGISTER_CALLBACKS 0U /* TIM register callback disabled */ +#define USE_HAL_UART_REGISTER_CALLBACKS 0U /* UART register callback disabled */ +#define USE_HAL_USART_REGISTER_CALLBACKS 0U /* USART register callback disabled */ +#define USE_HAL_WWDG_REGISTER_CALLBACKS 0U /* WWDG register callback disabled */ + +/* ########################## Assert Selection ############################## */ +/** + * @brief Uncomment the line below to expanse the "assert_param" macro in the + * HAL drivers code + */ +/* #define USE_FULL_ASSERT 1U */ + +/* ################## SPI peripheral configuration ########################## */ + +/* CRC FEATURE: Use to activate CRC feature inside HAL SPI Driver +* Activated: CRC code is present inside driver +* Deactivated: CRC code cleaned from driver +*/ + +#define USE_SPI_CRC 1U + +/* Includes ------------------------------------------------------------------*/ +/** + * @brief Include module's header file + */ + +#ifdef HAL_RCC_MODULE_ENABLED + #include "stm32f4xx_hal_rcc.h" +#endif /* HAL_RCC_MODULE_ENABLED */ + +#ifdef HAL_GPIO_MODULE_ENABLED + #include "stm32f4xx_hal_gpio.h" +#endif /* HAL_GPIO_MODULE_ENABLED */ + +#ifdef HAL_DMA_MODULE_ENABLED + #include "stm32f4xx_hal_dma.h" +#endif /* HAL_DMA_MODULE_ENABLED */ + +#ifdef HAL_CORTEX_MODULE_ENABLED + #include "stm32f4xx_hal_cortex.h" +#endif /* HAL_CORTEX_MODULE_ENABLED */ + +#ifdef HAL_ADC_MODULE_ENABLED + #include "stm32f4xx_hal_adc.h" +#endif /* HAL_ADC_MODULE_ENABLED */ + +#ifdef HAL_CAN_MODULE_ENABLED + #include "stm32f4xx_hal_can.h" +#endif /* HAL_CAN_MODULE_ENABLED */ + +#ifdef HAL_CAN_LEGACY_MODULE_ENABLED + #include "stm32f4xx_hal_can_legacy.h" +#endif /* HAL_CAN_LEGACY_MODULE_ENABLED */ + +#ifdef HAL_CRC_MODULE_ENABLED + #include "stm32f4xx_hal_crc.h" +#endif /* HAL_CRC_MODULE_ENABLED */ + +#ifdef HAL_CRYP_MODULE_ENABLED + #include "stm32f4xx_hal_cryp.h" +#endif /* HAL_CRYP_MODULE_ENABLED */ + +#ifdef HAL_DMA2D_MODULE_ENABLED + #include "stm32f4xx_hal_dma2d.h" +#endif /* HAL_DMA2D_MODULE_ENABLED */ + +#ifdef HAL_DAC_MODULE_ENABLED + #include "stm32f4xx_hal_dac.h" +#endif /* HAL_DAC_MODULE_ENABLED */ + +#ifdef HAL_DCMI_MODULE_ENABLED + #include "stm32f4xx_hal_dcmi.h" +#endif /* HAL_DCMI_MODULE_ENABLED */ + +#ifdef HAL_ETH_MODULE_ENABLED + #include "stm32f4xx_hal_eth.h" +#endif /* HAL_ETH_MODULE_ENABLED */ + +#ifdef HAL_FLASH_MODULE_ENABLED + #include "stm32f4xx_hal_flash.h" +#endif /* HAL_FLASH_MODULE_ENABLED */ + +#ifdef HAL_SRAM_MODULE_ENABLED + #include "stm32f4xx_hal_sram.h" +#endif /* HAL_SRAM_MODULE_ENABLED */ + +#ifdef HAL_NOR_MODULE_ENABLED + #include "stm32f4xx_hal_nor.h" +#endif /* HAL_NOR_MODULE_ENABLED */ + +#ifdef HAL_NAND_MODULE_ENABLED + #include "stm32f4xx_hal_nand.h" +#endif /* HAL_NAND_MODULE_ENABLED */ + +#ifdef HAL_PCCARD_MODULE_ENABLED + #include "stm32f4xx_hal_pccard.h" +#endif /* HAL_PCCARD_MODULE_ENABLED */ + +#ifdef HAL_SDRAM_MODULE_ENABLED + #include "stm32f4xx_hal_sdram.h" +#endif /* HAL_SDRAM_MODULE_ENABLED */ + +#ifdef HAL_HASH_MODULE_ENABLED + #include "stm32f4xx_hal_hash.h" +#endif /* HAL_HASH_MODULE_ENABLED */ + +#ifdef HAL_I2C_MODULE_ENABLED + #include "stm32f4xx_hal_i2c.h" +#endif /* HAL_I2C_MODULE_ENABLED */ + +#ifdef HAL_I2S_MODULE_ENABLED + #include "stm32f4xx_hal_i2s.h" +#endif /* HAL_I2S_MODULE_ENABLED */ + +#ifdef HAL_IWDG_MODULE_ENABLED + #include "stm32f4xx_hal_iwdg.h" +#endif /* HAL_IWDG_MODULE_ENABLED */ + +#ifdef HAL_LTDC_MODULE_ENABLED + #include "stm32f4xx_hal_ltdc.h" +#endif /* HAL_LTDC_MODULE_ENABLED */ + +#ifdef HAL_PWR_MODULE_ENABLED + #include "stm32f4xx_hal_pwr.h" +#endif /* HAL_PWR_MODULE_ENABLED */ + +#ifdef HAL_RNG_MODULE_ENABLED + #include "stm32f4xx_hal_rng.h" +#endif /* HAL_RNG_MODULE_ENABLED */ + +#ifdef HAL_RTC_MODULE_ENABLED + #include "stm32f4xx_hal_rtc.h" +#endif /* HAL_RTC_MODULE_ENABLED */ + +#ifdef HAL_SAI_MODULE_ENABLED + #include "stm32f4xx_hal_sai.h" +#endif /* HAL_SAI_MODULE_ENABLED */ + +#ifdef HAL_SD_MODULE_ENABLED + #include "stm32f4xx_hal_sd.h" +#endif /* HAL_SD_MODULE_ENABLED */ + +#ifdef HAL_SPI_MODULE_ENABLED + #include "stm32f4xx_hal_spi.h" +#endif /* HAL_SPI_MODULE_ENABLED */ + +#ifdef HAL_TIM_MODULE_ENABLED + #include "stm32f4xx_hal_tim.h" +#endif /* HAL_TIM_MODULE_ENABLED */ + +#ifdef HAL_UART_MODULE_ENABLED + #include "stm32f4xx_hal_uart.h" +#endif /* HAL_UART_MODULE_ENABLED */ + +#ifdef HAL_USART_MODULE_ENABLED + #include "stm32f4xx_hal_usart.h" +#endif /* HAL_USART_MODULE_ENABLED */ + +#ifdef HAL_IRDA_MODULE_ENABLED + #include "stm32f4xx_hal_irda.h" +#endif /* HAL_IRDA_MODULE_ENABLED */ + +#ifdef HAL_SMARTCARD_MODULE_ENABLED + #include "stm32f4xx_hal_smartcard.h" +#endif /* HAL_SMARTCARD_MODULE_ENABLED */ + +#ifdef HAL_WWDG_MODULE_ENABLED + #include "stm32f4xx_hal_wwdg.h" +#endif /* HAL_WWDG_MODULE_ENABLED */ + +#ifdef HAL_PCD_MODULE_ENABLED + #include "stm32f4xx_hal_pcd.h" +#endif /* HAL_PCD_MODULE_ENABLED */ + +#ifdef HAL_HCD_MODULE_ENABLED + #include "stm32f4xx_hal_hcd.h" +#endif /* HAL_HCD_MODULE_ENABLED */ + +/* Exported macro ------------------------------------------------------------*/ +#ifdef USE_FULL_ASSERT +/** + * @brief The assert_param macro is used for function's parameters check. + * @param expr: If expr is false, it calls assert_failed function + * which reports the name of the source file and the source + * line number of the call that failed. + * If expr is true, it returns no value. + * @retval None + */ + #define assert_param(expr) ((expr) ? (void)0U : assert_failed((uint8_t *)__FILE__, __LINE__)) +/* Exported functions ------------------------------------------------------- */ + void assert_failed(uint8_t* file, uint32_t line); +#else + #define assert_param(expr) ((void)0U) +#endif /* USE_FULL_ASSERT */ + + +#ifdef __cplusplus +} +#endif + +#endif /* __STM32F4xx_HAL_CONF_H */ + + +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ From ed698069d37dbea2146960ceda246c07585747c3 Mon Sep 17 00:00:00 2001 From: hathach Date: Sat, 20 Jul 2019 22:41:45 +0700 Subject: [PATCH 4/9] clean up --- hw/bsp/stm32f303disco/board_stm32f303disco.c | 13 +++++++++---- hw/bsp/stm32f411disco/board_stm32f411disco.c | 9 ++------- 2 files changed, 11 insertions(+), 11 deletions(-) diff --git a/hw/bsp/stm32f303disco/board_stm32f303disco.c b/hw/bsp/stm32f303disco/board_stm32f303disco.c index 9a103ac6..ce56fa7e 100644 --- a/hw/bsp/stm32f303disco/board_stm32f303disco.c +++ b/hw/bsp/stm32f303disco/board_stm32f303disco.c @@ -29,6 +29,9 @@ #include "stm32f3xx.h" #include "stm32f3xx_hal_conf.h" +#define LED_PORT GPIOE +#define LED_PIN GPIO_PIN_9 + void board_init(void) { RCC_ClkInitTypeDef RCC_ClkInitStruct; @@ -60,17 +63,19 @@ void board_init(void) SysTick_Config(SystemCoreClock / 1000); #endif - /* -1- Enable GPIOE Clock (to be able to program the configuration registers) */ + /* -1- Enable GPIO Clock (to be able to program the configuration registers) */ __HAL_RCC_GPIOE_CLK_ENABLE(); /* -2- Configure PE.8 to PE.15 IOs in output push-pull mode to drive external LEDs */ static GPIO_InitTypeDef GPIO_InitStruct; - GPIO_InitStruct.Pin = GPIO_PIN_9; + 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(GPIOE, &GPIO_InitStruct); + HAL_GPIO_Init(LED_PORT, &GPIO_InitStruct); + + board_led_write(false); #if 0 RCC->AHB2ENR |= RCC_AHB2ENR_OTGFSEN; @@ -97,7 +102,7 @@ void board_init(void) void board_led_write(bool state) { - HAL_GPIO_WritePin(GPIOE, GPIO_PIN_9, state); + HAL_GPIO_WritePin(LED_PORT, LED_PIN, state); } uint32_t board_button_read(void) diff --git a/hw/bsp/stm32f411disco/board_stm32f411disco.c b/hw/bsp/stm32f411disco/board_stm32f411disco.c index 3f5f9cf8..a4a918b0 100644 --- a/hw/bsp/stm32f411disco/board_stm32f411disco.c +++ b/hw/bsp/stm32f411disco/board_stm32f411disco.c @@ -45,8 +45,7 @@ void board_init(void) HAL_GPIO_Init(LED_PORT, &GPIO_InitStruct); - HAL_GPIO_WritePin(LED_PORT, LED_PIN, GPIO_PIN_RESET); - + board_led_write(false); #if 0 // Init the LED on PD14 @@ -112,11 +111,7 @@ void board_init(void) void board_led_write(bool state) { - if (!state) { - GPIOD->BSRR = GPIO_BSRR_BR14; - } else { - GPIOD->BSRR = GPIO_BSRR_BS14; - } + HAL_GPIO_WritePin(LED_PORT, LED_PIN, state); } uint32_t board_button_read(void) From cb8a33ca87a1b2e81c2b441d916f1b085adb335f Mon Sep 17 00:00:00 2001 From: hathach Date: Sat, 20 Jul 2019 22:59:24 +0700 Subject: [PATCH 5/9] able to blink LED with stm32f411 --- hw/bsp/stm32f303disco/board_stm32f303disco.c | 12 +++--- hw/bsp/stm32f411disco/board.mk | 6 ++- hw/bsp/stm32f411disco/board_stm32f411disco.c | 41 +++++++++++++++++++- 3 files changed, 50 insertions(+), 9 deletions(-) diff --git a/hw/bsp/stm32f303disco/board_stm32f303disco.c b/hw/bsp/stm32f303disco/board_stm32f303disco.c index ce56fa7e..cb370b4f 100644 --- a/hw/bsp/stm32f303disco/board_stm32f303disco.c +++ b/hw/bsp/stm32f303disco/board_stm32f303disco.c @@ -34,6 +34,12 @@ void board_init(void) { + #if CFG_TUSB_OS == OPT_OS_NONE + // 1ms tick timer + SysTick_Config(SystemCoreClock / 1000); + #endif + + /* Configure the system clock to 72 MHz */ RCC_ClkInitTypeDef RCC_ClkInitStruct; RCC_OscInitTypeDef RCC_OscInitStruct; @@ -58,11 +64,6 @@ void board_init(void) // Notify runtime of frequency change. SystemCoreClockUpdate(); - #if CFG_TUSB_OS == OPT_OS_NONE - // 1ms tick timer - SysTick_Config(SystemCoreClock / 1000); - #endif - /* -1- Enable GPIO Clock (to be able to program the configuration registers) */ __HAL_RCC_GPIOE_CLK_ENABLE(); @@ -72,7 +73,6 @@ void board_init(void) GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_PP; GPIO_InitStruct.Pull = GPIO_PULLUP; GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_HIGH; - HAL_GPIO_Init(LED_PORT, &GPIO_InitStruct); board_led_write(false); diff --git a/hw/bsp/stm32f411disco/board.mk b/hw/bsp/stm32f411disco/board.mk index 6b0a0fa2..a79c2695 100644 --- a/hw/bsp/stm32f411disco/board.mk +++ b/hw/bsp/stm32f411disco/board.mk @@ -14,8 +14,10 @@ LD_FILE = hw/bsp/stm32f411disco/STM32F411VETx_FLASH.ld SRC_C += \ hw/mcu/st/system-init/system_stm32f4xx.c \ - hw/mcu/st/stm32lib/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_gpio.c \ - + hw/mcu/st/stm32lib/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal.c \ + hw/mcu/st/stm32lib/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_cortex.c \ + hw/mcu/st/stm32lib/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_rcc.c \ + hw/mcu/st/stm32lib/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_gpio.c SRC_S += \ hw/mcu/st/startup/stm32f4/startup_stm32f411xe.s diff --git a/hw/bsp/stm32f411disco/board_stm32f411disco.c b/hw/bsp/stm32f411disco/board_stm32f411disco.c index a4a918b0..4871e138 100644 --- a/hw/bsp/stm32f411disco/board_stm32f411disco.c +++ b/hw/bsp/stm32f411disco/board_stm32f411disco.c @@ -34,6 +34,46 @@ void board_init(void) { + #if CFG_TUSB_OS == OPT_OS_NONE + // 1ms tick timer + SysTick_Config(SystemCoreClock / 1000); + #endif + + /* Configure the system clock to 100 MHz */ + RCC_ClkInitTypeDef RCC_ClkInitStruct; + RCC_OscInitTypeDef RCC_OscInitStruct; + + /* Enable Power Control clock */ + __HAL_RCC_PWR_CLK_ENABLE(); + + /* The voltage scaling allows optimizing the power consumption when the device is + clocked below the maximum system frequency, to update the voltage scaling value + regarding system frequency refer to product datasheet. */ + __HAL_PWR_VOLTAGESCALING_CONFIG(PWR_REGULATOR_VOLTAGE_SCALE2); + + /* Enable HSI Oscillator and activate PLL with HSI as source */ + RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_HSI; + RCC_OscInitStruct.HSIState = RCC_HSI_ON; + RCC_OscInitStruct.HSICalibrationValue = 0x10; + RCC_OscInitStruct.PLL.PLLState = RCC_PLL_ON; + RCC_OscInitStruct.PLL.PLLSource = RCC_PLLSOURCE_HSI; + RCC_OscInitStruct.PLL.PLLM = 16; + RCC_OscInitStruct.PLL.PLLN = 400; + RCC_OscInitStruct.PLL.PLLP = RCC_PLLP_DIV4; + RCC_OscInitStruct.PLL.PLLQ = 7; + HAL_RCC_OscConfig(&RCC_OscInitStruct); + + /* Select PLL as system clock source and configure the HCLK, PCLK1 and PCLK2 clocks dividers */ + RCC_ClkInitStruct.ClockType = (RCC_CLOCKTYPE_SYSCLK | RCC_CLOCKTYPE_HCLK | RCC_CLOCKTYPE_PCLK1 | RCC_CLOCKTYPE_PCLK2); + RCC_ClkInitStruct.SYSCLKSource = RCC_SYSCLKSOURCE_PLLCLK; + RCC_ClkInitStruct.AHBCLKDivider = RCC_SYSCLK_DIV1; + RCC_ClkInitStruct.APB1CLKDivider = RCC_HCLK_DIV2; + RCC_ClkInitStruct.APB2CLKDivider = RCC_HCLK_DIV1; + HAL_RCC_ClockConfig(&RCC_ClkInitStruct, FLASH_LATENCY_3); + + // Notify runtime of frequency change. + SystemCoreClockUpdate(); + /* Configure the GPIO_LED pin */ __HAL_RCC_GPIOD_CLK_ENABLE(); @@ -42,7 +82,6 @@ void board_init(void) GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_PP; GPIO_InitStruct.Pull = GPIO_PULLUP; GPIO_InitStruct.Speed = GPIO_SPEED_FAST; - HAL_GPIO_Init(LED_PORT, &GPIO_InitStruct); board_led_write(false); From be4eeeb9433c187eafabcd5e4048dc53e78ce194 Mon Sep 17 00:00:00 2001 From: hathach Date: Mon, 22 Jul 2019 18:35:22 +0700 Subject: [PATCH 6/9] refactor stm32f407 to use st hal api --- hw/bsp/stm32f407disco/board.mk | 10 +- hw/bsp/stm32f407disco/board_stm32f407disco.c | 141 +++++++++++++------ hw/bsp/stm32f411disco/board.mk | 4 +- 3 files changed, 105 insertions(+), 50 deletions(-) diff --git a/hw/bsp/stm32f407disco/board.mk b/hw/bsp/stm32f407disco/board.mk index 18223399..bc1fd7c7 100644 --- a/hw/bsp/stm32f407disco/board.mk +++ b/hw/bsp/stm32f407disco/board.mk @@ -13,14 +13,20 @@ CFLAGS += \ LD_FILE = hw/bsp/stm32f407disco/STM32F407VGTx_FLASH.ld SRC_C += \ - hw/mcu/st/system-init/system_stm32f4xx.c + hw/mcu/st/system-init/system_stm32f4xx.c \ + hw/mcu/st/stm32lib/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal.c \ + hw/mcu/st/stm32lib/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_cortex.c \ + hw/mcu/st/stm32lib/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_rcc.c \ + hw/mcu/st/stm32lib/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_gpio.c SRC_S += \ hw/mcu/st/startup/stm32f4/startup_stm32f407xx.s INC += \ + $(TOP)/hw/mcu/st/cmsis \ $(TOP)/hw/mcu/st/stm32lib/CMSIS/STM32F4xx/Include \ - $(TOP)/hw/mcu/st/cmsis + $(TOP)/hw/mcu/st/stm32lib/STM32F4xx_HAL_Driver/Inc \ + $(TOP)/hw/bsp/stm32f407disco # For TinyUSB port source VENDOR = st diff --git a/hw/bsp/stm32f407disco/board_stm32f407disco.c b/hw/bsp/stm32f407disco/board_stm32f407disco.c index c5695733..7ef1c16d 100644 --- a/hw/bsp/stm32f407disco/board_stm32f407disco.c +++ b/hw/bsp/stm32f407disco/board_stm32f407disco.c @@ -27,39 +27,13 @@ #include "../board.h" #include "stm32f4xx.h" +#include "stm32f4xx_hal_conf.h" + +#define LED_PORT GPIOD +#define LED_PIN GPIO_PIN_14 void board_init(void) { - // Init the LED on PD14 - RCC->AHB1ENR |= RCC_AHB1ENR_GPIODEN; - GPIOD->MODER |= GPIO_MODER_MODE14_0; - - // TODO Button - - // USB Clock init - // PLL input- 8 MHz (External oscillator clock; HSI clock tolerance isn't - // tight enough- 1%, need 0.25%) - // VCO input- 1 to 2 MHz (2 MHz, M = 4) - // VCO output- 100 to 432 MHz (144 MHz, N = 72) - // Main PLL out- <= 180 MHz (18 MHz, P = 3- divides by 8) - // USB PLL out- 48 MHz (Q = 3) - RCC->PLLCFGR = RCC_PLLCFGR_PLLSRC_HSE | (3 << RCC_PLLCFGR_PLLQ_Pos) | \ - (3 << RCC_PLLCFGR_PLLP_Pos) | (72 << RCC_PLLCFGR_PLLN_Pos) | \ - (4 << RCC_PLLCFGR_PLLM_Pos); - - // Wait for external clock to become ready - RCC->CR |= RCC_CR_HSEON; - while(!(RCC->CR & RCC_CR_HSERDY_Msk)); - - // Wait for PLL to become ready - RCC->CR |= RCC_CR_PLLON; - while(!(RCC->CR & RCC_CR_PLLRDY_Msk)); - - // Switch clocks! - RCC->CFGR |= RCC_CFGR_SW_1; - - // Notify runtime of frequency change. - SystemCoreClockUpdate(); #if CFG_TUSB_OS == OPT_OS_NONE // 1ms tick timer @@ -69,21 +43,100 @@ void board_init(void) //NVIC_SetPriority(USB0_IRQn, configLIBRARY_MAX_SYSCALL_INTERRUPT_PRIORITY ); #endif - RCC->AHB2ENR |= RCC_AHB2ENR_OTGFSEN; +/** System Clock Configuration + * The system Clock is configured as follow : + * System Clock source = PLL (HSE) + * SYSCLK(Hz) = 168000000 + * HCLK(Hz) = 168000000 + * AHB Prescaler = 1 + * APB1 Prescaler = 4 + * APB2 Prescaler = 2 + * HSE Frequency(Hz) = 8000000 + * PLL_M = 8 + * PLL_N = 336 + * PLL_P = 2 + * PLL_Q = 7 + * VDD(V) = 3.3 + * Main regulator output voltage = Scale1 mode + * Flash Latency(WS) = 5 + */ + RCC_ClkInitTypeDef RCC_ClkInitStruct; + RCC_OscInitTypeDef RCC_OscInitStruct; + + /* Enable Power Control clock */ + __HAL_RCC_PWR_CLK_ENABLE(); + + /* The voltage scaling allows optimizing the power consumption when the device is + clocked below the maximum system frequency, to update the voltage scaling value + regarding system frequency refer to product datasheet. */ + __HAL_PWR_VOLTAGESCALING_CONFIG(PWR_REGULATOR_VOLTAGE_SCALE1); + + /* Enable HSE Oscillator and activate PLL with HSE as source */ + RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_HSE; + RCC_OscInitStruct.HSEState = RCC_HSE_ON; + RCC_OscInitStruct.PLL.PLLState = RCC_PLL_ON; + RCC_OscInitStruct.PLL.PLLSource = RCC_PLLSOURCE_HSE; + RCC_OscInitStruct.PLL.PLLM = 8; + RCC_OscInitStruct.PLL.PLLN = 336; + RCC_OscInitStruct.PLL.PLLP = RCC_PLLP_DIV2; + RCC_OscInitStruct.PLL.PLLQ = 7; + HAL_RCC_OscConfig(&RCC_OscInitStruct); + + /* Select PLL as system clock source and configure the HCLK, PCLK1 and PCLK2 + clocks dividers */ + RCC_ClkInitStruct.ClockType = (RCC_CLOCKTYPE_SYSCLK | RCC_CLOCKTYPE_HCLK | RCC_CLOCKTYPE_PCLK1 | RCC_CLOCKTYPE_PCLK2); + RCC_ClkInitStruct.SYSCLKSource = RCC_SYSCLKSOURCE_PLLCLK; + RCC_ClkInitStruct.AHBCLKDivider = RCC_SYSCLK_DIV1; + RCC_ClkInitStruct.APB1CLKDivider = RCC_HCLK_DIV4; + RCC_ClkInitStruct.APB2CLKDivider = RCC_HCLK_DIV2; + HAL_RCC_ClockConfig(&RCC_ClkInitStruct, FLASH_LATENCY_5); + + // Notify runtime of frequency change. + SystemCoreClockUpdate(); + + // Enable USB OTG clock + __HAL_RCC_USB_OTG_FS_CLK_ENABLE(); + + GPIO_InitTypeDef GPIO_InitStruct; // USB Pin Init // PA9- VUSB, PA10- ID, PA11- DM, PA12- DP - // PC0- Power on - RCC->AHB1ENR |= RCC_AHB1ENR_GPIOAEN; - GPIOA->MODER |= GPIO_MODER_MODE9_1 | GPIO_MODER_MODE10_1 | \ - GPIO_MODER_MODE11_1 | GPIO_MODER_MODE12_1; - GPIOA->AFR[1] |= (10 << GPIO_AFRH_AFSEL9_Pos) | \ - (10 << GPIO_AFRH_AFSEL10_Pos) | (10 << GPIO_AFRH_AFSEL11_Pos) | \ - (10 << GPIO_AFRH_AFSEL12_Pos); + __HAL_RCC_GPIOA_CLK_ENABLE(); - // Pullup required on ID, despite the manual claiming there's an - // internal pullup already (page 1245, Rev 17) - GPIOA->PUPDR |= GPIO_PUPDR_PUPD10_0; + /* Configure DM DP Pins */ + GPIO_InitStruct.Pin = GPIO_PIN_11 | GPIO_PIN_12; + GPIO_InitStruct.Speed = GPIO_SPEED_HIGH; + GPIO_InitStruct.Mode = GPIO_MODE_AF_PP; + GPIO_InitStruct.Pull = GPIO_NOPULL; + GPIO_InitStruct.Alternate = GPIO_AF10_OTG_FS; + HAL_GPIO_Init(GPIOA, &GPIO_InitStruct); + + /* Configure VBUS Pin */ + GPIO_InitStruct.Pin = GPIO_PIN_9; + GPIO_InitStruct.Mode = GPIO_MODE_INPUT; + GPIO_InitStruct.Pull = GPIO_NOPULL; + HAL_GPIO_Init(GPIOA, &GPIO_InitStruct); + + /* This for ID line debug */ + GPIO_InitStruct.Pin = GPIO_PIN_10; + GPIO_InitStruct.Mode = GPIO_MODE_AF_OD; + GPIO_InitStruct.Pull = GPIO_PULLUP; + GPIO_InitStruct.Speed = GPIO_SPEED_HIGH; + GPIO_InitStruct.Alternate = GPIO_AF10_OTG_FS; + HAL_GPIO_Init(GPIOA, &GPIO_InitStruct); + + // Init the LED + __HAL_RCC_GPIOD_CLK_ENABLE(); + + GPIO_InitStruct.Pin = LED_PIN; + GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_PP; + GPIO_InitStruct.Pull = GPIO_PULLUP; + GPIO_InitStruct.Speed = GPIO_SPEED_FAST; + HAL_GPIO_Init(LED_PORT, &GPIO_InitStruct); + + board_led_write(false); + + // TODO Button } //--------------------------------------------------------------------+ @@ -92,11 +145,7 @@ void board_init(void) void board_led_write(bool state) { - if (!state) { - GPIOD->BSRR = GPIO_BSRR_BR14; - } else { - GPIOD->BSRR = GPIO_BSRR_BS14; - } + HAL_GPIO_WritePin(LED_PORT, LED_PIN, state); } uint32_t board_button_read(void) diff --git a/hw/bsp/stm32f411disco/board.mk b/hw/bsp/stm32f411disco/board.mk index a79c2695..8154545f 100644 --- a/hw/bsp/stm32f411disco/board.mk +++ b/hw/bsp/stm32f411disco/board.mk @@ -23,10 +23,10 @@ SRC_S += \ hw/mcu/st/startup/stm32f4/startup_stm32f411xe.s INC += \ - $(TOP)/hw/bsp/stm32f411disco \ + $(TOP)/hw/mcu/st/cmsis \ $(TOP)/hw/mcu/st/stm32lib/CMSIS/STM32F4xx/Include \ $(TOP)/hw/mcu/st/stm32lib/STM32F4xx_HAL_Driver/Inc \ - $(TOP)/hw/mcu/st/cmsis + $(TOP)/hw/bsp/stm32f411disco # For TinyUSB port source VENDOR = st From 1594a9de71c7fedd4c924051a6c09d041154e5b1 Mon Sep 17 00:00:00 2001 From: hathach Date: Mon, 22 Jul 2019 18:53:52 +0700 Subject: [PATCH 7/9] stm32f411 usb work with example --- hw/bsp/stm32f303disco/board_stm32f303disco.c | 2 +- hw/bsp/stm32f407disco/board_stm32f407disco.c | 61 ++++---- hw/bsp/stm32f411disco/board_stm32f411disco.c | 148 ++++++++++--------- 3 files changed, 110 insertions(+), 101 deletions(-) diff --git a/hw/bsp/stm32f303disco/board_stm32f303disco.c b/hw/bsp/stm32f303disco/board_stm32f303disco.c index cb370b4f..c5e1108e 100644 --- a/hw/bsp/stm32f303disco/board_stm32f303disco.c +++ b/hw/bsp/stm32f303disco/board_stm32f303disco.c @@ -68,7 +68,7 @@ void board_init(void) __HAL_RCC_GPIOE_CLK_ENABLE(); /* -2- Configure PE.8 to PE.15 IOs in output push-pull mode to drive external LEDs */ - static GPIO_InitTypeDef GPIO_InitStruct; + GPIO_InitTypeDef GPIO_InitStruct; GPIO_InitStruct.Pin = LED_PIN; GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_PP; GPIO_InitStruct.Pull = GPIO_PULLUP; diff --git a/hw/bsp/stm32f407disco/board_stm32f407disco.c b/hw/bsp/stm32f407disco/board_stm32f407disco.c index 7ef1c16d..6936f2b1 100644 --- a/hw/bsp/stm32f407disco/board_stm32f407disco.c +++ b/hw/bsp/stm32f407disco/board_stm32f407disco.c @@ -32,34 +32,28 @@ #define LED_PORT GPIOD #define LED_PIN GPIO_PIN_14 -void board_init(void) -{ - -#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 - -/** System Clock Configuration - * The system Clock is configured as follow : - * System Clock source = PLL (HSE) - * SYSCLK(Hz) = 168000000 - * HCLK(Hz) = 168000000 - * AHB Prescaler = 1 - * APB1 Prescaler = 4 - * APB2 Prescaler = 2 - * HSE Frequency(Hz) = 8000000 - * PLL_M = 8 - * PLL_N = 336 - * PLL_P = 2 - * PLL_Q = 7 - * VDD(V) = 3.3 - * Main regulator output voltage = Scale1 mode - * Flash Latency(WS) = 5 +/** + * @brief System Clock Configuration + * The system Clock is configured as follow : + * System Clock source = PLL (HSE) + * SYSCLK(Hz) = 168000000 + * HCLK(Hz) = 168000000 + * AHB Prescaler = 1 + * APB1 Prescaler = 4 + * APB2 Prescaler = 2 + * HSE Frequency(Hz) = 8000000 + * PLL_M = 8 + * PLL_N = 336 + * PLL_P = 2 + * PLL_Q = 7 + * VDD(V) = 3.3 + * Main regulator output voltage = Scale1 mode + * Flash Latency(WS) = 5 + * @param None + * @retval None */ +static void SystemClock_Config(void) +{ RCC_ClkInitTypeDef RCC_ClkInitStruct; RCC_OscInitTypeDef RCC_OscInitStruct; @@ -90,6 +84,19 @@ void board_init(void) RCC_ClkInitStruct.APB1CLKDivider = RCC_HCLK_DIV4; RCC_ClkInitStruct.APB2CLKDivider = RCC_HCLK_DIV2; HAL_RCC_ClockConfig(&RCC_ClkInitStruct, FLASH_LATENCY_5); +} + +void board_init(void) +{ +#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 + + SystemClock_Config(); // Notify runtime of frequency change. SystemCoreClockUpdate(); diff --git a/hw/bsp/stm32f411disco/board_stm32f411disco.c b/hw/bsp/stm32f411disco/board_stm32f411disco.c index 4871e138..cb598376 100644 --- a/hw/bsp/stm32f411disco/board_stm32f411disco.c +++ b/hw/bsp/stm32f411disco/board_stm32f411disco.c @@ -32,14 +32,28 @@ #define LED_PORT GPIOD #define LED_PIN GPIO_PIN_13 -void board_init(void) +/** + * @brief System Clock Configuration + * The system Clock is configured as follow : + * System Clock source = PLL (HSE) + * SYSCLK(Hz) = 84000000 + * HCLK(Hz) = 84000000 + * AHB Prescaler = 1 + * APB1 Prescaler = 2 + * APB2 Prescaler = 1 + * HSE Frequency(Hz) = 8000000 + * PLL_M = 8 + * PLL_N = 336 + * PLL_P = 4 + * PLL_Q = 7 + * VDD(V) = 3.3 + * Main regulator output voltage = Scale2 mode + * Flash Latency(WS) = 2 + * @param None + * @retval None + */ +static void SystemClock_Config(void) { - #if CFG_TUSB_OS == OPT_OS_NONE - // 1ms tick timer - SysTick_Config(SystemCoreClock / 1000); - #endif - - /* Configure the system clock to 100 MHz */ RCC_ClkInitTypeDef RCC_ClkInitStruct; RCC_OscInitTypeDef RCC_OscInitStruct; @@ -51,33 +65,76 @@ void board_init(void) regarding system frequency refer to product datasheet. */ __HAL_PWR_VOLTAGESCALING_CONFIG(PWR_REGULATOR_VOLTAGE_SCALE2); - /* Enable HSI Oscillator and activate PLL with HSI as source */ - RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_HSI; - RCC_OscInitStruct.HSIState = RCC_HSI_ON; - RCC_OscInitStruct.HSICalibrationValue = 0x10; + /* Enable HSE Oscillator and activate PLL with HSE as source */ + RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_HSE; + RCC_OscInitStruct.HSEState = RCC_HSE_ON; RCC_OscInitStruct.PLL.PLLState = RCC_PLL_ON; - RCC_OscInitStruct.PLL.PLLSource = RCC_PLLSOURCE_HSI; - RCC_OscInitStruct.PLL.PLLM = 16; - RCC_OscInitStruct.PLL.PLLN = 400; + RCC_OscInitStruct.PLL.PLLSource = RCC_PLLSOURCE_HSE; + RCC_OscInitStruct.PLL.PLLM = 8; + RCC_OscInitStruct.PLL.PLLN = 336; RCC_OscInitStruct.PLL.PLLP = RCC_PLLP_DIV4; RCC_OscInitStruct.PLL.PLLQ = 7; HAL_RCC_OscConfig(&RCC_OscInitStruct); - /* Select PLL as system clock source and configure the HCLK, PCLK1 and PCLK2 clocks dividers */ + /* Select PLL as system clock source and configure the HCLK, PCLK1 and PCLK2 + clocks dividers */ RCC_ClkInitStruct.ClockType = (RCC_CLOCKTYPE_SYSCLK | RCC_CLOCKTYPE_HCLK | RCC_CLOCKTYPE_PCLK1 | RCC_CLOCKTYPE_PCLK2); RCC_ClkInitStruct.SYSCLKSource = RCC_SYSCLKSOURCE_PLLCLK; RCC_ClkInitStruct.AHBCLKDivider = RCC_SYSCLK_DIV1; RCC_ClkInitStruct.APB1CLKDivider = RCC_HCLK_DIV2; RCC_ClkInitStruct.APB2CLKDivider = RCC_HCLK_DIV1; - HAL_RCC_ClockConfig(&RCC_ClkInitStruct, FLASH_LATENCY_3); + HAL_RCC_ClockConfig(&RCC_ClkInitStruct, FLASH_LATENCY_2); +} + +void board_init(void) +{ +#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 + + SystemClock_Config(); // Notify runtime of frequency change. SystemCoreClockUpdate(); - /* Configure the GPIO_LED pin */ - __HAL_RCC_GPIOD_CLK_ENABLE(); + // Enable USB OTG clock + __HAL_RCC_USB_OTG_FS_CLK_ENABLE(); + + + /* Configure USB FS GPIOs */ + __HAL_RCC_GPIOA_CLK_ENABLE(); GPIO_InitTypeDef GPIO_InitStruct; + + /* Configure DM DP Pins */ + GPIO_InitStruct.Pin = GPIO_PIN_11 | GPIO_PIN_12; + GPIO_InitStruct.Speed = GPIO_SPEED_HIGH; + GPIO_InitStruct.Mode = GPIO_MODE_AF_PP; + GPIO_InitStruct.Pull = GPIO_NOPULL; + GPIO_InitStruct.Alternate = GPIO_AF10_OTG_FS; + HAL_GPIO_Init(GPIOA, &GPIO_InitStruct); + + /* Configure VBUS Pin */ + GPIO_InitStruct.Pin = GPIO_PIN_9; + GPIO_InitStruct.Mode = GPIO_MODE_INPUT; + GPIO_InitStruct.Pull = GPIO_NOPULL; + HAL_GPIO_Init(GPIOA, &GPIO_InitStruct); + + /* This for ID line debug */ + GPIO_InitStruct.Pin = GPIO_PIN_10; + GPIO_InitStruct.Mode = GPIO_MODE_AF_OD; + GPIO_InitStruct.Pull = GPIO_PULLUP; + GPIO_InitStruct.Speed = GPIO_SPEED_HIGH; + GPIO_InitStruct.Alternate = GPIO_AF10_OTG_FS; + HAL_GPIO_Init(GPIOA, &GPIO_InitStruct); + + // Init the LED + __HAL_RCC_GPIOD_CLK_ENABLE(); + GPIO_InitStruct.Pin = LED_PIN; GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_PP; GPIO_InitStruct.Pull = GPIO_PULLUP; @@ -86,62 +143,7 @@ void board_init(void) board_led_write(false); -#if 0 - // Init the LED on PD14 - RCC->AHB1ENR |= RCC_AHB1ENR_GPIODEN; - GPIOD->MODER |= GPIO_MODER_MODE14_0; - // TODO Button - - // USB Clock init - // PLL input- 8 MHz (External oscillator clock; HSI clock tolerance isn't - // tight enough- 1%, need 0.25%) - // VCO input- 1 to 2 MHz (2 MHz, M = 4) - // VCO output- 100 to 432 MHz (144 MHz, N = 72) - // Main PLL out- <= 180 MHz (18 MHz, P = 3- divides by 8) - // USB PLL out- 48 MHz (Q = 3) - RCC->PLLCFGR = RCC_PLLCFGR_PLLSRC_HSE | (3 << RCC_PLLCFGR_PLLQ_Pos) | \ - (3 << RCC_PLLCFGR_PLLP_Pos) | (72 << RCC_PLLCFGR_PLLN_Pos) | \ - (4 << RCC_PLLCFGR_PLLM_Pos); - - // Wait for external clock to become ready - RCC->CR |= RCC_CR_HSEON; - while(!(RCC->CR & RCC_CR_HSERDY_Msk)); - - // Wait for PLL to become ready - RCC->CR |= RCC_CR_PLLON; - while(!(RCC->CR & RCC_CR_PLLRDY_Msk)); - - // Switch clocks! - RCC->CFGR |= RCC_CFGR_SW_1; - - // Notify runtime of frequency change. - 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 - - RCC->AHB2ENR |= RCC_AHB2ENR_OTGFSEN; - - // USB Pin Init - // PA9- VUSB, PA10- ID, PA11- DM, PA12- DP - // PC0- Power on - RCC->AHB1ENR |= RCC_AHB1ENR_GPIOAEN; - GPIOA->MODER |= GPIO_MODER_MODE9_1 | GPIO_MODER_MODE10_1 | \ - GPIO_MODER_MODE11_1 | GPIO_MODER_MODE12_1; - GPIOA->AFR[1] |= (10 << GPIO_AFRH_AFSEL9_Pos) | \ - (10 << GPIO_AFRH_AFSEL10_Pos) | (10 << GPIO_AFRH_AFSEL11_Pos) | \ - (10 << GPIO_AFRH_AFSEL12_Pos); - - // Pullup required on ID, despite the manual claiming there's an - // internal pullup already (page 1245, Rev 17) - GPIOA->PUPDR |= GPIO_PUPDR_PUPD10_0; -#endif } //--------------------------------------------------------------------+ From 2b43bba4531e46c3004481c7d1ec86390956e87d Mon Sep 17 00:00:00 2001 From: hathach Date: Mon, 22 Jul 2019 18:54:13 +0700 Subject: [PATCH 8/9] add missing conf file --- hw/bsp/stm32f407disco/stm32f4xx_hal_conf.h | 394 +++++++++++++++++++++ 1 file changed, 394 insertions(+) create mode 100644 hw/bsp/stm32f407disco/stm32f4xx_hal_conf.h diff --git a/hw/bsp/stm32f407disco/stm32f4xx_hal_conf.h b/hw/bsp/stm32f407disco/stm32f4xx_hal_conf.h new file mode 100644 index 00000000..d9a69004 --- /dev/null +++ b/hw/bsp/stm32f407disco/stm32f4xx_hal_conf.h @@ -0,0 +1,394 @@ +/** + ****************************************************************************** + * @file GPIO/GPIO_EXTI/Inc/stm32f4xx_hal_conf.h + * @author MCD Application Team + * @brief HAL configuration file + ****************************************************************************** + * @attention + * + *

© COPYRIGHT(c) 2017 STMicroelectronics

+ * + * Redistribution and use in source and binary forms, with or without modification, + * are permitted provided that the following conditions are met: + * 1. Redistributions of source code must retain the above copyright notice, + * this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * 3. Neither the name of STMicroelectronics nor the names of its contributors + * may be used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE + * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE + * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR + * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, + * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE + * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __STM32F4xx_HAL_CONF_H +#define __STM32F4xx_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_CRC_MODULE_ENABLED */ +/* #define HAL_CRYP_MODULE_ENABLED */ +/* #define HAL_DAC_MODULE_ENABLED */ +/* #define HAL_DCMI_MODULE_ENABLED */ +#define HAL_DMA_MODULE_ENABLED +/* #define HAL_DMA2D_MODULE_ENABLED */ +/* #define HAL_ETH_MODULE_ENABLED */ +#define HAL_FLASH_MODULE_ENABLED +/* #define HAL_NAND_MODULE_ENABLED */ +/* #define HAL_NOR_MODULE_ENABLED */ +/* #define HAL_PCCARD_MODULE_ENABLED */ +/* #define HAL_SRAM_MODULE_ENABLED */ +/* #define HAL_SDRAM_MODULE_ENABLED */ +/* #define HAL_HASH_MODULE_ENABLED */ +#define HAL_GPIO_MODULE_ENABLED +// #define HAL_I2C_MODULE_ENABLED +/* #define HAL_I2S_MODULE_ENABLED */ +/* #define HAL_IWDG_MODULE_ENABLED */ +/* #define HAL_LTDC_MODULE_ENABLED */ +#define HAL_PWR_MODULE_ENABLED +#define HAL_RCC_MODULE_ENABLED +/* #define HAL_RNG_MODULE_ENABLED */ +/* #define HAL_RTC_MODULE_ENABLED */ +/* #define HAL_SAI_MODULE_ENABLED */ +/* #define HAL_SD_MODULE_ENABLED */ +// #define HAL_SPI_MODULE_ENABLED +/* #define HAL_TIM_MODULE_ENABLED */ +/* #define HAL_UART_MODULE_ENABLED */ +/* #define HAL_USART_MODULE_ENABLED */ +/* #define HAL_IRDA_MODULE_ENABLED */ +/* #define HAL_SMARTCARD_MODULE_ENABLED */ +/* #define HAL_WWDG_MODULE_ENABLED */ +#define HAL_CORTEX_MODULE_ENABLED +/* #define HAL_PCD_MODULE_ENABLED */ +/* #define HAL_HCD_MODULE_ENABLED */ + + +/* ########################## HSE/HSI Values adaptation ##################### */ +/** + * @brief Adjust the value of External High Speed oscillator (HSE) used in your application. + * This value is used by the RCC HAL module to compute the system frequency + * (when HSE is used as system clock source, directly or through the PLL). + */ +#if !defined (HSE_VALUE) + #define HSE_VALUE (8000000U) /*!< Value of the External oscillator in Hz */ +#endif /* HSE_VALUE */ + +#if !defined (HSE_STARTUP_TIMEOUT) + #define HSE_STARTUP_TIMEOUT (100U) /*!< Time out for HSE start up, in ms */ +#endif /* HSE_STARTUP_TIMEOUT */ + +/** + * @brief Internal High Speed oscillator (HSI) value. + * This value is used by the RCC HAL module to compute the system frequency + * (when HSI is used as system clock source, directly or through the PLL). + */ +#if !defined (HSI_VALUE) + #define HSI_VALUE (16000000U) /*!< Value of the Internal oscillator in Hz*/ +#endif /* HSI_VALUE */ + +/** + * @brief Internal Low Speed oscillator (LSI) value. + */ +#if !defined (LSI_VALUE) + #define LSI_VALUE (32000U) +#endif /* LSI_VALUE */ /*!< Value of the Internal Low Speed oscillator in Hz + The real value may vary depending on the variations + in voltage and temperature. */ +/** + * @brief External Low Speed oscillator (LSE) value. + */ +#if !defined (LSE_VALUE) + #define LSE_VALUE (32768U) /*!< Value of the External Low Speed 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 */ + +/** + * @brief External clock source for I2S peripheral + * This value is used by the I2S HAL module to compute the I2S clock source + * frequency, this source is inserted directly through I2S_CKIN pad. + */ +#if !defined (EXTERNAL_CLOCK_VALUE) + #define EXTERNAL_CLOCK_VALUE (12288000U) /*!< Value of the External oscillator in Hz*/ +#endif /* EXTERNAL_CLOCK_VALUE */ + +/* Tip: To avoid modifying this file each time you need to use different HSE, + === you can define the HSE value in your toolchain compiler preprocessor. */ + +/* ########################### System Configuration ######################### */ +/** + * @brief This is the HAL system configuration section + */ +#define VDD_VALUE (3300U) /*!< Value of VDD in mv */ +#define TICK_INT_PRIORITY (0x0FU) /*!< tick interrupt priority */ +#define USE_RTOS 0U +#define PREFETCH_ENABLE 1U +#define INSTRUCTION_CACHE_ENABLE 1U +#define DATA_CACHE_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_CRYP_REGISTER_CALLBACKS 0U /* CRYP register callback disabled */ +#define USE_HAL_DAC_REGISTER_CALLBACKS 0U /* DAC register callback disabled */ +#define USE_HAL_DCMI_REGISTER_CALLBACKS 0U /* DCMI register callback disabled */ +#define USE_HAL_DFSDM_REGISTER_CALLBACKS 0U /* DFSDM register callback disabled */ +#define USE_HAL_DMA2D_REGISTER_CALLBACKS 0U /* DMA2D register callback disabled */ +#define USE_HAL_DSI_REGISTER_CALLBACKS 0U /* DSI register callback disabled */ +#define USE_HAL_ETH_REGISTER_CALLBACKS 0U /* ETH register callback disabled */ +#define USE_HAL_HASH_REGISTER_CALLBACKS 0U /* HASH register callback disabled */ +#define USE_HAL_HCD_REGISTER_CALLBACKS 0U /* HCD register callback disabled */ +#define USE_HAL_I2C_REGISTER_CALLBACKS 0U /* I2C register callback disabled */ +#define USE_HAL_FMPI2C_REGISTER_CALLBACKS 0U /* FMPI2C register callback disabled */ +#define USE_HAL_I2S_REGISTER_CALLBACKS 0U /* I2S register callback disabled */ +#define USE_HAL_IRDA_REGISTER_CALLBACKS 0U /* IRDA register callback disabled */ +#define USE_HAL_LPTIM_REGISTER_CALLBACKS 0U /* LPTIM register callback disabled */ +#define USE_HAL_LTDC_REGISTER_CALLBACKS 0U /* LTDC 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_QSPI_REGISTER_CALLBACKS 0U /* QSPI register callback disabled */ +#define USE_HAL_RNG_REGISTER_CALLBACKS 0U /* RNG register callback disabled */ +#define USE_HAL_RTC_REGISTER_CALLBACKS 0U /* RTC register callback disabled */ +#define USE_HAL_SAI_REGISTER_CALLBACKS 0U /* SAI register callback disabled */ +#define USE_HAL_SD_REGISTER_CALLBACKS 0U /* SD register callback disabled */ +#define USE_HAL_SMARTCARD_REGISTER_CALLBACKS 0U /* SMARTCARD register callback disabled */ +#define USE_HAL_SDRAM_REGISTER_CALLBACKS 0U /* SDRAM register callback disabled */ +#define USE_HAL_SRAM_REGISTER_CALLBACKS 0U /* SRAM register callback disabled */ +#define USE_HAL_SPDIFRX_REGISTER_CALLBACKS 0U /* SPDIFRX register callback disabled */ +#define USE_HAL_SMBUS_REGISTER_CALLBACKS 0U /* SMBUS register callback disabled */ +#define USE_HAL_SPI_REGISTER_CALLBACKS 0U /* SPI register callback disabled */ +#define USE_HAL_TIM_REGISTER_CALLBACKS 0U /* TIM register callback disabled */ +#define USE_HAL_UART_REGISTER_CALLBACKS 0U /* UART register callback disabled */ +#define USE_HAL_USART_REGISTER_CALLBACKS 0U /* USART register callback disabled */ +#define USE_HAL_WWDG_REGISTER_CALLBACKS 0U /* WWDG register callback disabled */ + +/* ########################## Assert Selection ############################## */ +/** + * @brief Uncomment the line below to expanse the "assert_param" macro in the + * HAL drivers code + */ +/* #define USE_FULL_ASSERT 1U */ + +/* ################## SPI peripheral configuration ########################## */ + +/* CRC FEATURE: Use to activate CRC feature inside HAL SPI Driver +* Activated: CRC code is present inside driver +* Deactivated: CRC code cleaned from driver +*/ + +#define USE_SPI_CRC 1U + +/* Includes ------------------------------------------------------------------*/ +/** + * @brief Include module's header file + */ + +#ifdef HAL_RCC_MODULE_ENABLED + #include "stm32f4xx_hal_rcc.h" +#endif /* HAL_RCC_MODULE_ENABLED */ + +#ifdef HAL_GPIO_MODULE_ENABLED + #include "stm32f4xx_hal_gpio.h" +#endif /* HAL_GPIO_MODULE_ENABLED */ + +#ifdef HAL_DMA_MODULE_ENABLED + #include "stm32f4xx_hal_dma.h" +#endif /* HAL_DMA_MODULE_ENABLED */ + +#ifdef HAL_CORTEX_MODULE_ENABLED + #include "stm32f4xx_hal_cortex.h" +#endif /* HAL_CORTEX_MODULE_ENABLED */ + +#ifdef HAL_ADC_MODULE_ENABLED + #include "stm32f4xx_hal_adc.h" +#endif /* HAL_ADC_MODULE_ENABLED */ + +#ifdef HAL_CAN_MODULE_ENABLED + #include "stm32f4xx_hal_can.h" +#endif /* HAL_CAN_MODULE_ENABLED */ + +#ifdef HAL_CAN_LEGACY_MODULE_ENABLED + #include "stm32f4xx_hal_can_legacy.h" +#endif /* HAL_CAN_LEGACY_MODULE_ENABLED */ + +#ifdef HAL_CRC_MODULE_ENABLED + #include "stm32f4xx_hal_crc.h" +#endif /* HAL_CRC_MODULE_ENABLED */ + +#ifdef HAL_CRYP_MODULE_ENABLED + #include "stm32f4xx_hal_cryp.h" +#endif /* HAL_CRYP_MODULE_ENABLED */ + +#ifdef HAL_DMA2D_MODULE_ENABLED + #include "stm32f4xx_hal_dma2d.h" +#endif /* HAL_DMA2D_MODULE_ENABLED */ + +#ifdef HAL_DAC_MODULE_ENABLED + #include "stm32f4xx_hal_dac.h" +#endif /* HAL_DAC_MODULE_ENABLED */ + +#ifdef HAL_DCMI_MODULE_ENABLED + #include "stm32f4xx_hal_dcmi.h" +#endif /* HAL_DCMI_MODULE_ENABLED */ + +#ifdef HAL_ETH_MODULE_ENABLED + #include "stm32f4xx_hal_eth.h" +#endif /* HAL_ETH_MODULE_ENABLED */ + +#ifdef HAL_FLASH_MODULE_ENABLED + #include "stm32f4xx_hal_flash.h" +#endif /* HAL_FLASH_MODULE_ENABLED */ + +#ifdef HAL_SRAM_MODULE_ENABLED + #include "stm32f4xx_hal_sram.h" +#endif /* HAL_SRAM_MODULE_ENABLED */ + +#ifdef HAL_NOR_MODULE_ENABLED + #include "stm32f4xx_hal_nor.h" +#endif /* HAL_NOR_MODULE_ENABLED */ + +#ifdef HAL_NAND_MODULE_ENABLED + #include "stm32f4xx_hal_nand.h" +#endif /* HAL_NAND_MODULE_ENABLED */ + +#ifdef HAL_PCCARD_MODULE_ENABLED + #include "stm32f4xx_hal_pccard.h" +#endif /* HAL_PCCARD_MODULE_ENABLED */ + +#ifdef HAL_SDRAM_MODULE_ENABLED + #include "stm32f4xx_hal_sdram.h" +#endif /* HAL_SDRAM_MODULE_ENABLED */ + +#ifdef HAL_HASH_MODULE_ENABLED + #include "stm32f4xx_hal_hash.h" +#endif /* HAL_HASH_MODULE_ENABLED */ + +#ifdef HAL_I2C_MODULE_ENABLED + #include "stm32f4xx_hal_i2c.h" +#endif /* HAL_I2C_MODULE_ENABLED */ + +#ifdef HAL_I2S_MODULE_ENABLED + #include "stm32f4xx_hal_i2s.h" +#endif /* HAL_I2S_MODULE_ENABLED */ + +#ifdef HAL_IWDG_MODULE_ENABLED + #include "stm32f4xx_hal_iwdg.h" +#endif /* HAL_IWDG_MODULE_ENABLED */ + +#ifdef HAL_LTDC_MODULE_ENABLED + #include "stm32f4xx_hal_ltdc.h" +#endif /* HAL_LTDC_MODULE_ENABLED */ + +#ifdef HAL_PWR_MODULE_ENABLED + #include "stm32f4xx_hal_pwr.h" +#endif /* HAL_PWR_MODULE_ENABLED */ + +#ifdef HAL_RNG_MODULE_ENABLED + #include "stm32f4xx_hal_rng.h" +#endif /* HAL_RNG_MODULE_ENABLED */ + +#ifdef HAL_RTC_MODULE_ENABLED + #include "stm32f4xx_hal_rtc.h" +#endif /* HAL_RTC_MODULE_ENABLED */ + +#ifdef HAL_SAI_MODULE_ENABLED + #include "stm32f4xx_hal_sai.h" +#endif /* HAL_SAI_MODULE_ENABLED */ + +#ifdef HAL_SD_MODULE_ENABLED + #include "stm32f4xx_hal_sd.h" +#endif /* HAL_SD_MODULE_ENABLED */ + +#ifdef HAL_SPI_MODULE_ENABLED + #include "stm32f4xx_hal_spi.h" +#endif /* HAL_SPI_MODULE_ENABLED */ + +#ifdef HAL_TIM_MODULE_ENABLED + #include "stm32f4xx_hal_tim.h" +#endif /* HAL_TIM_MODULE_ENABLED */ + +#ifdef HAL_UART_MODULE_ENABLED + #include "stm32f4xx_hal_uart.h" +#endif /* HAL_UART_MODULE_ENABLED */ + +#ifdef HAL_USART_MODULE_ENABLED + #include "stm32f4xx_hal_usart.h" +#endif /* HAL_USART_MODULE_ENABLED */ + +#ifdef HAL_IRDA_MODULE_ENABLED + #include "stm32f4xx_hal_irda.h" +#endif /* HAL_IRDA_MODULE_ENABLED */ + +#ifdef HAL_SMARTCARD_MODULE_ENABLED + #include "stm32f4xx_hal_smartcard.h" +#endif /* HAL_SMARTCARD_MODULE_ENABLED */ + +#ifdef HAL_WWDG_MODULE_ENABLED + #include "stm32f4xx_hal_wwdg.h" +#endif /* HAL_WWDG_MODULE_ENABLED */ + +#ifdef HAL_PCD_MODULE_ENABLED + #include "stm32f4xx_hal_pcd.h" +#endif /* HAL_PCD_MODULE_ENABLED */ + +#ifdef HAL_HCD_MODULE_ENABLED + #include "stm32f4xx_hal_hcd.h" +#endif /* HAL_HCD_MODULE_ENABLED */ + +/* Exported macro ------------------------------------------------------------*/ +#ifdef USE_FULL_ASSERT +/** + * @brief The assert_param macro is used for function's parameters check. + * @param expr: If expr is false, it calls assert_failed function + * which reports the name of the source file and the source + * line number of the call that failed. + * If expr is true, it returns no value. + * @retval None + */ + #define assert_param(expr) ((expr) ? (void)0U : assert_failed((uint8_t *)__FILE__, __LINE__)) +/* Exported functions ------------------------------------------------------- */ + void assert_failed(uint8_t* file, uint32_t line); +#else + #define assert_param(expr) ((void)0U) +#endif /* USE_FULL_ASSERT */ + + +#ifdef __cplusplus +} +#endif + +#endif /* __STM32F4xx_HAL_CONF_H */ + + +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ From 97e2629d647584681b2883f2081fa2cddb3d61cc Mon Sep 17 00:00:00 2001 From: hathach Date: Mon, 22 Jul 2019 18:58:45 +0700 Subject: [PATCH 9/9] change EPNUM for example --- examples/device/midi_test/src/usb_descriptors.c | 11 +++++++---- examples/device/msc_dual_lun/src/usb_descriptors.c | 11 +++++++---- 2 files changed, 14 insertions(+), 8 deletions(-) diff --git a/examples/device/midi_test/src/usb_descriptors.c b/examples/device/midi_test/src/usb_descriptors.c index 192dacfb..3eef02bb 100644 --- a/examples/device/midi_test/src/usb_descriptors.c +++ b/examples/device/midi_test/src/usb_descriptors.c @@ -71,10 +71,13 @@ enum CONFIG_TOTAL_LEN = TUD_CONFIG_DESC_LEN + TUD_MIDI_DESC_LEN }; -// Use Endpoint 2 instead of 1 due to NXP MCU -// 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 ... -#define EPNUM_MIDI 0x02 +#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 ... + #define EPNUM_MIDI 0x02 +#else + #define EPNUM_MIDI 0x01 +#endif uint8_t const desc_configuration[] = { diff --git a/examples/device/msc_dual_lun/src/usb_descriptors.c b/examples/device/msc_dual_lun/src/usb_descriptors.c index 26ebe190..1a71b7fc 100644 --- a/examples/device/msc_dual_lun/src/usb_descriptors.c +++ b/examples/device/msc_dual_lun/src/usb_descriptors.c @@ -68,10 +68,13 @@ enum CONFIG_TOTAL_LEN = TUD_CONFIG_DESC_LEN + TUD_MSC_DESC_LEN }; -// Use Endpoint 2 instead of 1 due to NXP MCU -// 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 ... -#define EPNUM_MSC 0x02 +#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 ... + #define EPNUM_MSC 0x02 +#else + #define EPNUM_MSC 0x01 +#endif uint8_t const desc_configuration[] = {