From 13f7121285946eb32965f1bffac7a8ccb656ecad Mon Sep 17 00:00:00 2001
From: hathach <thach@tinyusb.org>
Date: Mon, 16 Sep 2019 23:42:56 +0700
Subject: [PATCH 1/6] add pyboard v1.1 link to bsp

---
 docs/boards.md | 1 +
 1 file changed, 1 insertion(+)

diff --git a/docs/boards.md b/docs/boards.md
index 30b0eb958..5e33c3ee3 100644
--- a/docs/boards.md
+++ b/docs/boards.md
@@ -41,6 +41,7 @@ This code base already had supported for a handful of following boards
 
 ### ST STM32
 
+- [Micro Python PyBoard v1.1](https://store.micropython.org/product/PYBv1.1)
 - [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 F207zg Nucleo](https://www.st.com/en/evaluation-tools/nucleo-f207zg.html)

From 3440083bfd11245936b9d65831713d014a188b74 Mon Sep 17 00:00:00 2001
From: hathach <thach@tinyusb.org>
Date: Wed, 18 Sep 2019 14:38:56 +0700
Subject: [PATCH 2/6] added board feather stm32f045

---
 docs/boards.md                                |   1 +
 .../feather_stm32f405/STM32F405RGTx_FLASH.ld  | 189 +++++++
 hw/bsp/feather_stm32f405/board.mk             |  50 ++
 hw/bsp/feather_stm32f405/feather_stm32f405.c  | 198 +++++++
 hw/bsp/feather_stm32f405/stm32f4xx_hal_conf.h | 489 ++++++++++++++++++
 hw/bsp/pyboardv11/board.mk                    |   2 +-
 6 files changed, 928 insertions(+), 1 deletion(-)
 create mode 100644 hw/bsp/feather_stm32f405/STM32F405RGTx_FLASH.ld
 create mode 100644 hw/bsp/feather_stm32f405/board.mk
 create mode 100644 hw/bsp/feather_stm32f405/feather_stm32f405.c
 create mode 100644 hw/bsp/feather_stm32f405/stm32f4xx_hal_conf.h

diff --git a/docs/boards.md b/docs/boards.md
index 5e33c3ee3..fef682f48 100644
--- a/docs/boards.md
+++ b/docs/boards.md
@@ -41,6 +41,7 @@ This code base already had supported for a handful of following boards
 
 ### ST STM32
 
+- Adafruit Feather STM32F405 
 - [Micro Python PyBoard v1.1](https://store.micropython.org/product/PYBv1.1)
 - [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)
diff --git a/hw/bsp/feather_stm32f405/STM32F405RGTx_FLASH.ld b/hw/bsp/feather_stm32f405/STM32F405RGTx_FLASH.ld
new file mode 100644
index 000000000..57ef61e26
--- /dev/null
+++ b/hw/bsp/feather_stm32f405/STM32F405RGTx_FLASH.ld
@@ -0,0 +1,189 @@
+/*
+*****************************************************************************
+**
+
+**  File        : LinkerScript.ld
+**
+**  Abstract    : Linker script for STM32F405RGTx Device with
+**                1024KByte 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
+{
+RAM (xrw)      : ORIGIN = 0x20000000, LENGTH = 128K
+CCMRAM (rw)      : ORIGIN = 0x10000000, LENGTH = 64K
+FLASH (rx)      : ORIGIN = 0x8000000, LENGTH = 1024K
+}
+
+/* Define output sections */
+SECTIONS
+{
+  /* The startup code goes first into FLASH */
+  .isr_vector :
+  {
+    . = ALIGN(4);
+    KEEP(*(.isr_vector)) /* Startup code */
+    . = ALIGN(4);
+  } >FLASH
+
+  /* The program code and other data goes into FLASH */
+  .text :
+  {
+    . = ALIGN(4);
+    *(.text)           /* .text sections (code) */
+    *(.text*)          /* .text* sections (code) */
+    *(.glue_7)         /* glue arm to thumb code */
+    *(.glue_7t)        /* glue thumb to arm code */
+    *(.eh_frame)
+
+    KEEP (*(.init))
+    KEEP (*(.fini))
+
+    . = ALIGN(4);
+    _etext = .;        /* define a global symbols at end of code */
+  } >FLASH
+
+  /* Constant data goes into FLASH */
+  .rodata :
+  {
+    . = ALIGN(4);
+    *(.rodata)         /* .rodata sections (constants, strings, etc.) */
+    *(.rodata*)        /* .rodata* sections (constants, strings, etc.) */
+    . = ALIGN(4);
+  } >FLASH
+
+  .ARM.extab   : { *(.ARM.extab* .gnu.linkonce.armextab.*) } >FLASH
+  .ARM : {
+    __exidx_start = .;
+    *(.ARM.exidx*)
+    __exidx_end = .;
+  } >FLASH
+
+  .preinit_array     :
+  {
+    PROVIDE_HIDDEN (__preinit_array_start = .);
+    KEEP (*(.preinit_array*))
+    PROVIDE_HIDDEN (__preinit_array_end = .);
+  } >FLASH
+  .init_array :
+  {
+    PROVIDE_HIDDEN (__init_array_start = .);
+    KEEP (*(SORT(.init_array.*)))
+    KEEP (*(.init_array*))
+    PROVIDE_HIDDEN (__init_array_end = .);
+  } >FLASH
+  .fini_array :
+  {
+    PROVIDE_HIDDEN (__fini_array_start = .);
+    KEEP (*(SORT(.fini_array.*)))
+    KEEP (*(.fini_array*))
+    PROVIDE_HIDDEN (__fini_array_end = .);
+  } >FLASH
+
+  /* used by the startup to initialize data */
+  _sidata = LOADADDR(.data);
+
+  /* Initialized data sections goes into RAM, load LMA copy after code */
+  .data : 
+  {
+    . = ALIGN(4);
+    _sdata = .;        /* create a global symbol at data start */
+    *(.data)           /* .data sections */
+    *(.data*)          /* .data* sections */
+
+    . = ALIGN(4);
+    _edata = .;        /* define a global symbol at data end */
+  } >RAM AT> FLASH
+
+  _siccmram = LOADADDR(.ccmram);
+
+  /* CCM-RAM section 
+  * 
+  * IMPORTANT NOTE! 
+  * If initialized variables will be placed in this section,
+  * the startup code needs to be modified to copy the init-values.  
+  */
+  .ccmram :
+  {
+    . = ALIGN(4);
+    _sccmram = .;       /* create a global symbol at ccmram start */
+    *(.ccmram)
+    *(.ccmram*)
+    
+    . = ALIGN(4);
+    _eccmram = .;       /* create a global symbol at ccmram end */
+  } >CCMRAM 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/feather_stm32f405/board.mk b/hw/bsp/feather_stm32f405/board.mk
new file mode 100644
index 000000000..ef9777976
--- /dev/null
+++ b/hw/bsp/feather_stm32f405/board.mk
@@ -0,0 +1,50 @@
+CFLAGS += \
+  -DHSE_VALUE=12000000 \
+  -DSTM32F405xx \
+  -mthumb \
+  -mabi=aapcs \
+  -mcpu=cortex-m4 \
+  -mfloat-abi=hard \
+  -mfpu=fpv4-sp-d16 \
+  -nostdlib -nostartfiles \
+  -DCFG_TUSB_MCU=OPT_MCU_STM32F4
+
+ST_HAL_DRIVER = hw/mcu/st/st_driver/STM32F4xx_HAL_Driver
+ST_CMSIS = hw/mcu/st/st_driver/CMSIS/Device/ST/STM32F4xx
+
+# All source paths should be relative to the top level.
+LD_FILE = hw/bsp/pyboardv11/STM32F405RGTx_FLASH.ld
+
+SRC_C += \
+	$(ST_CMSIS)/Source/Templates/system_stm32f4xx.c \
+	$(ST_HAL_DRIVER)/Src/stm32f4xx_hal.c \
+	$(ST_HAL_DRIVER)/Src/stm32f4xx_hal_cortex.c \
+	$(ST_HAL_DRIVER)/Src/stm32f4xx_hal_rcc.c \
+	$(ST_HAL_DRIVER)/Src/stm32f4xx_hal_gpio.c
+
+SRC_S += \
+	$(ST_CMSIS)/Source/Templates/gcc/startup_stm32f405xx.s
+
+INC += \
+	$(TOP)/hw/mcu/st/st_driver/CMSIS/Include \
+	$(TOP)/$(ST_CMSIS)/Include \
+	$(TOP)/$(ST_HAL_DRIVER)/Inc \
+	$(TOP)/hw/bsp/$(BOARD)
+
+# For TinyUSB port source
+VENDOR = st
+CHIP_FAMILY = synopsys
+
+# For freeRTOS port source
+FREERTOS_PORT = ARM_CM4F
+
+# For flash-jlink target
+JLINK_DEVICE = stm32f405rg
+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/feather_stm32f405/feather_stm32f405.c b/hw/bsp/feather_stm32f405/feather_stm32f405.c
new file mode 100644
index 000000000..02c33a0a8
--- /dev/null
+++ b/hw/bsp/feather_stm32f405/feather_stm32f405.c
@@ -0,0 +1,198 @@
+/*
+ * 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"
+#include "stm32f4xx_hal_conf.h"
+
+// Blue LED is chosen because the other LEDs are connected to ST-LINK lines.
+#define LED_PORT              GPIOC
+#define LED_PIN               GPIO_PIN_4
+#define LED_STATE_ON          1
+
+// Pin D5
+#define BUTTON_PORT           GPIOC
+#define BUTTON_PIN            GPIO_PIN_7
+#define BUTTON_STATE_ACTIVE   0
+
+/**
+  * @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)              = 12000000
+  *            PLL_M                          = 12
+  *            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;
+
+  /* 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 = 12;
+  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);
+}
+
+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();
+
+  GPIO_InitTypeDef  GPIO_InitStruct;
+
+  // LED
+  __HAL_RCC_GPIOC_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);
+
+  // Button
+  //__HAL_RCC_GPIOC_CLK_ENABLE();
+  GPIO_InitStruct.Pin = BUTTON_PIN;
+  GPIO_InitStruct.Mode = GPIO_MODE_INPUT;
+  GPIO_InitStruct.Pull = GPIO_PULLUP;
+  GPIO_InitStruct.Speed = GPIO_SPEED_FAST;
+  HAL_GPIO_Init(BUTTON_PORT, &GPIO_InitStruct);
+
+  // Enable USB OTG clock
+  __HAL_RCC_USB_OTG_FS_CLK_ENABLE();
+
+  // USB Pin Init
+  // PA9- VUSB, PA10- ID, PA11- DM, PA12- DP
+  __HAL_RCC_GPIOA_CLK_ENABLE();
+
+  /* Configure DM DP Pins */
+  GPIO_InitStruct.Pin = GPIO_PIN_11 | GPIO_PIN_12;
+  GPIO_InitStruct.Speed = GPIO_SPEED_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);
+}
+
+//--------------------------------------------------------------------+
+// 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");
+}
+
+// Required by __libc_init_array in startup code if we are compiling using
+// -nostdlib/-nostartfiles.
+void _init(void)
+{
+
+}
diff --git a/hw/bsp/feather_stm32f405/stm32f4xx_hal_conf.h b/hw/bsp/feather_stm32f405/stm32f4xx_hal_conf.h
new file mode 100644
index 000000000..dbef20e0a
--- /dev/null
+++ b/hw/bsp/feather_stm32f405/stm32f4xx_hal_conf.h
@@ -0,0 +1,489 @@
+/**
+  ******************************************************************************
+  * @file    stm32f4xx_hal_conf.h
+  * @brief   HAL configuration file.
+  ******************************************************************************
+  * @attention
+  *
+  * <h2><center>&copy; COPYRIGHT(c) 2019 STMicroelectronics</center></h2>
+  *
+  * 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_CRYP_MODULE_ENABLED   */
+/* #define HAL_CAN_MODULE_ENABLED   */
+/* #define HAL_CRC_MODULE_ENABLED   */
+/* #define HAL_CRYP_MODULE_ENABLED   */
+/* #define HAL_DAC_MODULE_ENABLED   */
+/* #define HAL_DCMI_MODULE_ENABLED   */
+/* #define HAL_DMA2D_MODULE_ENABLED   */
+/* #define HAL_ETH_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_I2C_MODULE_ENABLED   */
+/* #define HAL_I2S_MODULE_ENABLED   */
+/* #define HAL_IWDG_MODULE_ENABLED   */
+/* #define HAL_LTDC_MODULE_ENABLED   */
+/* #define HAL_RNG_MODULE_ENABLED   */
+/* #define HAL_RTC_MODULE_ENABLED   */
+/* #define HAL_SAI_MODULE_ENABLED   */
+/* #define HAL_SD_MODULE_ENABLED   */
+/* #define HAL_MMC_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_PCD_MODULE_ENABLED
+/* #define HAL_HCD_MODULE_ENABLED   */
+/* #define HAL_DSI_MODULE_ENABLED   */
+/* #define HAL_QSPI_MODULE_ENABLED   */
+/* #define HAL_QSPI_MODULE_ENABLED   */
+/* #define HAL_CEC_MODULE_ENABLED   */
+/* #define HAL_FMPI2C_MODULE_ENABLED   */
+/* #define HAL_SPDIFRX_MODULE_ENABLED   */
+/* #define HAL_DFSDM_MODULE_ENABLED   */
+/* #define HAL_LPTIM_MODULE_ENABLED   */
+/* #define HAL_EXTI_MODULE_ENABLED   */
+#define HAL_GPIO_MODULE_ENABLED
+#define HAL_DMA_MODULE_ENABLED
+#define HAL_RCC_MODULE_ENABLED
+#define HAL_FLASH_MODULE_ENABLED
+#define HAL_PWR_MODULE_ENABLED
+#define HAL_CORTEX_MODULE_ENABLED
+
+/* ########################## HSE/HSI Values adaptation ##################### */
+/**
+  * @brief Adjust the value of External High Speed oscillator (HSE) used in your application.
+  *        This value is used by the RCC HAL module to compute the system frequency
+  *        (when HSE is used as system clock source, directly or through the PLL).
+  */
+#if !defined  (HSE_VALUE)
+  #define HSE_VALUE    ((uint32_t)12000000U) /*!< Value of the External oscillator in Hz */
+#endif /* HSE_VALUE */
+
+#if !defined  (HSE_STARTUP_TIMEOUT)
+  #define HSE_STARTUP_TIMEOUT    ((uint32_t)100U)   /*!< Time out for HSE start up, in ms */
+#endif /* HSE_STARTUP_TIMEOUT */
+
+/**
+  * @brief Internal High Speed oscillator (HSI) value.
+  *        This value is used by the RCC HAL module to compute the system frequency
+  *        (when HSI is used as system clock source, directly or through the PLL).
+  */
+#if !defined  (HSI_VALUE)
+  #define HSI_VALUE    ((uint32_t)16000000U) /*!< Value of the Internal oscillator in Hz*/
+#endif /* HSI_VALUE */
+
+/**
+  * @brief Internal Low Speed oscillator (LSI) value.
+  */
+#if !defined  (LSI_VALUE)
+ #define LSI_VALUE  ((uint32_t)32000U)       /*!< LSI Typical Value in Hz*/
+#endif /* LSI_VALUE */                      /*!< Value of the Internal Low Speed oscillator in Hz
+                                             The real value may vary depending on the variations
+                                             in voltage and temperature.*/
+/**
+  * @brief External Low Speed oscillator (LSE) value.
+  */
+#if !defined  (LSE_VALUE)
+ #define LSE_VALUE  ((uint32_t)32768U)    /*!< Value of the External Low Speed oscillator in Hz */
+#endif /* LSE_VALUE */
+
+#if !defined  (LSE_STARTUP_TIMEOUT)
+  #define LSE_STARTUP_TIMEOUT    ((uint32_t)5000U)   /*!< Time out for LSE start up, in ms */
+#endif /* LSE_STARTUP_TIMEOUT */
+
+/**
+  * @brief External clock source for I2S peripheral
+  *        This value is used by the I2S HAL module to compute the I2S clock source
+  *        frequency, this source is inserted directly through I2S_CKIN pad.
+  */
+#if !defined  (EXTERNAL_CLOCK_VALUE)
+  #define EXTERNAL_CLOCK_VALUE    ((uint32_t)12288000U) /*!< Value of the External audio frequency in Hz*/
+#endif /* EXTERNAL_CLOCK_VALUE */
+
+/* Tip: To avoid modifying this file each time you need to use different HSE,
+   ===  you can define the HSE value in your toolchain compiler preprocessor. */
+
+/* ########################### System Configuration ######################### */
+/**
+  * @brief This is the HAL system configuration section
+  */
+#define  VDD_VALUE		      ((uint32_t)3300U) /*!< Value of VDD in mv */
+#define  TICK_INT_PRIORITY            ((uint32_t)0U)   /*!< tick interrupt priority */
+#define  USE_RTOS                     0U
+#define  PREFETCH_ENABLE              1U
+#define  INSTRUCTION_CACHE_ENABLE     1U
+#define  DATA_CACHE_ENABLE            1U
+
+/* Copied over manually- STM32Cube didn't generate these for some reason. */
+#define  USE_HAL_ADC_REGISTER_CALLBACKS     0U /* ADC register callback disabled     */
+#define  USE_HAL_CEC_REGISTER_CALLBACKS     0U /* CEC register callback disabled     */
+#define  USE_HAL_COMP_REGISTER_CALLBACKS    0U /* COMP register callback disabled    */
+#define  USE_HAL_CRYP_REGISTER_CALLBACKS    0U /* CRYP register callback disabled    */
+#define  USE_HAL_DAC_REGISTER_CALLBACKS     0U /* DAC register callback disabled     */
+#define  USE_HAL_DCMI_REGISTER_CALLBACKS    0U /* DCMI register callback disabled    */
+#define  USE_HAL_DFSDM_REGISTER_CALLBACKS   0U /* DFSDM register callback disabled   */
+#define  USE_HAL_DMA2D_REGISTER_CALLBACKS   0U /* DMA2D register callback disabled   */
+#define  USE_HAL_DSI_REGISTER_CALLBACKS     0U /* DSI register callback disabled     */
+#define  USE_HAL_ETH_REGISTER_CALLBACKS     0U /* ETH register callback disabled     */
+#define  USE_HAL_FDCAN_REGISTER_CALLBACKS   0U /* FDCAN register callback disabled   */
+#define  USE_HAL_NAND_REGISTER_CALLBACKS    0U /* NAND register callback disabled    */
+#define  USE_HAL_NOR_REGISTER_CALLBACKS     0U /* NOR register callback disabled     */
+#define  USE_HAL_SDRAM_REGISTER_CALLBACKS   0U /* SDRAM register callback disabled   */
+#define  USE_HAL_SRAM_REGISTER_CALLBACKS    0U /* SRAM register callback disabled    */
+#define  USE_HAL_HASH_REGISTER_CALLBACKS    0U /* HASH register callback disabled    */
+#define  USE_HAL_HCD_REGISTER_CALLBACKS     0U /* HCD register callback disabled     */
+#define  USE_HAL_HRTIM_REGISTER_CALLBACKS   0U /* HRTIM register callback disabled   */
+#define  USE_HAL_I2C_REGISTER_CALLBACKS     0U /* I2C register callback disabled     */
+#define  USE_HAL_I2S_REGISTER_CALLBACKS     0U /* I2S register callback disabled     */
+#define  USE_HAL_JPEG_REGISTER_CALLBACKS    0U /* JPEG register callback disabled    */
+#define  USE_HAL_LPTIM_REGISTER_CALLBACKS   0U /* LPTIM register callback disabled   */
+#define  USE_HAL_LTDC_REGISTER_CALLBACKS    0U /* LTDC register callback disabled    */
+#define  USE_HAL_MDIOS_REGISTER_CALLBACKS   0U /* MDIO register callback disabled    */
+#define  USE_HAL_OPAMP_REGISTER_CALLBACKS   0U /* MDIO register callback disabled    */
+#define  USE_HAL_PCD_REGISTER_CALLBACKS     0U /* PCD register callback disabled     */
+#define  USE_HAL_QSPI_REGISTER_CALLBACKS    0U /* QSPI register callback disabled    */
+#define  USE_HAL_RNG_REGISTER_CALLBACKS     0U /* RNG register callback disabled     */
+#define  USE_HAL_RTC_REGISTER_CALLBACKS     0U /* RTC register callback disabled     */
+#define  USE_HAL_SAI_REGISTER_CALLBACKS     0U /* SAI register callback disabled     */
+#define  USE_HAL_SPDIFRX_REGISTER_CALLBACKS 0U /* SPDIFRX register callback disabled */
+#define  USE_HAL_SMBUS_REGISTER_CALLBACKS   0U /* SMBUS register callback disabled   */
+#define  USE_HAL_SPI_REGISTER_CALLBACKS     0U /* SPI register callback disabled     */
+#define  USE_HAL_SWPMI_REGISTER_CALLBACKS   0U /* SWPMI register callback disabled   */
+#define  USE_HAL_TIM_REGISTER_CALLBACKS     0U /* TIM register callback disabled     */
+#define  USE_HAL_WWDG_REGISTER_CALLBACKS    0U /* WWDG register callback disabled    */
+
+/* ########################## 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                    ((uint32_t)4U)       /* 4 Rx buffers of size ETH_RX_BUF_SIZE  */
+#define ETH_TXBUFNB                    ((uint32_t)4U)       /* 4 Tx buffers of size ETH_TX_BUF_SIZE  */
+
+/* Section 2: PHY configuration section */
+
+/* DP83848_PHY_ADDRESS Address*/
+#define DP83848_PHY_ADDRESS           0x01U
+/* PHY Reset delay these values are based on a 1 ms Systick interrupt*/
+#define PHY_RESET_DELAY                 ((uint32_t)0x000000FFU)
+/* PHY Configuration delay */
+#define PHY_CONFIG_DELAY                ((uint32_t)0x00000FFFU)
+
+#define PHY_READ_TO                     ((uint32_t)0x0000FFFFU)
+#define PHY_WRITE_TO                    ((uint32_t)0x0000FFFFU)
+
+/* Section 3: Common PHY Registers */
+
+#define PHY_BCR                         ((uint16_t)0x0000U)    /*!< Transceiver Basic Control Register   */
+#define PHY_BSR                         ((uint16_t)0x0001U)    /*!< Transceiver Basic Status Register    */
+
+#define PHY_RESET                       ((uint16_t)0x8000U)  /*!< PHY Reset */
+#define PHY_LOOPBACK                    ((uint16_t)0x4000U)  /*!< Select loop-back mode */
+#define PHY_FULLDUPLEX_100M             ((uint16_t)0x2100U)  /*!< Set the full-duplex mode at 100 Mb/s */
+#define PHY_HALFDUPLEX_100M             ((uint16_t)0x2000U)  /*!< Set the half-duplex mode at 100 Mb/s */
+#define PHY_FULLDUPLEX_10M              ((uint16_t)0x0100U)  /*!< Set the full-duplex mode at 10 Mb/s  */
+#define PHY_HALFDUPLEX_10M              ((uint16_t)0x0000U)  /*!< Set the half-duplex mode at 10 Mb/s  */
+#define PHY_AUTONEGOTIATION             ((uint16_t)0x1000U)  /*!< Enable auto-negotiation function     */
+#define PHY_RESTART_AUTONEGOTIATION     ((uint16_t)0x0200U)  /*!< Restart auto-negotiation function    */
+#define PHY_POWERDOWN                   ((uint16_t)0x0800U)  /*!< Select the power down mode           */
+#define PHY_ISOLATE                     ((uint16_t)0x0400U)  /*!< Isolate PHY from MII                 */
+
+#define PHY_AUTONEGO_COMPLETE           ((uint16_t)0x0020U)  /*!< Auto-Negotiation process completed   */
+#define PHY_LINKED_STATUS               ((uint16_t)0x0004U)  /*!< Valid link established               */
+#define PHY_JABBER_DETECTION            ((uint16_t)0x0002U)  /*!< Jabber condition detected            */
+
+/* Section 4: Extended PHY Registers */
+#define PHY_SR                          ((uint16_t)0x10U)    /*!< PHY status register Offset                      */
+
+#define PHY_SPEED_STATUS                ((uint16_t)0x0002U)  /*!< PHY Speed mask                                  */
+#define PHY_DUPLEX_STATUS               ((uint16_t)0x0004U)  /*!< PHY Duplex 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                     0U
+
+/* Includes ------------------------------------------------------------------*/
+/**
+  * @brief Include module's header file
+  */
+
+#ifdef HAL_RCC_MODULE_ENABLED
+  #include "stm32f4xx_hal_rcc.h"
+#endif /* HAL_RCC_MODULE_ENABLED */
+
+#ifdef HAL_EXTI_MODULE_ENABLED
+  #include "stm32f4xx_hal_exti.h"
+#endif /* HAL_EXTI_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_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_MMC_MODULE_ENABLED
+ #include "stm32f4xx_hal_mmc.h"
+#endif /* HAL_MMC_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 */
+
+#ifdef HAL_DSI_MODULE_ENABLED
+ #include "stm32f4xx_hal_dsi.h"
+#endif /* HAL_DSI_MODULE_ENABLED */
+
+#ifdef HAL_QSPI_MODULE_ENABLED
+ #include "stm32f4xx_hal_qspi.h"
+#endif /* HAL_QSPI_MODULE_ENABLED */
+
+#ifdef HAL_CEC_MODULE_ENABLED
+ #include "stm32f4xx_hal_cec.h"
+#endif /* HAL_CEC_MODULE_ENABLED */
+
+#ifdef HAL_FMPI2C_MODULE_ENABLED
+ #include "stm32f4xx_hal_fmpi2c.h"
+#endif /* HAL_FMPI2C_MODULE_ENABLED */
+
+#ifdef HAL_SPDIFRX_MODULE_ENABLED
+ #include "stm32f4xx_hal_spdifrx.h"
+#endif /* HAL_SPDIFRX_MODULE_ENABLED */
+
+#ifdef HAL_DFSDM_MODULE_ENABLED
+ #include "stm32f4xx_hal_dfsdm.h"
+#endif /* HAL_DFSDM_MODULE_ENABLED */
+
+#ifdef HAL_LPTIM_MODULE_ENABLED
+ #include "stm32f4xx_hal_lptim.h"
+#endif /* HAL_LPTIM_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****/
diff --git a/hw/bsp/pyboardv11/board.mk b/hw/bsp/pyboardv11/board.mk
index 2ba1d3900..ef9777976 100644
--- a/hw/bsp/pyboardv11/board.mk
+++ b/hw/bsp/pyboardv11/board.mk
@@ -39,7 +39,7 @@ CHIP_FAMILY = synopsys
 FREERTOS_PORT = ARM_CM4F
 
 # For flash-jlink target
-JLINK_DEVICE = stm32f407vg
+JLINK_DEVICE = stm32f405rg
 JLINK_IF = swd
 
 # Path to STM32 Cube Programmer CLI, should be added into system path

From 80b430fcfcf4dfe4d397212330e8eaba57a4a87e Mon Sep 17 00:00:00 2001
From: hathach <thach@tinyusb.org>
Date: Fri, 20 Sep 2019 13:02:17 +0700
Subject: [PATCH 3/6] added stm32L0538 discovery board, board test exmaple
 works

---
 examples/device/board_test/Makefile           |   3 +
 hw/bsp/stm32l0538disco/STM32L053C8Tx_FLASH.ld | 169 +++++++++
 hw/bsp/stm32l0538disco/board.mk               |  52 +++
 hw/bsp/stm32l0538disco/stm32l0538disco.c      | 187 ++++++++++
 hw/bsp/stm32l0538disco/stm32l0xx_hal_conf.h   | 331 ++++++++++++++++++
 5 files changed, 742 insertions(+)
 create mode 100644 hw/bsp/stm32l0538disco/STM32L053C8Tx_FLASH.ld
 create mode 100644 hw/bsp/stm32l0538disco/board.mk
 create mode 100644 hw/bsp/stm32l0538disco/stm32l0538disco.c
 create mode 100644 hw/bsp/stm32l0538disco/stm32l0xx_hal_conf.h

diff --git a/examples/device/board_test/Makefile b/examples/device/board_test/Makefile
index 5a455078e..e0c6d6ce2 100644
--- a/examples/device/board_test/Makefile
+++ b/examples/device/board_test/Makefile
@@ -5,6 +5,9 @@ INC += \
   src \
   $(TOP)/hw \
 
+# stop on the first build error, which is quite a lot of porting new board
+CFLAGS += -Wfatal-errors
+
 # Example source
 EXAMPLE_SOURCE += $(wildcard src/*.c)
 SRC_C += $(addprefix $(CURRENT_PATH)/, $(EXAMPLE_SOURCE))
diff --git a/hw/bsp/stm32l0538disco/STM32L053C8Tx_FLASH.ld b/hw/bsp/stm32l0538disco/STM32L053C8Tx_FLASH.ld
new file mode 100644
index 000000000..787418e09
--- /dev/null
+++ b/hw/bsp/stm32l0538disco/STM32L053C8Tx_FLASH.ld
@@ -0,0 +1,169 @@
+/*
+*****************************************************************************
+**
+
+**  File        : LinkerScript.ld
+**
+**  Abstract    : Linker script for STM32L053C8Tx Device with
+**                64KByte FLASH, 8KByte 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 = 0x20002000;    /* 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 = 0x200; /* required amount of stack */
+
+/* Specify the memory areas */
+MEMORY
+{
+FLASH (rx)      : ORIGIN = 0x08000000, LENGTH = 64K
+RAM (xrw)      : ORIGIN = 0x20000000, LENGTH = 8K
+}
+
+/* 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/stm32l0538disco/board.mk b/hw/bsp/stm32l0538disco/board.mk
new file mode 100644
index 000000000..f4088ba77
--- /dev/null
+++ b/hw/bsp/stm32l0538disco/board.mk
@@ -0,0 +1,52 @@
+CFLAGS += \
+	-DHSE_VALUE=8000000 \
+	-DSTM32L053xx \
+	-mthumb \
+	-mabi=aapcs \
+	-mcpu=cortex-m0plus \
+	-mfloat-abi=soft \
+	-nostdlib -nostartfiles \
+	-DCFG_TUSB_MCU=OPT_MCU_STM32L0
+
+#	-DCFG_EXAMPLE_MSC_READONLY \
+
+ST_HAL_DRIVER = hw/mcu/st/st_driver/STM32L0xx_HAL_Driver
+ST_CMSIS = hw/mcu/st/st_driver/CMSIS/Device/ST/STM32L0xx
+
+# All source paths should be relative to the top level.
+LD_FILE = hw/bsp/$(BOARD)/STM32L053C8Tx_FLASH.ld
+
+SRC_C += \
+	$(ST_CMSIS)/Source/Templates/system_stm32l0xx.c \
+	$(ST_HAL_DRIVER)/Src/stm32l0xx_hal.c \
+	$(ST_HAL_DRIVER)/Src/stm32l0xx_hal_cortex.c \
+	$(ST_HAL_DRIVER)/Src/stm32l0xx_hal_rcc.c \
+	$(ST_HAL_DRIVER)/Src/stm32l0xx_hal_rcc_ex.c \
+	$(ST_HAL_DRIVER)/Src/stm32l0xx_hal_gpio.c
+
+SRC_S += \
+	$(ST_CMSIS)/Source/Templates/gcc/startup_stm32l053xx.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_CM0
+
+# For flash-jlink target
+JLINK_DEVICE = STM32L053R8
+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/stm32l0538disco/stm32l0538disco.c b/hw/bsp/stm32l0538disco/stm32l0538disco.c
new file mode 100644
index 000000000..a3daaf0d2
--- /dev/null
+++ b/hw/bsp/stm32l0538disco/stm32l0538disco.c
@@ -0,0 +1,187 @@
+/* 
+ * 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 "stm32l0xx.h"
+#include "stm32l0xx_hal_conf.h"
+
+#define LED_PORT              GPIOA
+#define LED_PIN               GPIO_PIN_5
+#define LED_STATE_ON          1
+
+#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:
+  *         HSI48 used as USB clock source
+  *              - System Clock source            = HSI
+  *              - HSI Frequency(Hz)              = 16000000
+  *              - SYSCLK(Hz)                     = 16000000
+  *              - HCLK(Hz)                       = 16000000
+  *              - AHB Prescaler                  = 1
+  *              - APB1 Prescaler                 = 1
+  *              - APB2 Prescaler                 = 1
+  *              - Flash Latency(WS)              = 0
+  *              - Main regulator output voltage  = Scale1 mode
+  * @param  None
+  * @retval None
+  */
+static void SystemClock_Config(void)
+{
+  RCC_ClkInitTypeDef RCC_ClkInitStruct;
+  RCC_OscInitTypeDef RCC_OscInitStruct;
+  RCC_PeriphCLKInitTypeDef  PeriphClkInitStruct;
+  static RCC_CRSInitTypeDef RCC_CRSInitStruct;
+
+  /* Enable HSI Oscillator to be used as System clock source
+     Enable HSI48 Oscillator to be used as USB clock source */
+  RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_HSI | RCC_OSCILLATORTYPE_HSI48;
+  RCC_OscInitStruct.HSIState = RCC_HSI_ON;
+  RCC_OscInitStruct.HSI48State = RCC_HSI48_ON;
+  HAL_RCC_OscConfig(&RCC_OscInitStruct);
+
+  /* Select HSI48 as USB clock source */
+  PeriphClkInitStruct.PeriphClockSelection = RCC_PERIPHCLK_USB;
+  PeriphClkInitStruct.UsbClockSelection = RCC_USBCLKSOURCE_HSI48;
+  HAL_RCCEx_PeriphCLKConfig(&PeriphClkInitStruct);
+
+  /* Select HSI as system clock source and configure the HCLK, PCLK1 and PCLK2
+     clock dividers */
+  RCC_ClkInitStruct.ClockType = (RCC_CLOCKTYPE_SYSCLK | RCC_CLOCKTYPE_HCLK | RCC_CLOCKTYPE_PCLK1 | RCC_CLOCKTYPE_PCLK2);
+  RCC_ClkInitStruct.SYSCLKSource = RCC_SYSCLKSOURCE_HSI;
+  RCC_ClkInitStruct.AHBCLKDivider = RCC_SYSCLK_DIV1;
+  RCC_ClkInitStruct.APB1CLKDivider = RCC_HCLK_DIV1;
+  RCC_ClkInitStruct.APB2CLKDivider = RCC_HCLK_DIV1;
+  HAL_RCC_ClockConfig(&RCC_ClkInitStruct, FLASH_LATENCY_0);
+
+  /*Configure the clock recovery system (CRS)**********************************/
+
+  /*Enable CRS Clock*/
+  __HAL_RCC_CRS_CLK_ENABLE();
+
+  /* Default Synchro Signal division factor (not divided) */
+  RCC_CRSInitStruct.Prescaler = RCC_CRS_SYNC_DIV1;
+  /* Set the SYNCSRC[1:0] bits according to CRS_Source value */
+  RCC_CRSInitStruct.Source = RCC_CRS_SYNC_SOURCE_USB;
+  /* HSI48 is synchronized with USB SOF at 1KHz rate */
+  RCC_CRSInitStruct.ReloadValue =  __HAL_RCC_CRS_RELOADVALUE_CALCULATE(48000000, 1000);
+  RCC_CRSInitStruct.ErrorLimitValue = RCC_CRS_ERRORLIMIT_DEFAULT;
+  /* Set the TRIM[5:0] to the default value*/
+  RCC_CRSInitStruct.HSI48CalibrationValue = 0x20;
+  /* Start automatic synchronization */
+  HAL_RCCEx_CRSConfig (&RCC_CRSInitStruct);
+}
+
+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();
+
+  GPIO_InitTypeDef  GPIO_InitStruct;
+
+  // LED
+  __HAL_RCC_GPIOA_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);
+
+  // 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_FAST;
+  HAL_GPIO_Init(BUTTON_PORT, &GPIO_InitStruct);
+
+  // USB
+  /* Configure DM 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_VERY_HIGH;
+  HAL_GPIO_Init(GPIOA, &GPIO_InitStruct);
+
+  /* Enable USB FS Clock */
+  __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");
+}
+
+// Required by __libc_init_array in startup code if we are compiling using
+// -nostdlib/-nostartfiles.
+void _init(void)
+{
+
+}
diff --git a/hw/bsp/stm32l0538disco/stm32l0xx_hal_conf.h b/hw/bsp/stm32l0538disco/stm32l0xx_hal_conf.h
new file mode 100644
index 000000000..773b74e29
--- /dev/null
+++ b/hw/bsp/stm32l0538disco/stm32l0xx_hal_conf.h
@@ -0,0 +1,331 @@
+/**
+  ******************************************************************************
+  * @file    stm32l0xx_hal_conf.h
+  * @author  MCD Application Team
+  * @brief   HAL configuration file.
+  ******************************************************************************
+  *
+  * Copyright (c) 2016 STMicroelectronics International N.V. All rights reserved.
+  *
+  * Redistribution and use in source and binary forms, with or without 
+  * modification, are permitted, provided that the following conditions are met:
+  *
+  * 1. Redistribution 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 other 
+  *    contributors to this software may be used to endorse or promote products 
+  *    derived from this software without specific written permission.
+  * 4. This software, including modifications and/or derivative works of this 
+  *    software, must execute solely and exclusively on microcontroller or
+  *    microprocessor devices manufactured by or for STMicroelectronics.
+  * 5. Redistribution and use of this software other than as permitted under 
+  *    this license is void and will automatically terminate your rights under 
+  *    this license. 
+  *
+  * THIS SOFTWARE IS PROVIDED BY STMICROELECTRONICS AND CONTRIBUTORS "AS IS" 
+  * AND ANY EXPRESS, IMPLIED OR STATUTORY WARRANTIES, INCLUDING, BUT NOT 
+  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, FITNESS FOR A 
+  * PARTICULAR PURPOSE AND NON-INFRINGEMENT OF THIRD PARTY INTELLECTUAL PROPERTY
+  * RIGHTS ARE DISCLAIMED TO THE FULLEST EXTENT PERMITTED BY LAW. IN NO EVENT 
+  * SHALL STMICROELECTRONICS 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 __STM32L0xx_HAL_CONF_H
+#define __STM32L0xx_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_COMP_MODULE_ENABLED */ 
+/* #define HAL_CRC_MODULE_ENABLED */  
+/* #define HAL_CRYP_MODULE_ENABLED */ 
+/* #define HAL_DAC_MODULE_ENABLED */   
+#define HAL_DMA_MODULE_ENABLED
+/* #define HAL_FIREWALL_MODULE_ENABLED */
+#define HAL_FLASH_MODULE_ENABLED 
+#define HAL_GPIO_MODULE_ENABLED
+/* #define HAL_I2C_MODULE_ENABLED */
+/* #define HAL_I2S_MODULE_ENABLED */   
+/* #define HAL_IWDG_MODULE_ENABLED */
+/* #define HAL_LCD_MODULE_ENABLED */ 
+/* #define HAL_LPTIM_MODULE_ENABLED */
+#define HAL_PWR_MODULE_ENABLED  
+#define HAL_RCC_MODULE_ENABLED 
+//#define HAL_RNG_MODULE_ENABLED
+/* #define HAL_RTC_MODULE_ENABLED */
+//#define HAL_SPI_MODULE_ENABLED
+/* #define HAL_TIM_MODULE_ENABLED */   
+/* #define HAL_TSC_MODULE_ENABLED */
+/* #define HAL_UART_MODULE_ENABLED */ 
+/* #define HAL_USART_MODULE_ENABLED */ 
+/* #define HAL_IRDA_MODULE_ENABLED */
+/* #define HAL_SMARTCARD_MODULE_ENABLED */
+/* #define HAL_SMBUS_MODULE_ENABLED */   
+/* #define HAL_WWDG_MODULE_ENABLED */ 
+//#define HAL_PCD_MODULE_ENABLED
+#define HAL_CORTEX_MODULE_ENABLED
+/* #define HAL_PCD_MODULE_ENABLED */
+
+
+/* ########################## Oscillator Values adaptation ####################*/
+/**
+  * @brief Adjust the value of External High Speed oscillator (HSE) used in your application.
+  *        This value is used by the RCC HAL module to compute the system frequency
+  *        (when HSE is used as system clock source, directly or through the PLL).  
+  */
+#if !defined  (HSE_VALUE) 
+  #define HSE_VALUE    ((uint32_t)8000000U) /*!< Value of the External oscillator in Hz */
+#endif /* HSE_VALUE */
+
+#if !defined  (HSE_STARTUP_TIMEOUT)
+  #define HSE_STARTUP_TIMEOUT    ((uint32_t)100U)   /*!< Time out for HSE start up, in ms */
+#endif /* HSE_STARTUP_TIMEOUT */
+
+/**
+  * @brief Internal Multiple Speed oscillator (MSI) default value.
+  *        This value is the default MSI range value after Reset.
+  */
+#if !defined  (MSI_VALUE)
+  #define MSI_VALUE    ((uint32_t)2097152U) /*!< Value of the Internal oscillator in Hz*/
+#endif /* MSI_VALUE */
+
+/**
+  * @brief Internal High Speed oscillator (HSI) value.
+  *        This value is used by the RCC HAL module to compute the system frequency
+  *        (when HSI is used as system clock source, directly or through the PLL). 
+  */
+#if !defined  (HSI_VALUE)
+  #define HSI_VALUE    ((uint32_t)16000000U) /*!< Value of the Internal oscillator in Hz*/
+#endif /* HSI_VALUE */
+
+/**
+  * @brief Internal High Speed oscillator for USB (HSI48) value.
+  */
+#if !defined  (HSI48_VALUE) 
+#define HSI48_VALUE ((uint32_t)48000000U) /*!< Value of the Internal High Speed oscillator for USB in Hz.
+                                             The real value may vary depending on the variations
+                                             in voltage and temperature.  */
+#endif /* HSI48_VALUE */
+
+/**
+  * @brief Internal Low Speed oscillator (LSI) value.
+  */
+#if !defined  (LSI_VALUE) 
+ #define LSI_VALUE  ((uint32_t)37000U)       /*!< 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    ((uint32_t)32768U) /*!< Value of the External oscillator in Hz*/
+#endif /* LSE_VALUE */
+
+/**
+  * @brief Time out for LSE start up value in ms.
+  */
+#if !defined  (LSE_STARTUP_TIMEOUT)
+  #define LSE_STARTUP_TIMEOUT    ((uint32_t)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                    ((uint32_t)3300U) /*!< Value of VDD in mv */ 
+#define  TICK_INT_PRIORITY            ((uint32_t)0U)    /*!< tick interrupt priority */           
+#define  USE_RTOS                     0U     
+#define  PREFETCH_ENABLE              1U              
+#define  PREREAD_ENABLE               1U
+#define  BUFFER_CACHE_DISABLE         0U
+
+/* ########################## Assert Selection ############################## */
+/**
+  * @brief Uncomment the line below to expanse the "assert_param" macro in the 
+  *        HAL drivers code
+  */
+/* #define USE_FULL_ASSERT    1 */
+
+/* ################## 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 "stm32l0xx_hal_rcc.h"
+#endif /* HAL_RCC_MODULE_ENABLED */
+
+#ifdef HAL_GPIO_MODULE_ENABLED
+  #include "stm32l0xx_hal_gpio.h"
+#endif /* HAL_GPIO_MODULE_ENABLED */
+
+#ifdef HAL_DMA_MODULE_ENABLED
+  #include "stm32l0xx_hal_dma.h"
+#endif /* HAL_DMA_MODULE_ENABLED */
+   
+#ifdef HAL_CORTEX_MODULE_ENABLED
+  #include "stm32l0xx_hal_cortex.h"
+#endif /* HAL_CORTEX_MODULE_ENABLED */
+
+#ifdef HAL_ADC_MODULE_ENABLED
+  #include "stm32l0xx_hal_adc.h"
+#endif /* HAL_ADC_MODULE_ENABLED */
+
+#ifdef HAL_COMP_MODULE_ENABLED
+  #include "stm32l0xx_hal_comp.h"
+#endif /* HAL_COMP_MODULE_ENABLED */
+   
+#ifdef HAL_CRC_MODULE_ENABLED
+  #include "stm32l0xx_hal_crc.h"
+#endif /* HAL_CRC_MODULE_ENABLED */
+
+#ifdef HAL_CRYP_MODULE_ENABLED
+  #include "stm32l0xx_hal_cryp.h"
+#endif /* HAL_CRYP_MODULE_ENABLED */
+
+#ifdef HAL_DAC_MODULE_ENABLED
+  #include "stm32l0xx_hal_dac.h"
+#endif /* HAL_DAC_MODULE_ENABLED */
+
+#ifdef HAL_FIREWALL_MODULE_ENABLED
+  #include "stm32l0xx_hal_firewall.h"
+#endif /* HAL_FIREWALL_MODULE_ENABLED */
+
+#ifdef HAL_FLASH_MODULE_ENABLED
+  #include "stm32l0xx_hal_flash.h"
+#endif /* HAL_FLASH_MODULE_ENABLED */
+ 
+#ifdef HAL_I2C_MODULE_ENABLED
+ #include "stm32l0xx_hal_i2c.h"
+#endif /* HAL_I2C_MODULE_ENABLED */
+
+#ifdef HAL_I2S_MODULE_ENABLED
+ #include "stm32l0xx_hal_i2s.h"
+#endif /* HAL_I2S_MODULE_ENABLED */
+
+#ifdef HAL_IWDG_MODULE_ENABLED
+ #include "stm32l0xx_hal_iwdg.h"
+#endif /* HAL_IWDG_MODULE_ENABLED */
+
+#ifdef HAL_LCD_MODULE_ENABLED
+ #include "stm32l0xx_hal_lcd.h"
+#endif /* HAL_LCD_MODULE_ENABLED */
+
+#ifdef HAL_LPTIM_MODULE_ENABLED
+#include "stm32l0xx_hal_lptim.h"
+#endif /* HAL_LPTIM_MODULE_ENABLED */
+   
+#ifdef HAL_PWR_MODULE_ENABLED
+ #include "stm32l0xx_hal_pwr.h"
+#endif /* HAL_PWR_MODULE_ENABLED */
+
+#ifdef HAL_RNG_MODULE_ENABLED
+ #include "stm32l0xx_hal_rng.h"
+#endif /* HAL_RNG_MODULE_ENABLED */
+
+#ifdef HAL_RTC_MODULE_ENABLED
+  #include "stm32l0xx_hal_rtc.h"
+#endif /* HAL_RTC_MODULE_ENABLED */
+
+#ifdef HAL_SPI_MODULE_ENABLED
+ #include "stm32l0xx_hal_spi.h"
+#endif /* HAL_SPI_MODULE_ENABLED */
+
+#ifdef HAL_TIM_MODULE_ENABLED
+ #include "stm32l0xx_hal_tim.h"
+#endif /* HAL_TIM_MODULE_ENABLED */
+
+#ifdef HAL_TSC_MODULE_ENABLED
+  #include "stm32l0xx_hal_tsc.h"
+#endif /* HAL_TSC_MODULE_ENABLED */
+
+#ifdef HAL_UART_MODULE_ENABLED
+ #include "stm32l0xx_hal_uart.h"
+#endif /* HAL_UART_MODULE_ENABLED */
+
+#ifdef HAL_USART_MODULE_ENABLED
+ #include "stm32l0xx_hal_usart.h"
+#endif /* HAL_USART_MODULE_ENABLED */
+
+#ifdef HAL_IRDA_MODULE_ENABLED
+ #include "stm32l0xx_hal_irda.h"
+#endif /* HAL_IRDA_MODULE_ENABLED */
+
+#ifdef HAL_SMARTCARD_MODULE_ENABLED
+ #include "stm32l0xx_hal_smartcard.h"
+#endif /* HAL_SMARTCARD_MODULE_ENABLED */
+
+#ifdef HAL_SMBUS_MODULE_ENABLED
+ #include "stm32l0xx_hal_smbus.h"
+#endif /* HAL_SMBUS_MODULE_ENABLED */
+
+#ifdef HAL_WWDG_MODULE_ENABLED
+ #include "stm32l0xx_hal_wwdg.h"
+#endif /* HAL_WWDG_MODULE_ENABLED */
+
+#ifdef HAL_PCD_MODULE_ENABLED
+ #include "stm32l0xx_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 /* __STM32L0xx_HAL_CONF_H */
+ 
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

From 7b2f8cc73a758eefc2a308813d0081f08ddfeb2b Mon Sep 17 00:00:00 2001
From: hathach <thach@tinyusb.org>
Date: Fri, 20 Sep 2019 13:49:33 +0700
Subject: [PATCH 4/6] added stm32 L0 support

close #125
---
 examples/device/board_test/Makefile           |  3 -
 examples/make.mk                              |  1 +
 hw/bsp/stm32l0538disco/board.mk               |  2 +-
 src/portable/st/stm32_fsdev/dcd_stm32_fsdev.c | 38 ++++-----
 .../st/stm32_fsdev/dcd_stm32_fsdev_pvt_st.h   | 77 ++++++++++---------
 5 files changed, 63 insertions(+), 58 deletions(-)

diff --git a/examples/device/board_test/Makefile b/examples/device/board_test/Makefile
index e0c6d6ce2..5a455078e 100644
--- a/examples/device/board_test/Makefile
+++ b/examples/device/board_test/Makefile
@@ -5,9 +5,6 @@ INC += \
   src \
   $(TOP)/hw \
 
-# stop on the first build error, which is quite a lot of porting new board
-CFLAGS += -Wfatal-errors
-
 # Example source
 EXAMPLE_SOURCE += $(wildcard src/*.c)
 SRC_C += $(addprefix $(CURRENT_PATH)/, $(EXAMPLE_SOURCE))
diff --git a/examples/make.mk b/examples/make.mk
index b0aa5659e..f35195fde 100644
--- a/examples/make.mk
+++ b/examples/make.mk
@@ -58,6 +58,7 @@ CFLAGS += \
 	-Wall \
 	-Werror \
 	-Werror-implicit-function-declaration \
+	-Wfatal-errors \
 	-Wfloat-equal \
 	-Wundef \
 	-Wshadow \
diff --git a/hw/bsp/stm32l0538disco/board.mk b/hw/bsp/stm32l0538disco/board.mk
index f4088ba77..3b84159d1 100644
--- a/hw/bsp/stm32l0538disco/board.mk
+++ b/hw/bsp/stm32l0538disco/board.mk
@@ -6,9 +6,9 @@ CFLAGS += \
 	-mcpu=cortex-m0plus \
 	-mfloat-abi=soft \
 	-nostdlib -nostartfiles \
+	-DCFG_EXAMPLE_MSC_READONLY \
 	-DCFG_TUSB_MCU=OPT_MCU_STM32L0
 
-#	-DCFG_EXAMPLE_MSC_READONLY \
 
 ST_HAL_DRIVER = hw/mcu/st/st_driver/STM32L0xx_HAL_Driver
 ST_CMSIS = hw/mcu/st/st_driver/CMSIS/Device/ST/STM32L0xx
diff --git a/src/portable/st/stm32_fsdev/dcd_stm32_fsdev.c b/src/portable/st/stm32_fsdev/dcd_stm32_fsdev.c
index aec8ea0c7..d83098fd9 100644
--- a/src/portable/st/stm32_fsdev/dcd_stm32_fsdev.c
+++ b/src/portable/st/stm32_fsdev/dcd_stm32_fsdev.c
@@ -106,14 +106,17 @@
 
 #include "tusb_option.h"
 
+#define STM32F1_FSDEV   ( \
+    defined(STM32F102x6) || defined(STM32F102xB) || \
+    defined(STM32F103x6) || defined(STM32F103xB) || \
+    defined(STM32F103xE) || defined(STM32F103xG)   \
+)
+
 #if (TUSB_OPT_DEVICE_ENABLED) && ( \
-      ((CFG_TUSB_MCU) == OPT_MCU_STM32F0) || \
-      (((CFG_TUSB_MCU) == OPT_MCU_STM32F1) && ( \
-          defined(stm32f102x6) || defined(stm32f102xb) || \
-          defined(stm32f103x6) || defined(stm32f103xb) || \
-          defined(stm32f103xe) || defined(stm32f103xg) \
-      )) || \
-      ((CFG_TUSB_MCU) == OPT_MCU_STM32F3) \
+      (CFG_TUSB_MCU == OPT_MCU_STM32F0                  ) || \
+      (CFG_TUSB_MCU == OPT_MCU_STM32F1 && STM32F1_FSDEV ) || \
+      (CFG_TUSB_MCU == OPT_MCU_STM32F3                  ) || \
+      (CFG_TUSB_MCU == OPT_MCU_STM32L0                  ) \
     )
 
 // In order to reduce the dependance on HAL, we undefine this.
@@ -165,7 +168,7 @@ typedef struct
 
 static xfer_ctl_t xfer_status[MAX_EP_COUNT][2];
 
-static xfer_ctl_t* xfer_ctl_ptr(uint32_t epnum, uint32_t dir)
+static inline xfer_ctl_t* xfer_ctl_ptr(uint32_t epnum, uint32_t dir)
 {
   return &xfer_status[epnum][dir];
 }
@@ -252,9 +255,10 @@ void dcd_init (uint8_t rhport)
 void dcd_int_enable (uint8_t rhport)
 {
   (void)rhport;
-#if defined(STM32F0)
+
+#if CFG_TUSB_MCU == OPT_MCU_STM32F0 || CFG_TUSB_MCU == OPT_MCU_STM32L0
   NVIC_EnableIRQ(USB_IRQn);
-#elif defined(STM32F3)
+#elif CFG_TUSB_MCU == OPT_MCU_STM32F3
   NVIC_EnableIRQ(USB_HP_CAN_TX_IRQn);
   NVIC_EnableIRQ(USB_LP_CAN_RX0_IRQn);
   NVIC_EnableIRQ(USBWakeUp_IRQn);
@@ -265,14 +269,15 @@ void dcd_int_enable (uint8_t rhport)
 void dcd_int_disable(uint8_t rhport)
 {
   (void)rhport;
-#if defined(STM32F0)
+
+#if CFG_TUSB_MCU == OPT_MCU_STM32F0 || CFG_TUSB_MCU == OPT_MCU_STM32L0
   NVIC_DisableIRQ(USB_IRQn);
-#elif defined(STM32F3)
+#elif CFG_TUSB_MCU == OPT_MCU_STM32F3
   NVIC_DisableIRQ(USB_HP_CAN_TX_IRQn);
   NVIC_DisableIRQ(USB_LP_CAN_RX0_IRQn);
   NVIC_DisableIRQ(USBWakeUp_IRQn);
 #else
-#error Unknown arch in USB driver
+  #error Unknown arch in USB driver
 #endif
   // I'm not convinced that memory synchronization is completely necessary, but
   // it isn't a bad idea.
@@ -305,7 +310,7 @@ void dcd_remote_wakeup(uint8_t rhport)
 {
   (void) rhport;
 
-  USB->CNTR |= (uint16_t)USB_CNTR_RESUME;
+  USB->CNTR |= (uint16_t) USB_CNTR_RESUME;
   remoteWakeCountdown = 4u; // required to be 1 to 15 ms, ESOF should trigger every 1ms.
 }
 
@@ -448,14 +453,11 @@ static uint16_t dcd_ep_ctr_handler(void)
           {
             pcd_set_ep_rx_status(USB, EPindex, USB_EP_RX_VALID);// Await next SETUP
           }
-
         }
-
       }
     }
     else /* Decode and service non control endpoints interrupt  */
     {
-
       /* process related endpoint register */
       wEPVal = pcd_get_endpoint(USB, EPindex);
       if ((wEPVal & USB_EP_CTR_RX) != 0U) // OUT
@@ -809,7 +811,7 @@ static bool dcd_read_packet_memory(void *__restrict dst, uint16_t src, size_t wN
 
 
 // Interrupt handlers
-#if (CFG_TUSB_MCU) == (OPT_MCU_STM32F0)
+#if CFG_TUSB_MCU == OPT_MCU_STM32F0 || CFG_TUSB_MCU == OPT_MCU_STM32L0
 void USB_IRQHandler(void)
 {
   dcd_fs_irqHandler();
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 ff25df048..30538541a 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
@@ -41,51 +41,56 @@
 #ifndef PORTABLE_ST_STM32F0_DCD_STM32F0_FSDEV_PVT_ST_H_
 #define PORTABLE_ST_STM32F0_DCD_STM32F0_FSDEV_PVT_ST_H_
 
-#if defined(STM32F042x6) | \
-    defined(STM32F070x6) | defined(STM32F070xB) | \
-    defined(STM32F072xB) | \
+#if defined(STM32F042x6) || \
+    defined(STM32F070x6) || defined(STM32F070xB) || \
+    defined(STM32F072xB) || \
     defined(STM32F078xx)
-#include "stm32f0xx.h"
-#define PMA_LENGTH (1024u)
-// F0x2 models are crystal-less
-// All have internal D+ pull-up
-// 070RB:    2 x 16 bits/word memory     LPM Support, BCD Support
-// PMA dedicated to USB (no sharing with CAN)
-#elif defined(STM32F102x6) | defined(STM32F102x6) | \
-      defined(STM32F103x6) | defined(STM32F103xB) | \
-      defined(STM32F103xE) | defined(STM32F103xB)
-#include "stm32f1xx.h"
-#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?
+  #include "stm32f0xx.h"
+  #define PMA_LENGTH (1024u)
+  // F0x2 models are crystal-less
+  // All have internal D+ pull-up
+  // 070RB:    2 x 16 bits/word memory     LPM Support, BCD Support
+  // PMA dedicated to USB (no sharing with CAN)
 
-#elif defined(STM32F302xB) | defined(STM32F302xC) | \
-      defined(STM32F303xB) | defined(STM32F303xC) | \
+#elif STM32F1_FSDEV
+  #include "stm32f1xx.h"
+  #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?
+
+#elif defined(STM32F302xB) || defined(STM32F302xC) || \
+      defined(STM32F303xB) || defined(STM32F303xC) || \
       defined(STM32F373xC)
-#include "stm32f3xx.h"
-#define PMA_LENGTH (512u)
-// NO internal Pull-ups
-//         *B, and *C:    1 x 16 bits/word
-// PMA dedicated to USB (no sharing with CAN)
-#elif defined(STM32F302x6) | defined(STM32F302x8) | \
-      defined(STM32F302xD) | defined(STM32F302xE) | \
-      defined(STM32F303xD) | defined(STM32F303xE) | \
-#include "stm32f3xx.h"
-#define PMA_LENGTH (1024u)
-// NO internal Pull-ups
-// *6, *8, *D, and *E:    2 x 16 bits/word     LPM Support
-// When CAN clock is enabled, USB can use first 768 bytes ONLY.
+  #include "stm32f3xx.h"
+  #define PMA_LENGTH (512u)
+  // NO internal Pull-ups
+  //         *B, and *C:    1 x 16 bits/word
+  // PMA dedicated to USB (no sharing with CAN)
+
+#elif defined(STM32F302x6) || defined(STM32F302x8) || \
+      defined(STM32F302xD) || defined(STM32F302xE) || \
+      defined(STM32F303xD) || defined(STM32F303xE)
+  #include "stm32f3xx.h"
+  #define PMA_LENGTH (1024u)
+  // NO internal Pull-ups
+  // *6, *8, *D, and *E:    2 x 16 bits/word     LPM Support
+  // When CAN clock is enabled, USB can use first 768 bytes ONLY.
+
+#elif CFG_TUSB_MCU == OPT_MCU_STM32L0
+  #include "stm32l0xx.h"
+  #define PMA_LENGTH (1024u)
+
 #else
-#error You are using an untested or unimplemented STM32 variant. Please update the driver.
-// This includes L0x2, L0x3, L1x0, L1x1, L1x2, L4x2 and L4x3, G1x1, G1x3, and G1x4
+  #error You are using an untested or unimplemented STM32 variant. Please update the driver.
+  // This includes L1x0, L1x1, L1x2, L4x2 and L4x3, G1x1, G1x3, and G1x4
 #endif
 
 // For purposes of accessing the packet
 #if ((PMA_LENGTH) == 512u)
-#define PMA_STRIDE  (2u)
+  #define PMA_STRIDE  (2u)
 #elif ((PMA_LENGTH) == 1024u)
-#define PMA_STRIDE  (1u)
+  #define PMA_STRIDE  (1u)
 #endif
 
 // And for type-safety create a new macro for the volatile address of PMAADDR

From 94c9cf0eff7973475e4f6d93cc96c2c86b541b08 Mon Sep 17 00:00:00 2001
From: hathach <thach@tinyusb.org>
Date: Fri, 20 Sep 2019 16:14:35 +0700
Subject: [PATCH 5/6] doc update

---
 README.md                                     | 26 +++++++++----------
 docs/boards.md                                |  1 +
 src/portable/st/stm32_fsdev/dcd_stm32_fsdev.c |  5 +---
 3 files changed, 15 insertions(+), 17 deletions(-)

diff --git a/README.md b/README.md
index 0fbfaec37..a811e3b49 100644
--- a/README.md
+++ b/README.md
@@ -21,6 +21,17 @@ TinyUSB is an open-source cross-platform USB Host/Device stack for embedded syst
 └── tools           # Files used internally
 ```
 
+## Supported MCUs
+
+The stack supports the following MCUs
+
+- **Nordic:** nRF52840
+- **NXP:** LPC11Uxx, LPC13xx, LPC175x_6x, LPC177x_8x, LPC18xx, LPC40xx, LPC43xx, LPC51Uxx
+- **MicroChip:** SAMD21, SAMD51 (device only)
+- **ST:** STM32 series: L0, F0, F2, F3, F4, F7, H7 (device only)
+
+[Here is the list of supported Boards](docs/boards.md) that can be used with provided examples.
+
 ## Device Stack
 
 Support multiple device configurations by dynamically changing usb descriptors. Low power functions such as suspend, resume and remote wakeup. Following device classes are supported:
@@ -42,23 +53,12 @@ Support multiple device configurations by dynamically changing usb descriptors.
 
 ## OS Abtraction layer
 
-Currently the following OS are supported with tinyusb out of the box with a simple change of **CFG_TUSB_OS** macro.
+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.
 
-- **No OS**
+- **No OS** : Disabling USB IRQ is used as way to provide mutex
 - **FreeRTOS**
 - **Mynewt** Due to the newt package build system, Mynewt examples are better to be on its [own repo](https://github.com/hathach/mynewt-tinyusb-example) 
 
-## Supported MCUs
-
-The stack supports the following MCUs
-
-- **Nordic:** nRF52840
-- **NXP:** LPC11Uxx, LPC13xx, LPC175x_6x, LPC177x_8x, LPC18xx, LPC40xx, LPC43xx, LPC51Uxx
-- **MicroChip:** SAMD21, SAMD51 (device only)
-- **ST:** STM32F0, STM32F2, STM32F3, STM32F4, STM32F7, STM32H7 (device only)
-
-[Here is the list of supported Boards](docs/boards.md)
-
 ## Compiler & IDE
 
 The stack is developed with GCC compiler, and should be compilable with others. Folder `examples` provide Makefile and Segger Embedded Studio build support. [Here is instruction to build example](examples/readme.md).
diff --git a/docs/boards.md b/docs/boards.md
index fef682f48..b6b48a7f1 100644
--- a/docs/boards.md
+++ b/docs/boards.md
@@ -43,6 +43,7 @@ This code base already had supported for a handful of following boards
 
 - Adafruit Feather STM32F405 
 - [Micro Python PyBoard v1.1](https://store.micropython.org/product/PYBv1.1)
+- [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 F207zg Nucleo](https://www.st.com/en/evaluation-tools/nucleo-f207zg.html)
diff --git a/src/portable/st/stm32_fsdev/dcd_stm32_fsdev.c b/src/portable/st/stm32_fsdev/dcd_stm32_fsdev.c
index d83098fd9..9bd4d2362 100644
--- a/src/portable/st/stm32_fsdev/dcd_stm32_fsdev.c
+++ b/src/portable/st/stm32_fsdev/dcd_stm32_fsdev.c
@@ -30,10 +30,7 @@
 
 /**********************************************
  * This driver has been tested with the following MCUs:
- * 
- * 
- * STM32F070RB
- *
+ *  - F070, F072, L053
  *
  * It also should work with minimal changes for any ST MCU with an "USB A"/"PCD"/"HCD" peripheral. This
  *  covers:

From c975976a7565a6186f503b0ce106b6ba84805091 Mon Sep 17 00:00:00 2001
From: hathach <thach@tinyusb.org>
Date: Fri, 20 Sep 2019 23:05:08 +0700
Subject: [PATCH 6/6] update doc

---
 README.md | 2 +-
 1 file changed, 1 insertion(+), 1 deletion(-)

diff --git a/README.md b/README.md
index a811e3b49..0a9cd770c 100644
--- a/README.md
+++ b/README.md
@@ -53,7 +53,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. 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**