group all stm32f4 boards

This commit is contained in:
hathach 2020-11-29 22:48:21 +07:00
parent daf9d06c0e
commit 0dd78aa916
42 changed files with 877 additions and 1875 deletions

View File

@ -1,54 +0,0 @@
CFLAGS += \
-flto \
-mthumb \
-mabi=aapcs \
-mcpu=cortex-m4 \
-mfloat-abi=hard \
-mfpu=fpv4-sp-d16 \
-nostdlib -nostartfiles \
-DSTM32F405xx \
-DCFG_TUSB_MCU=OPT_MCU_STM32F4
# suppress warning caused by vendor mcu driver
CFLAGS += -Wno-error=cast-align
ST_FAMILY = f4
ST_CMSIS = hw/mcu/st/cmsis_device_$(ST_FAMILY)
ST_HAL_DRIVER = hw/mcu/st/stm32$(ST_FAMILY)xx_hal_driver
# All source paths should be relative to the top level.
LD_FILE = hw/bsp/$(BOARD)/STM32F405RGTx_FLASH.ld
SRC_C += \
$(ST_CMSIS)/Source/Templates/system_stm32$(ST_FAMILY)xx.c \
$(ST_HAL_DRIVER)/Src/stm32$(ST_FAMILY)xx_hal.c \
$(ST_HAL_DRIVER)/Src/stm32$(ST_FAMILY)xx_hal_cortex.c \
$(ST_HAL_DRIVER)/Src/stm32$(ST_FAMILY)xx_hal_rcc.c \
$(ST_HAL_DRIVER)/Src/stm32$(ST_FAMILY)xx_hal_gpio.c \
$(ST_HAL_DRIVER)/Src/stm32$(ST_FAMILY)xx_hal_uart.c
SRC_S += \
$(ST_CMSIS)/Source/Templates/gcc/startup_stm32f405xx.s
INC += \
$(TOP)/lib/CMSIS_5/CMSIS/Core/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
# Path to STM32 Cube Programmer CLI, should be added into system path
STM32Prog = STM32_Programmer_CLI
# flash target ROM bootloader
flash: $(BUILD)/$(BOARD)-firmware.bin
dfu-util -R -a 0 --dfuse-address 0x08000000 -D $<

View File

@ -1,249 +0,0 @@
/*
* The MIT License (MIT)
*
* Copyright (c) 2019 Ha Thach (tinyusb.org)
*
* Permission is hereby granted, free of charge, to any person obtaining a copy
* of this software and associated documentation files (the "Software"), to deal
* in the Software without restriction, including without limitation the rights
* to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
* copies of the Software, and to permit persons to whom the Software is
* furnished to do so, subject to the following conditions:
*
* The above copyright notice and this permission notice shall be included in
* all copies or substantial portions of the Software.
*
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
* IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
* AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
* LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
* OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
* THE SOFTWARE.
*
* This file is part of the TinyUSB stack.
*/
#include "../board.h"
#include "stm32f4xx.h"
#include "stm32f4xx_hal_conf.h"
//--------------------------------------------------------------------+
// Forward USB interrupt events to TinyUSB IRQ Handler
//--------------------------------------------------------------------+
void OTG_FS_IRQHandler(void)
{
tud_int_handler(0);
}
//--------------------------------------------------------------------+
// MACRO TYPEDEF CONSTANT ENUM
//--------------------------------------------------------------------+
// Blue LED is chosen because the other LEDs are connected to ST-LINK lines.
#define LED_PORT GPIOC
#define LED_PIN GPIO_PIN_1
#define LED_STATE_ON 1
// Pin D5
#define BUTTON_PORT GPIOC
#define BUTTON_PIN GPIO_PIN_7
#define BUTTON_STATE_ACTIVE 0
#define UARTx USART3
#define UART_GPIO_PORT GPIOB
#define UART_GPIO_AF GPIO_AF7_USART3
#define UART_TX_PIN GPIO_PIN_10
#define UART_RX_PIN GPIO_PIN_11
UART_HandleTypeDef UartHandle;
// enable all LED, Button, Uart, USB clock
static void all_rcc_clk_enable(void)
{
__HAL_RCC_GPIOA_CLK_ENABLE(); // USB D+, D-
__HAL_RCC_GPIOC_CLK_ENABLE(); // LED, Button
__HAL_RCC_GPIOB_CLK_ENABLE(); // Uart tx, rx
__HAL_RCC_USART3_CLK_ENABLE(); // Uart module
}
/**
* @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 = HSE_VALUE/1000000
* 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 = HSE_VALUE/1000000;
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();
SystemCoreClockUpdate();
all_rcc_clk_enable();
GPIO_InitTypeDef GPIO_InitStruct;
// LED
GPIO_InitStruct.Pin = LED_PIN;
GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_PP;
GPIO_InitStruct.Pull = GPIO_PULLUP;
GPIO_InitStruct.Speed = GPIO_SPEED_FAST;
HAL_GPIO_Init(LED_PORT, &GPIO_InitStruct);
board_led_write(false);
// Button
GPIO_InitStruct.Pin = BUTTON_PIN;
GPIO_InitStruct.Mode = GPIO_MODE_INPUT;
GPIO_InitStruct.Pull = GPIO_PULLUP;
GPIO_InitStruct.Speed = GPIO_SPEED_FAST;
HAL_GPIO_Init(BUTTON_PORT, &GPIO_InitStruct);
// Uart
GPIO_InitStruct.Pin = UART_TX_PIN | UART_RX_PIN;
GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
GPIO_InitStruct.Pull = GPIO_PULLUP;
GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_HIGH;
GPIO_InitStruct.Alternate = UART_GPIO_AF;
HAL_GPIO_Init(UART_GPIO_PORT, &GPIO_InitStruct);
// USB Pin Init
// PA9- VUSB, PA10- ID, PA11- DM, PA12- DP
/* Configure DM DP Pins */
GPIO_InitStruct.Pin = GPIO_PIN_11 | GPIO_PIN_12;
GPIO_InitStruct.Speed = GPIO_SPEED_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);
// Enable USB OTG clock
__HAL_RCC_USB_OTG_FS_CLK_ENABLE();
// Enable VBUS sense (B device) via pin PA9
USB_OTG_FS->GCCFG &= ~USB_OTG_GCCFG_NOVBUSSENS;
USB_OTG_FS->GCCFG |= USB_OTG_GCCFG_VBUSBSEN;
}
//--------------------------------------------------------------------+
// Board porting API
//--------------------------------------------------------------------+
void board_led_write(bool state)
{
HAL_GPIO_WritePin(LED_PORT, LED_PIN, state ? LED_STATE_ON : (1-LED_STATE_ON));
}
uint32_t board_button_read(void)
{
return BUTTON_STATE_ACTIVE == HAL_GPIO_ReadPin(BUTTON_PORT, BUTTON_PIN);
}
int board_uart_read(uint8_t* buf, int len)
{
(void) buf; (void) len;
return 0;
}
int board_uart_write(void const * buf, int len)
{
HAL_UART_Transmit(&UartHandle, (uint8_t*) buf, len, 0xffff);
return len;
}
#if CFG_TUSB_OS == OPT_OS_NONE
volatile uint32_t system_ticks = 0;
void SysTick_Handler (void)
{
system_ticks++;
}
uint32_t board_millis(void)
{
return system_ticks;
}
#endif
void HardFault_Handler (void)
{
asm("bkpt");
}
// Required by __libc_init_array in startup code if we are compiling using
// -nostdlib/-nostartfiles.
void _init(void)
{
}

View File

@ -1,46 +0,0 @@
CFLAGS += \
-flto \
-mthumb \
-mabi=aapcs \
-mcpu=cortex-m4 \
-mfloat-abi=hard \
-mfpu=fpv4-sp-d16 \
-nostdlib -nostartfiles \
-DSTM32F405xx \
-DCFG_TUSB_MCU=OPT_MCU_STM32F4
ST_FAMILY = f4
ST_CMSIS = hw/mcu/st/cmsis_device_$(ST_FAMILY)
ST_HAL_DRIVER = hw/mcu/st/stm32$(ST_FAMILY)xx_hal_driver
# All source paths should be relative to the top level.
LD_FILE = hw/bsp/$(BOARD)/STM32F405RGTx_FLASH.ld
SRC_C += \
$(ST_CMSIS)/Source/Templates/system_stm32$(ST_FAMILY)xx.c \
$(ST_HAL_DRIVER)/Src/stm32$(ST_FAMILY)xx_hal.c \
$(ST_HAL_DRIVER)/Src/stm32$(ST_FAMILY)xx_hal_cortex.c \
$(ST_HAL_DRIVER)/Src/stm32$(ST_FAMILY)xx_hal_rcc.c \
$(ST_HAL_DRIVER)/Src/stm32$(ST_FAMILY)xx_hal_gpio.c
SRC_S += \
$(ST_CMSIS)/Source/Templates/gcc/startup_stm32f405xx.s
INC += \
$(TOP)/lib/CMSIS_5/CMSIS/Core/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
# flash target using on-board stlink
flash: flash-stlink

View File

@ -1,232 +0,0 @@
/*
* The MIT License (MIT)
*
* Copyright (c) 2019 Ha Thach (tinyusb.org)
*
* Permission is hereby granted, free of charge, to any person obtaining a copy
* of this software and associated documentation files (the "Software"), to deal
* in the Software without restriction, including without limitation the rights
* to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
* copies of the Software, and to permit persons to whom the Software is
* furnished to do so, subject to the following conditions:
*
* The above copyright notice and this permission notice shall be included in
* all copies or substantial portions of the Software.
*
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
* IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
* AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
* LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
* OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
* THE SOFTWARE.
*
* This file is part of the TinyUSB stack.
*/
#include "../board.h"
#include "stm32f4xx.h"
#include "stm32f4xx_hal_conf.h"
//--------------------------------------------------------------------+
// Forward USB interrupt events to TinyUSB IRQ Handler
//--------------------------------------------------------------------+
void OTG_FS_IRQHandler(void)
{
tud_int_handler(0);
}
//--------------------------------------------------------------------+
// MACRO TYPEDEF CONSTANT ENUM
//--------------------------------------------------------------------+
// Blue LED is chosen because the other LEDs are connected to ST-LINK lines.
#define LED_PORT GPIOB
#define LED_PIN GPIO_PIN_4
#define LED_STATE_ON 1
#define BUTTON_PORT GPIOB
#define BUTTON_PIN GPIO_PIN_3
#define BUTTON_STATE_ACTIVE 1
// enable all LED, Button, Uart, USB clock
static void all_rcc_clk_enable(void)
{
__HAL_RCC_GPIOA_CLK_ENABLE(); // USB D+, D-
__HAL_RCC_GPIOB_CLK_ENABLE(); // LED, Button
}
/**
* @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 = HSE_VALUE/1000000
* 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 = HSE_VALUE/1000000;
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();
all_rcc_clk_enable();
GPIO_InitTypeDef GPIO_InitStruct;
// LED
GPIO_InitStruct.Pin = LED_PIN;
GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_PP;
GPIO_InitStruct.Pull = GPIO_PULLUP;
GPIO_InitStruct.Speed = GPIO_SPEED_FAST;
HAL_GPIO_Init(LED_PORT, &GPIO_InitStruct);
board_led_write(false);
// Button
GPIO_InitStruct.Pin = BUTTON_PIN;
GPIO_InitStruct.Mode = GPIO_MODE_INPUT;
GPIO_InitStruct.Pull = GPIO_PULLDOWN;
GPIO_InitStruct.Speed = GPIO_SPEED_FAST;
HAL_GPIO_Init(BUTTON_PORT, &GPIO_InitStruct);
// USB Pin Init
// PA9- VUSB, PA10- ID, PA11- DM, PA12- DP
/* Configure DM DP Pins */
GPIO_InitStruct.Pin = GPIO_PIN_11 | GPIO_PIN_12;
GPIO_InitStruct.Speed = GPIO_SPEED_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);
// Enable USB OTG clock
__HAL_RCC_USB_OTG_FS_CLK_ENABLE();
// Enable VBUS sense (B device) via pin PA9
USB_OTG_FS->GCCFG &= ~USB_OTG_GCCFG_NOVBUSSENS;
USB_OTG_FS->GCCFG |= USB_OTG_GCCFG_VBUSBSEN;
}
//--------------------------------------------------------------------+
// Board porting API
//--------------------------------------------------------------------+
void board_led_write(bool state)
{
HAL_GPIO_WritePin(LED_PORT, LED_PIN, state ? LED_STATE_ON : (1-LED_STATE_ON));
}
uint32_t board_button_read(void)
{
return BUTTON_STATE_ACTIVE == HAL_GPIO_ReadPin(BUTTON_PORT, BUTTON_PIN);
}
int board_uart_read(uint8_t* buf, int len)
{
(void) buf; (void) len;
return 0;
}
int board_uart_write(void const * buf, int len)
{
(void) buf; (void) len;
return 0;
}
#if CFG_TUSB_OS == OPT_OS_NONE
volatile uint32_t system_ticks = 0;
void SysTick_Handler (void)
{
system_ticks++;
}
uint32_t board_millis(void)
{
return system_ticks;
}
#endif
void HardFault_Handler (void)
{
asm("bkpt");
}
// Required by __libc_init_array in startup code if we are compiling using
// -nostdlib/-nostartfiles.
void _init(void)
{
}

View File

@ -0,0 +1,104 @@
/*
* The MIT License (MIT)
*
* Copyright (c) 2020, 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.
*/
#ifndef BOARD_H_
#define BOARD_H_
#ifdef __cplusplus
extern "C" {
#endif
// LED
#define LED_PORT GPIOC
#define LED_PIN GPIO_PIN_1
#define LED_STATE_ON 1
// Button: Pin D5
#define BUTTON_PORT GPIOC
#define BUTTON_PIN GPIO_PIN_7
#define BUTTON_STATE_ACTIVE 0
// UART
#define UART_DEV USART3
#define UART_GPIO_PORT GPIOB
#define UART_GPIO_AF GPIO_AF7_USART3
#define UART_TX_PIN GPIO_PIN_10
#define UART_RX_PIN GPIO_PIN_11
//--------------------------------------------------------------------+
// RCC Clock
//--------------------------------------------------------------------+
static inline void board_clock_init(void)
{
RCC_ClkInitTypeDef RCC_ClkInitStruct;
RCC_OscInitTypeDef RCC_OscInitStruct;
/* Enable Power Control clock */
__HAL_RCC_PWR_CLK_ENABLE();
/* The voltage scaling allows optimizing the power consumption when the device is
clocked below the maximum system frequency, to update the voltage scaling value
regarding system frequency refer to product datasheet. */
__HAL_PWR_VOLTAGESCALING_CONFIG(PWR_REGULATOR_VOLTAGE_SCALE1);
/* Enable HSE Oscillator and activate PLL with HSE as source */
RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_HSE;
RCC_OscInitStruct.HSEState = RCC_HSE_ON;
RCC_OscInitStruct.PLL.PLLState = RCC_PLL_ON;
RCC_OscInitStruct.PLL.PLLSource = RCC_PLLSOURCE_HSE;
RCC_OscInitStruct.PLL.PLLM = HSE_VALUE/1000000;
RCC_OscInitStruct.PLL.PLLN = 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);
// Enable clocks for LED, Button, Uart
__HAL_RCC_GPIOB_CLK_ENABLE();
__HAL_RCC_GPIOC_CLK_ENABLE();
__HAL_RCC_USART3_CLK_ENABLE();
}
static inline void board_vbus_sense_init(void)
{
// Enable VBUS sense (B device) via pin PA9
USB_OTG_FS->GCCFG &= ~USB_OTG_GCCFG_NOVBUSSENS;
USB_OTG_FS->GCCFG |= USB_OTG_GCCFG_VBUSBSEN;
}
#ifdef __cplusplus
}
#endif
#endif /* BOARD_H_ */

View File

@ -0,0 +1,12 @@
CFLAGS += -DSTM32F405xx
LD_FILE = $(BOARD_PATH)/STM32F405RGTx_FLASH.ld
SRC_S += $(ST_CMSIS)/Source/Templates/gcc/startup_stm32f405xx.s
# For flash-jlink target
JLINK_DEVICE = stm32f405rg
# flash target ROM bootloader
flash: $(BUILD)/$(BOARD)-firmware.bin
dfu-util -R -a 0 --dfuse-address 0x08000000 -D $<

View File

@ -0,0 +1,102 @@
/*
* The MIT License (MIT)
*
* Copyright (c) 2020, 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.
*/
#ifndef BOARD_H_
#define BOARD_H_
#ifdef __cplusplus
extern "C" {
#endif
// Blue LED is chosen because the other LEDs are connected to ST-LINK lines.
#define LED_PORT GPIOB
#define LED_PIN GPIO_PIN_4
#define LED_STATE_ON 1
#define BUTTON_PORT GPIOB
#define BUTTON_PIN GPIO_PIN_3
#define BUTTON_STATE_ACTIVE 1
// Enable PA2 as the debug log UART
// It is not routed to the ST/Link on the Discovery board.
//#define UART_DEV USART2
//#define UART_GPIO_PORT GPIOA
//#define UART_GPIO_AF GPIO_AF7_USART2
//#define UART_TX_PIN GPIO_PIN_2
//#define UART_RX_PIN GPIO_PIN_3
//--------------------------------------------------------------------+
// RCC Clock
//--------------------------------------------------------------------+
static inline void board_clock_init(void)
{
RCC_ClkInitTypeDef RCC_ClkInitStruct;
RCC_OscInitTypeDef RCC_OscInitStruct;
/* Enable Power Control clock */
__HAL_RCC_PWR_CLK_ENABLE();
/* The voltage scaling allows optimizing the power consumption when the device is
clocked below the maximum system frequency, to update the voltage scaling value
regarding system frequency refer to product datasheet. */
__HAL_PWR_VOLTAGESCALING_CONFIG(PWR_REGULATOR_VOLTAGE_SCALE1);
/* Enable HSE Oscillator and activate PLL with HSE as source */
RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_HSE;
RCC_OscInitStruct.HSEState = RCC_HSE_ON;
RCC_OscInitStruct.PLL.PLLState = RCC_PLL_ON;
RCC_OscInitStruct.PLL.PLLSource = RCC_PLLSOURCE_HSE;
RCC_OscInitStruct.PLL.PLLM = HSE_VALUE/1000000;
RCC_OscInitStruct.PLL.PLLN = 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);
// Enable clocks for LED, Button, Uart
__HAL_RCC_GPIOB_CLK_ENABLE();
}
static inline void board_vbus_sense_init(void)
{
// Enable VBUS sense (B device) via pin PA9
USB_OTG_FS->GCCFG &= ~USB_OTG_GCCFG_NOVBUSSENS;
USB_OTG_FS->GCCFG |= USB_OTG_GCCFG_VBUSBSEN;
}
#ifdef __cplusplus
}
#endif
#endif /* BOARD_H_ */

View File

@ -0,0 +1,11 @@
CFLAGS += -DSTM32F405xx
LD_FILE = $(BOARD_PATH)/STM32F405RGTx_FLASH.ld
SRC_S += $(ST_CMSIS)/Source/Templates/gcc/startup_stm32f405xx.s
# For flash-jlink target
JLINK_DEVICE = stm32f405rg
# flash target using on-board stlink
flash: flash-stlink

View File

@ -75,7 +75,7 @@
/* #define HAL_MMC_MODULE_ENABLED */
/* #define HAL_SPI_MODULE_ENABLED */
/* #define HAL_TIM_MODULE_ENABLED */
/* #define HAL_UART_MODULE_ENABLED */
#define HAL_UART_MODULE_ENABLED
/* #define HAL_USART_MODULE_ENABLED */
/* #define HAL_IRDA_MODULE_ENABLED */
/* #define HAL_SMARTCARD_MODULE_ENABLED */
@ -199,6 +199,8 @@
#define USE_HAL_SPI_REGISTER_CALLBACKS 0U /* SPI register callback disabled */
#define USE_HAL_SWPMI_REGISTER_CALLBACKS 0U /* SWPMI register callback disabled */
#define USE_HAL_TIM_REGISTER_CALLBACKS 0U /* TIM register callback disabled */
#define USE_HAL_UART_REGISTER_CALLBACKS 0U /* UART register callback disabled */
#define USE_HAL_USART_REGISTER_CALLBACKS 0U /* USART register callback disabled */
#define USE_HAL_WWDG_REGISTER_CALLBACKS 0U /* WWDG register callback disabled */
/* ########################## Assert Selection ############################## */

View File

@ -0,0 +1,106 @@
/*
* The MIT License (MIT)
*
* Copyright (c) 2020, 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.
*/
#ifndef BOARD_H_
#define BOARD_H_
#ifdef __cplusplus
extern "C" {
#endif
// LED
#define LED_PORT GPIOC
#define LED_PIN GPIO_PIN_13
#define LED_STATE_ON 1
// Button
#define BUTTON_PORT GPIOA
#define BUTTON_PIN GPIO_PIN_0
#define BUTTON_STATE_ACTIVE 0
// Enable PA2 as the debug log UART
//#define UART_DEV USART2
//#define UART_GPIO_PORT GPIOA
//#define UART_GPIO_AF GPIO_AF7_USART2
//#define UART_TX_PIN GPIO_PIN_2
//#define UART_RX_PIN GPIO_PIN_3
//--------------------------------------------------------------------+
// RCC Clock
//--------------------------------------------------------------------+
static inline void board_clock_init(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_SCALE2);
/* Enable HSE Oscillator and activate PLL with HSE as source */
RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_HSE;
RCC_OscInitStruct.HSEState = RCC_HSE_ON;
RCC_OscInitStruct.PLL.PLLState = RCC_PLL_ON;
RCC_OscInitStruct.PLL.PLLSource = RCC_PLLSOURCE_HSE;
RCC_OscInitStruct.PLL.PLLM = HSE_VALUE/1000000;
RCC_OscInitStruct.PLL.PLLN = 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 */
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_2);
// Enable clocks for LED, Button, Uart
__HAL_RCC_GPIOA_CLK_ENABLE();
__HAL_RCC_GPIOC_CLK_ENABLE();
//__HAL_RCC_USART2_CLK_ENABLE();
}
static inline void board_vbus_sense_init(void)
{
// Blackpill doens't use VBUS sense (B device) explicitly disable it
USB_OTG_FS->GCCFG |= USB_OTG_GCCFG_NOVBUSSENS;
USB_OTG_FS->GCCFG &= ~USB_OTG_GCCFG_VBUSBSEN;
USB_OTG_FS->GCCFG &= ~USB_OTG_GCCFG_VBUSASEN;
}
#ifdef __cplusplus
}
#endif
#endif /* BOARD_H_ */

View File

@ -0,0 +1,12 @@
CFLAGS += -DSTM32F401xC
LD_FILE = $(BOARD_PATH)/STM32F401VCTx_FLASH.ld
SRC_S += $(ST_CMSIS)/Source/Templates/gcc/startup_stm32f401xc.s
# For flash-jlink target
JLINK_DEVICE = stm32f401cc
# flash target ROM bootloader
flash: $(BUILD)/$(BOARD)-firmware.bin
dfu-util -R -a 0 --dfuse-address 0x08000000 -D $<

View File

@ -68,7 +68,7 @@
/* #define HAL_SD_MODULE_ENABLED */
// #define HAL_SPI_MODULE_ENABLED
/* #define HAL_TIM_MODULE_ENABLED */
/* #define HAL_UART_MODULE_ENABLED */
#define HAL_UART_MODULE_ENABLED
/* #define HAL_USART_MODULE_ENABLED */
/* #define HAL_IRDA_MODULE_ENABLED */
/* #define HAL_SMARTCARD_MODULE_ENABLED */

View File

@ -0,0 +1,105 @@
/*
* The MIT License (MIT)
*
* Copyright (c) 2020, 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.
*/
#ifndef BOARD_H_
#define BOARD_H_
#ifdef __cplusplus
extern "C" {
#endif
// LED
#define LED_PORT GPIOD
#define LED_PIN GPIO_PIN_14
#define LED_STATE_ON 1
// Button
#define BUTTON_PORT GPIOA
#define BUTTON_PIN GPIO_PIN_0
#define BUTTON_STATE_ACTIVE 1
// Enable PA2 as the debug log UART
// It is not routed to the ST/Link on the Discovery board.
#define UART_DEV USART2
#define UART_GPIO_PORT GPIOA
#define UART_GPIO_AF GPIO_AF7_USART2
#define UART_TX_PIN GPIO_PIN_2
#define UART_RX_PIN GPIO_PIN_3
//--------------------------------------------------------------------+
// RCC Clock
//--------------------------------------------------------------------+
static inline void board_clock_init(void)
{
RCC_ClkInitTypeDef RCC_ClkInitStruct;
RCC_OscInitTypeDef RCC_OscInitStruct;
/* Enable Power Control clock */
__HAL_RCC_PWR_CLK_ENABLE();
/* The voltage scaling allows optimizing the power consumption when the device is
clocked below the maximum system frequency, to update the voltage scaling value
regarding system frequency refer to product datasheet. */
__HAL_PWR_VOLTAGESCALING_CONFIG(PWR_REGULATOR_VOLTAGE_SCALE1);
/* Enable HSE Oscillator and activate PLL with HSE as source */
RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_HSE;
RCC_OscInitStruct.HSEState = RCC_HSE_ON;
RCC_OscInitStruct.PLL.PLLState = RCC_PLL_ON;
RCC_OscInitStruct.PLL.PLLSource = RCC_PLLSOURCE_HSE;
RCC_OscInitStruct.PLL.PLLM = HSE_VALUE/1000000;
RCC_OscInitStruct.PLL.PLLN = 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);
// Enable clocks for LED, Button, Uart
__HAL_RCC_GPIOA_CLK_ENABLE();
__HAL_RCC_GPIOD_CLK_ENABLE();
__HAL_RCC_USART2_CLK_ENABLE();
}
static inline void board_vbus_sense_init(void)
{
// Enable VBUS sense (B device) via pin PA9
USB_OTG_FS->GCCFG &= ~USB_OTG_GCCFG_NOVBUSSENS;
USB_OTG_FS->GCCFG |= USB_OTG_GCCFG_VBUSBSEN;
}
#ifdef __cplusplus
}
#endif
#endif /* BOARD_H_ */

View File

@ -0,0 +1,11 @@
CFLAGS += -DSTM32F407xx
LD_FILE = $(BOARD_PATH)/STM32F407VGTx_FLASH.ld
SRC_S += $(ST_CMSIS)/Source/Templates/gcc/startup_stm32f407xx.s
# For flash-jlink target
JLINK_DEVICE = stm32f407vg
# flash target using on-board stlink
flash: flash-stlink

View File

@ -0,0 +1,106 @@
/*
* The MIT License (MIT)
*
* Copyright (c) 2020, 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.
*/
#ifndef BOARD_H_
#define BOARD_H_
#ifdef __cplusplus
extern "C" {
#endif
// LED
#define LED_PORT GPIOC
#define LED_PIN GPIO_PIN_13
#define LED_STATE_ON 1
// Button
#define BUTTON_PORT GPIOA
#define BUTTON_PIN GPIO_PIN_0
#define BUTTON_STATE_ACTIVE 0
// Enable PA2 as the debug log UART
//#define UART_DEV USART2
//#define UART_GPIO_PORT GPIOA
//#define UART_GPIO_AF GPIO_AF7_USART2
//#define UART_TX_PIN GPIO_PIN_2
//#define UART_RX_PIN GPIO_PIN_3
//--------------------------------------------------------------------+
// RCC Clock
//--------------------------------------------------------------------+
static inline void board_clock_init(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_SCALE2);
/* Enable HSE Oscillator and activate PLL with HSE as source */
RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_HSE;
RCC_OscInitStruct.HSEState = RCC_HSE_ON;
RCC_OscInitStruct.PLL.PLLState = RCC_PLL_ON;
RCC_OscInitStruct.PLL.PLLSource = RCC_PLLSOURCE_HSE;
RCC_OscInitStruct.PLL.PLLM = HSE_VALUE/1000000;
RCC_OscInitStruct.PLL.PLLN = 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 */
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_2);
// Enable clocks for LED, Button, Uart
__HAL_RCC_GPIOA_CLK_ENABLE();
__HAL_RCC_GPIOC_CLK_ENABLE();
//__HAL_RCC_USART2_CLK_ENABLE();
}
static inline void board_vbus_sense_init(void)
{
// Blackpill doens't use VBUS sense (B device) explicitly disable it
USB_OTG_FS->GCCFG |= USB_OTG_GCCFG_NOVBUSSENS;
USB_OTG_FS->GCCFG &= ~USB_OTG_GCCFG_VBUSBSEN;
USB_OTG_FS->GCCFG &= ~USB_OTG_GCCFG_VBUSASEN;
}
#ifdef __cplusplus
}
#endif
#endif /* BOARD_H_ */

View File

@ -0,0 +1,12 @@
CFLAGS += -DSTM32F411xE
LD_FILE = $(BOARD_PATH)/STM32F411CEUx_FLASH.ld
SRC_S += $(ST_CMSIS)/Source/Templates/gcc/startup_stm32f411xe.s
# For flash-jlink target
JLINK_DEVICE = stm32f411ce
# flash target ROM bootloader
flash: $(BUILD)/$(BOARD)-firmware.bin
dfu-util -R -a 0 --dfuse-address 0x08000000 -D $<

View File

@ -68,7 +68,7 @@
/* #define HAL_SD_MODULE_ENABLED */
// #define HAL_SPI_MODULE_ENABLED
/* #define HAL_TIM_MODULE_ENABLED */
/* #define HAL_UART_MODULE_ENABLED */
#define HAL_UART_MODULE_ENABLED
/* #define HAL_USART_MODULE_ENABLED */
/* #define HAL_IRDA_MODULE_ENABLED */
/* #define HAL_SMARTCARD_MODULE_ENABLED */

View File

@ -0,0 +1,104 @@
/*
* The MIT License (MIT)
*
* Copyright (c) 2020, 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.
*/
#ifndef BOARD_H_
#define BOARD_H_
#ifdef __cplusplus
extern "C" {
#endif
// Orange LED
#define LED_PORT GPIOD
#define LED_PIN GPIO_PIN_13
#define LED_STATE_ON 1
#define BUTTON_PORT GPIOA
#define BUTTON_PIN GPIO_PIN_0
#define BUTTON_STATE_ACTIVE 1
// Enable PA2 as the debug log UART
#define UART_DEV USART2
#define UART_GPIO_PORT GPIOA
#define UART_GPIO_AF GPIO_AF7_USART2
#define UART_TX_PIN GPIO_PIN_2
#define UART_RX_PIN GPIO_PIN_3
//--------------------------------------------------------------------+
// RCC Clock
//--------------------------------------------------------------------+
static inline void board_clock_init(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_SCALE2);
/* Enable HSE Oscillator and activate PLL with HSE as source */
RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_HSE;
RCC_OscInitStruct.HSEState = RCC_HSE_ON;
RCC_OscInitStruct.PLL.PLLState = RCC_PLL_ON;
RCC_OscInitStruct.PLL.PLLSource = RCC_PLLSOURCE_HSE;
RCC_OscInitStruct.PLL.PLLM = HSE_VALUE/1000000;
RCC_OscInitStruct.PLL.PLLN = 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 */
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_2);
// Enable clocks for LED, Button, Uart
__HAL_RCC_GPIOA_CLK_ENABLE();
__HAL_RCC_GPIOD_CLK_ENABLE();
__HAL_RCC_USART2_CLK_ENABLE();
}
static inline void board_vbus_sense_init(void)
{
// Enable VBUS sense (B device) via pin PA9
USB_OTG_FS->GCCFG &= ~USB_OTG_GCCFG_NOVBUSSENS;
USB_OTG_FS->GCCFG |= USB_OTG_GCCFG_VBUSBSEN;
}
#ifdef __cplusplus
}
#endif
#endif /* BOARD_H_ */

View File

@ -0,0 +1,11 @@
CFLAGS += -DSTM32F411xE
LD_FILE = $(BOARD_PATH)/STM32F411VETx_FLASH.ld
SRC_S += $(ST_CMSIS)/Source/Templates/gcc/startup_stm32f411xe.s
# For flash-jlink target
JLINK_DEVICE = stm32f411ve
# flash target using on-board stlink
flash: flash-stlink

View File

@ -0,0 +1,118 @@
/*
* The MIT License (MIT)
*
* Copyright (c) 2020, 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.
*/
#ifndef BOARD_H_
#define BOARD_H_
#ifdef __cplusplus
extern "C" {
#endif
// LED
#define LED_PORT GPIOE
#define LED_PIN GPIO_PIN_2
#define LED_STATE_ON 0
// Button
#define BUTTON_PORT GPIOA
#define BUTTON_PIN GPIO_PIN_0
#define BUTTON_STATE_ACTIVE 1
// UART Enable PA2 as the debug log UART
#define UART_DEV USART2
#define UART_GPIO_PORT GPIOA
#define UART_GPIO_AF GPIO_AF7_USART2
#define UART_TX_PIN GPIO_PIN_2
#define UART_RX_PIN GPIO_PIN_3
//--------------------------------------------------------------------+
// RCC Clock
//--------------------------------------------------------------------+
static inline void board_clock_init(void)
{
RCC_ClkInitTypeDef RCC_ClkInitStruct;
RCC_OscInitTypeDef RCC_OscInitStruct;
RCC_PeriphCLKInitTypeDef PeriphClkInitStruct;
/* Enable Power Control clock */
__HAL_RCC_PWR_CLK_ENABLE();
/* The voltage scaling allows optimizing the power consumption when the
* device is clocked below the maximum system frequency, to update the
* voltage scaling value regarding system frequency refer to product
* datasheet. */
__HAL_PWR_VOLTAGESCALING_CONFIG(PWR_REGULATOR_VOLTAGE_SCALE1);
/* Enable HSE Oscillator and activate PLL with HSE as source */
RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_HSE;
RCC_OscInitStruct.HSEState = RCC_HSE_ON;
RCC_OscInitStruct.PLL.PLLState = RCC_PLL_ON;
RCC_OscInitStruct.PLL.PLLSource = RCC_PLLSOURCE_HSE;
RCC_OscInitStruct.PLL.PLLM = HSE_VALUE/1000000;
RCC_OscInitStruct.PLL.PLLN = 200;
RCC_OscInitStruct.PLL.PLLP = RCC_PLLP_DIV2;
RCC_OscInitStruct.PLL.PLLQ = 7;
RCC_OscInitStruct.PLL.PLLR = 2;
HAL_RCC_OscConfig(&RCC_OscInitStruct);
/* Select PLLSAI output as USB clock source */
PeriphClkInitStruct.PLLI2S.PLLI2SM = 8;
PeriphClkInitStruct.PLLI2S.PLLI2SQ = 4;
PeriphClkInitStruct.PLLI2S.PLLI2SN = 192;
PeriphClkInitStruct.PeriphClockSelection = RCC_PERIPHCLK_CK48;
PeriphClkInitStruct.Clk48ClockSelection = RCC_CK48CLKSOURCE_PLLI2SQ;
PeriphClkInitStruct.PLLI2SSelection = RCC_PLLI2SCLKSOURCE_PLLSRC;
PeriphClkInitStruct.PLLI2S.PLLI2SR = 7;
HAL_RCCEx_PeriphCLKConfig(&PeriphClkInitStruct);
/* Select PLL as system clock source and configure the HCLK, PCLK1 and PCLK2
* clocks dividers */
RCC_ClkInitStruct.ClockType = RCC_CLOCKTYPE_SYSCLK | RCC_CLOCKTYPE_HCLK |
RCC_CLOCKTYPE_PCLK1 | RCC_CLOCKTYPE_PCLK2;
RCC_ClkInitStruct.SYSCLKSource = RCC_SYSCLKSOURCE_PLLCLK;
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);
// Enable clocks for LED, Button, Uart
__HAL_RCC_GPIOA_CLK_ENABLE();
__HAL_RCC_GPIOE_CLK_ENABLE();
__HAL_RCC_USART2_CLK_ENABLE();
}
static inline void board_vbus_sense_init(void)
{
// Enable VBUS sense (B device) via pin PA9
USB_OTG_FS->GCCFG |= USB_OTG_GCCFG_VBDEN;
}
#ifdef __cplusplus
}
#endif
#endif /* BOARD_H_ */

View File

@ -0,0 +1,11 @@
CFLAGS += -DSTM32F412Zx
LD_FILE = $(BOARD_PATH)/STM32F412ZGTx_FLASH.ld
SRC_S += $(ST_CMSIS)/Source/Templates/gcc/startup_stm32f412zx.s
# For flash-jlink target
JLINK_DEVICE = stm32f412zg
# flash target using on-board stlink
flash: flash-stlink

View File

@ -24,8 +24,9 @@
* This file is part of the TinyUSB stack.
*/
#include "../board.h"
#include "stm32f4xx_hal.h"
#include "bsp/board.h"
#include "board.h"
//--------------------------------------------------------------------+
// Forward USB interrupt events to TinyUSB IRQ Handler
@ -38,91 +39,12 @@ void OTG_FS_IRQHandler(void)
//--------------------------------------------------------------------+
// MACRO TYPEDEF CONSTANT ENUM
//--------------------------------------------------------------------+
// Orange LED
#define LED_PORT GPIOD
#define LED_PIN GPIO_PIN_13
#define LED_STATE_ON 1
#define BUTTON_PORT GPIOA
#define BUTTON_PIN GPIO_PIN_0
#define BUTTON_STATE_ACTIVE 1
// Enable PA2 as the debug log UART
#define UARTx USART2
#define UART_GPIO_PORT GPIOA
#define UART_GPIO_AF GPIO_AF7_USART2
#define UART_TX_PIN GPIO_PIN_2
#define UART_RX_PIN GPIO_PIN_3
UART_HandleTypeDef UartHandle;
// enable all LED, Button, Uart, USB clock
static void all_rcc_clk_enable(void)
{
__HAL_RCC_GPIOA_CLK_ENABLE(); // USB D+, D-, Button
__HAL_RCC_GPIOD_CLK_ENABLE(); // LED
__HAL_RCC_USART2_CLK_ENABLE(); // Uart module
}
/**
* @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 = HSE_VALUE/1000000
* 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)
{
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 HSE Oscillator and activate PLL with HSE as source */
RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_HSE;
RCC_OscInitStruct.HSEState = RCC_HSE_ON;
RCC_OscInitStruct.PLL.PLLState = RCC_PLL_ON;
RCC_OscInitStruct.PLL.PLLSource = RCC_PLLSOURCE_HSE;
RCC_OscInitStruct.PLL.PLLM = HSE_VALUE/1000000;
RCC_OscInitStruct.PLL.PLLN = 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 */
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_2);
}
void board_init(void)
{
SystemClock_Config();
all_rcc_clk_enable();
board_clock_init();
//SystemCoreClockUpdate();
#if CFG_TUSB_OS == OPT_OS_NONE
// 1ms tick timer
@ -146,11 +68,35 @@ void board_init(void)
// Button
GPIO_InitStruct.Pin = BUTTON_PIN;
GPIO_InitStruct.Mode = GPIO_MODE_INPUT;
GPIO_InitStruct.Pull = GPIO_PULLDOWN;
GPIO_InitStruct.Pull = BUTTON_STATE_ACTIVE ? GPIO_PULLDOWN : GPIO_PULLUP;
GPIO_InitStruct.Speed = GPIO_SPEED_FAST;
HAL_GPIO_Init(BUTTON_PORT, &GPIO_InitStruct);
#ifdef UART_DEV
// UART
GPIO_InitStruct.Pin = UART_TX_PIN | UART_RX_PIN;
GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
GPIO_InitStruct.Pull = GPIO_PULLUP;
GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_HIGH;
GPIO_InitStruct.Alternate = UART_GPIO_AF;
HAL_GPIO_Init(UART_GPIO_PORT, &GPIO_InitStruct);
UartHandle = (UART_HandleTypeDef){
.Instance = UART_DEV,
.Init.BaudRate = CFG_BOARD_UART_BAUDRATE,
.Init.WordLength = UART_WORDLENGTH_8B,
.Init.StopBits = UART_STOPBITS_1,
.Init.Parity = UART_PARITY_NONE,
.Init.HwFlowCtl = UART_HWCONTROL_NONE,
.Init.Mode = UART_MODE_TX_RX,
.Init.OverSampling = UART_OVERSAMPLING_16
};
HAL_UART_Init(&UartHandle);
#endif
/* Configure USB FS GPIOs */
__HAL_RCC_GPIOA_CLK_ENABLE();
/* Configure USB D+ D- Pins */
GPIO_InitStruct.Pin = GPIO_PIN_11 | GPIO_PIN_12;
GPIO_InitStruct.Speed = GPIO_SPEED_HIGH;
@ -165,7 +111,7 @@ void board_init(void)
GPIO_InitStruct.Pull = GPIO_NOPULL;
HAL_GPIO_Init(GPIOA, &GPIO_InitStruct);
/* This for ID line debug */
/* ID Pin */
GPIO_InitStruct.Pin = GPIO_PIN_10;
GPIO_InitStruct.Mode = GPIO_MODE_AF_OD;
GPIO_InitStruct.Pull = GPIO_PULLUP;
@ -173,31 +119,19 @@ void board_init(void)
GPIO_InitStruct.Alternate = GPIO_AF10_OTG_FS;
HAL_GPIO_Init(GPIOA, &GPIO_InitStruct);
GPIO_InitStruct.Pin = UART_TX_PIN | UART_RX_PIN;
GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
GPIO_InitStruct.Pull = GPIO_PULLUP;
GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_HIGH;
GPIO_InitStruct.Alternate = UART_GPIO_AF;
HAL_GPIO_Init(UART_GPIO_PORT, &GPIO_InitStruct);
UartHandle = (UART_HandleTypeDef){
.Instance = UARTx,
.Init.BaudRate = CFG_BOARD_UART_BAUDRATE,
.Init.WordLength = UART_WORDLENGTH_8B,
.Init.StopBits = UART_STOPBITS_1,
.Init.Parity = UART_PARITY_NONE,
.Init.HwFlowCtl = UART_HWCONTROL_NONE,
.Init.Mode = UART_MODE_TX_RX,
.Init.OverSampling = UART_OVERSAMPLING_16
};
HAL_UART_Init(&UartHandle);
#ifdef STM32F412Zx
/* Configure POWER_SWITCH IO pin */
__HAL_RCC_GPIOG_CLK_ENABLE();
GPIO_InitStruct.Pin = GPIO_PIN_8;
GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_OD;
GPIO_InitStruct.Pull = GPIO_NOPULL;
HAL_GPIO_Init(GPIOG, &GPIO_InitStruct);
#endif
// Enable USB OTG clock
__HAL_RCC_USB_OTG_FS_CLK_ENABLE();
// Enable VBUS sense (B device) via pin PA9
USB_OTG_FS->GCCFG &= ~USB_OTG_GCCFG_NOVBUSSENS;
USB_OTG_FS->GCCFG |= USB_OTG_GCCFG_VBUSBSEN;
board_vbus_sense_init();
}
//--------------------------------------------------------------------+
@ -222,8 +156,13 @@ int board_uart_read(uint8_t* buf, int len)
int board_uart_write(void const * buf, int len)
{
#ifdef UART_DEV
HAL_UART_Transmit(&UartHandle, (uint8_t*) buf, len, 0xffff);
return len;
#else
(void) buf; (void) len; (void) UartHandle;
return 0;
#endif
}
#if CFG_TUSB_OS == OPT_OS_NONE

View File

@ -1,3 +1,5 @@
include $(TOP)/$(BOARD_PATH)/board.mk
CFLAGS += \
-flto \
-mthumb \
@ -6,7 +8,6 @@ CFLAGS += \
-mfloat-abi=hard \
-mfpu=fpv4-sp-d16 \
-nostdlib -nostartfiles \
-DSTM32F412Zx \
-DCFG_TUSB_MCU=OPT_MCU_STM32F4
# suppress warning caused by vendor mcu driver
@ -16,9 +17,6 @@ ST_FAMILY = f4
ST_CMSIS = hw/mcu/st/cmsis_device_$(ST_FAMILY)
ST_HAL_DRIVER = hw/mcu/st/stm32$(ST_FAMILY)xx_hal_driver
# All source paths should be relative to the top level.
LD_FILE = hw/bsp/$(BOARD)/STM32F412ZGTx_FLASH.ld
SRC_C += \
$(ST_CMSIS)/Source/Templates/system_stm32$(ST_FAMILY)xx.c \
$(ST_HAL_DRIVER)/Src/stm32$(ST_FAMILY)xx_hal.c \
@ -28,10 +26,8 @@ SRC_C += \
$(ST_HAL_DRIVER)/Src/stm32$(ST_FAMILY)xx_hal_uart.c \
$(ST_HAL_DRIVER)/Src/stm32$(ST_FAMILY)xx_hal_gpio.c
SRC_S += \
$(ST_CMSIS)/Source/Templates/gcc/startup_stm32f412zx.s
INC += \
$(TOP)/$(BOARD_PATH) \
$(TOP)/lib/CMSIS_5/CMSIS/Core/Include \
$(TOP)/$(ST_CMSIS)/Include \
$(TOP)/$(ST_HAL_DRIVER)/Inc \
@ -44,8 +40,5 @@ CHIP_FAMILY = synopsys
# For freeRTOS port source
FREERTOS_PORT = ARM_CM4F
# For flash-jlink target
JLINK_DEVICE = stm32f41zx
# flash target using on-board stlink
flash: flash-stlink

View File

@ -1,47 +0,0 @@
CFLAGS += \
-flto \
-mthumb \
-mabi=aapcs \
-mcpu=cortex-m4 \
-mfloat-abi=hard \
-mfpu=fpv4-sp-d16 \
-nostdlib -nostartfiles \
-DSTM32F401xC \
-DCFG_TUSB_MCU=OPT_MCU_STM32F4
ST_FAMILY = f4
ST_CMSIS = hw/mcu/st/cmsis_device_$(ST_FAMILY)
ST_HAL_DRIVER = hw/mcu/st/stm32$(ST_FAMILY)xx_hal_driver
# All source paths should be relative to the top level.
LD_FILE = hw/bsp/$(BOARD)/STM32F401VCTx_FLASH.ld
SRC_C += \
$(ST_CMSIS)/Source/Templates/system_stm32$(ST_FAMILY)xx.c \
$(ST_HAL_DRIVER)/Src/stm32$(ST_FAMILY)xx_hal.c \
$(ST_HAL_DRIVER)/Src/stm32$(ST_FAMILY)xx_hal_cortex.c \
$(ST_HAL_DRIVER)/Src/stm32$(ST_FAMILY)xx_hal_rcc.c \
$(ST_HAL_DRIVER)/Src/stm32$(ST_FAMILY)xx_hal_gpio.c
SRC_S += \
$(ST_CMSIS)/Source/Templates/gcc/startup_stm32f401xc.s
INC += \
$(TOP)/lib/CMSIS_5/CMSIS/Core/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 = stm32f401cc
# flash target ROM bootloader
flash: $(BUILD)/$(BOARD)-firmware.bin
dfu-util -R -a 0 --dfuse-address 0x08000000 -D $<

View File

@ -1,226 +0,0 @@
/*
* The MIT License (MIT)
*
* Copyright (c) 2019 Ha Thach (tinyusb.org)
*
* Permission is hereby granted, free of charge, to any person obtaining a copy
* of this software and associated documentation files (the "Software"), to deal
* in the Software without restriction, including without limitation the rights
* to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
* copies of the Software, and to permit persons to whom the Software is
* furnished to do so, subject to the following conditions:
*
* The above copyright notice and this permission notice shall be included in
* all copies or substantial portions of the Software.
*
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
* IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
* AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
* LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
* OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
* THE SOFTWARE.
*
* This file is part of the TinyUSB stack.
*/
#include "../board.h"
#include "stm32f4xx.h"
#include "stm32f4xx_hal_conf.h"
//--------------------------------------------------------------------+
// Forward USB interrupt events to TinyUSB IRQ Handler
//--------------------------------------------------------------------+
void OTG_FS_IRQHandler(void)
{
tud_int_handler(0);
}
//--------------------------------------------------------------------+
// MACRO TYPEDEF CONSTANT ENUM
//--------------------------------------------------------------------+
#define LED_PORT GPIOC
#define LED_PIN GPIO_PIN_13
#define LED_STATE_ON 1
#define BUTTON_PORT GPIOA
#define BUTTON_PIN GPIO_PIN_0
#define BUTTON_STATE_ACTIVE 0
// enable all LED, Button, Uart, USB clock
static void all_rcc_clk_enable(void)
{
__HAL_RCC_GPIOA_CLK_ENABLE(); // USB D+, D-, Button
__HAL_RCC_GPIOC_CLK_ENABLE(); // LED
}
/**
* @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) = 25000000
* PLL_M = HSE_VALUE/1000000
* 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)
{
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 HSE Oscillator and activate PLL with HSE as source */
RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_HSE;
RCC_OscInitStruct.HSEState = RCC_HSE_ON;
RCC_OscInitStruct.PLL.PLLState = RCC_PLL_ON;
RCC_OscInitStruct.PLL.PLLSource = RCC_PLLSOURCE_HSE;
RCC_OscInitStruct.PLL.PLLM = HSE_VALUE/1000000;
RCC_OscInitStruct.PLL.PLLN = 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 */
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_2);
}
void board_init(void)
{
SystemClock_Config();
all_rcc_clk_enable();
#if CFG_TUSB_OS == OPT_OS_NONE
// 1ms tick timer
SysTick_Config(SystemCoreClock / 1000);
#elif CFG_TUSB_OS == OPT_OS_FREERTOS
// If freeRTOS is used, IRQ priority is limit by max syscall ( smaller is higher )
//NVIC_SetPriority(USB0_IRQn, configLIBRARY_MAX_SYSCALL_INTERRUPT_PRIORITY );
#endif
GPIO_InitTypeDef GPIO_InitStruct;
// LED
GPIO_InitStruct.Pin = LED_PIN;
GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_PP;
GPIO_InitStruct.Pull = GPIO_PULLUP;
GPIO_InitStruct.Speed = GPIO_SPEED_FAST;
HAL_GPIO_Init(LED_PORT, &GPIO_InitStruct);
board_led_write(false);
// Button
GPIO_InitStruct.Pin = BUTTON_PIN;
GPIO_InitStruct.Mode = GPIO_MODE_INPUT;
GPIO_InitStruct.Pull = BUTTON_STATE_ACTIVE ? GPIO_PULLDOWN : GPIO_PULLUP;
GPIO_InitStruct.Speed = GPIO_SPEED_FAST;
HAL_GPIO_Init(BUTTON_PORT, &GPIO_InitStruct);
/* Configure USB FS GPIOs */
/* Configure USB D+ D- 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);
// Enable USB OTG clock
__HAL_RCC_USB_OTG_FS_CLK_ENABLE();
// Blackpill doens't use VBUS sense (B device)
// explicitly disable it
USB_OTG_FS->GCCFG |= USB_OTG_GCCFG_NOVBUSSENS;
USB_OTG_FS->GCCFG &= ~USB_OTG_GCCFG_VBUSBSEN;
USB_OTG_FS->GCCFG &= ~USB_OTG_GCCFG_VBUSASEN;
}
//--------------------------------------------------------------------+
// Board porting API
//--------------------------------------------------------------------+
void board_led_write(bool state)
{
HAL_GPIO_WritePin(LED_PORT, LED_PIN, state ? LED_STATE_ON : (1-LED_STATE_ON));
}
uint32_t board_button_read(void)
{
return BUTTON_STATE_ACTIVE == HAL_GPIO_ReadPin(BUTTON_PORT, BUTTON_PIN);
}
int board_uart_read(uint8_t* buf, int len)
{
(void) buf; (void) len;
return 0;
}
int board_uart_write(void const * buf, int len)
{
(void) buf; (void) len;
return 0;
}
#if CFG_TUSB_OS == OPT_OS_NONE
volatile uint32_t system_ticks = 0;
void SysTick_Handler (void)
{
system_ticks++;
}
uint32_t board_millis(void)
{
return system_ticks;
}
#endif
void HardFault_Handler (void)
{
asm("bkpt");
}
// Required by __libc_init_array in startup code if we are compiling using
// -nostdlib/-nostartfiles.
void _init(void)
{
}

View File

@ -1,50 +0,0 @@
CFLAGS += \
-flto \
-mthumb \
-mabi=aapcs \
-mcpu=cortex-m4 \
-mfloat-abi=hard \
-mfpu=fpv4-sp-d16 \
-nostdlib -nostartfiles \
-DSTM32F407xx \
-DCFG_TUSB_MCU=OPT_MCU_STM32F4
# suppress warning caused by vendor mcu driver
CFLAGS += -Wno-error=cast-align
ST_FAMILY = f4
ST_CMSIS = hw/mcu/st/cmsis_device_$(ST_FAMILY)
ST_HAL_DRIVER = hw/mcu/st/stm32$(ST_FAMILY)xx_hal_driver
# All source paths should be relative to the top level.
LD_FILE = hw/bsp/$(BOARD)/STM32F407VGTx_FLASH.ld
SRC_C += \
$(ST_CMSIS)/Source/Templates/system_stm32$(ST_FAMILY)xx.c \
$(ST_HAL_DRIVER)/Src/stm32$(ST_FAMILY)xx_hal.c \
$(ST_HAL_DRIVER)/Src/stm32$(ST_FAMILY)xx_hal_cortex.c \
$(ST_HAL_DRIVER)/Src/stm32$(ST_FAMILY)xx_hal_rcc.c \
$(ST_HAL_DRIVER)/Src/stm32$(ST_FAMILY)xx_hal_uart.c \
$(ST_HAL_DRIVER)/Src/stm32$(ST_FAMILY)xx_hal_gpio.c
SRC_S += \
$(ST_CMSIS)/Source/Templates/gcc/startup_stm32f407xx.s
INC += \
$(TOP)/lib/CMSIS_5/CMSIS/Core/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 = stm32f407vg
# flash target using on-board stlink
flash: flash-stlink

View File

@ -1,254 +0,0 @@
/*
* The MIT License (MIT)
*
* Copyright (c) 2019 Ha Thach (tinyusb.org)
*
* Permission is hereby granted, free of charge, to any person obtaining a copy
* of this software and associated documentation files (the "Software"), to deal
* in the Software without restriction, including without limitation the rights
* to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
* copies of the Software, and to permit persons to whom the Software is
* furnished to do so, subject to the following conditions:
*
* The above copyright notice and this permission notice shall be included in
* all copies or substantial portions of the Software.
*
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
* IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
* AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
* LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
* OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
* THE SOFTWARE.
*
* This file is part of the TinyUSB stack.
*/
#include "../board.h"
#include "stm32f4xx_hal.h"
//--------------------------------------------------------------------+
// Forward USB interrupt events to TinyUSB IRQ Handler
//--------------------------------------------------------------------+
void OTG_FS_IRQHandler(void)
{
tud_int_handler(0);
}
//--------------------------------------------------------------------+
// MACRO TYPEDEF CONSTANT ENUM
//--------------------------------------------------------------------+
#define LED_PORT GPIOD
#define LED_PIN GPIO_PIN_14
#define LED_STATE_ON 1
#define BUTTON_PORT GPIOA
#define BUTTON_PIN GPIO_PIN_0
#define BUTTON_STATE_ACTIVE 1
// Enable PA2 as the debug log UART
// It is not routed to the ST/Link on the Discovery board.
#define UARTx USART2
#define UART_GPIO_PORT GPIOA
#define UART_GPIO_AF GPIO_AF7_USART2
#define UART_TX_PIN GPIO_PIN_2
#define UART_RX_PIN GPIO_PIN_3
UART_HandleTypeDef UartHandle;
// enable all LED, Button, Uart, USB clock
static void all_rcc_clk_enable(void)
{
__HAL_RCC_GPIOA_CLK_ENABLE(); // USB D+, D-, Button
__HAL_RCC_GPIOD_CLK_ENABLE(); // LED
__HAL_RCC_USART2_CLK_ENABLE(); // Uart module
}
/**
* @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 = HSE_VALUE/1000000
* 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 = HSE_VALUE/1000000;
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)
{
SystemClock_Config();
all_rcc_clk_enable();
#if CFG_TUSB_OS == OPT_OS_NONE
// 1ms tick timer
SysTick_Config(SystemCoreClock / 1000);
#elif CFG_TUSB_OS == OPT_OS_FREERTOS
// If freeRTOS is used, IRQ priority is limit by max syscall ( smaller is higher )
//NVIC_SetPriority(USB0_IRQn, configLIBRARY_MAX_SYSCALL_INTERRUPT_PRIORITY );
#endif
GPIO_InitTypeDef GPIO_InitStruct;
// LED
GPIO_InitStruct.Pin = LED_PIN;
GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_PP;
GPIO_InitStruct.Pull = GPIO_PULLUP;
GPIO_InitStruct.Speed = GPIO_SPEED_FAST;
HAL_GPIO_Init(LED_PORT, &GPIO_InitStruct);
board_led_write(false);
// Button
GPIO_InitStruct.Pin = BUTTON_PIN;
GPIO_InitStruct.Mode = GPIO_MODE_INPUT;
GPIO_InitStruct.Pull = GPIO_PULLDOWN;
GPIO_InitStruct.Speed = GPIO_SPEED_FAST;
HAL_GPIO_Init(BUTTON_PORT, &GPIO_InitStruct);
// USB Pin Init
// PA9- VUSB, PA10- ID, PA11- DM, PA12- DP
/* Configure DM DP Pins */
GPIO_InitStruct.Pin = GPIO_PIN_11 | GPIO_PIN_12;
GPIO_InitStruct.Speed = GPIO_SPEED_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);
GPIO_InitStruct.Pin = UART_TX_PIN | UART_RX_PIN;
GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
GPIO_InitStruct.Pull = GPIO_PULLUP;
GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_HIGH;
GPIO_InitStruct.Alternate = UART_GPIO_AF;
HAL_GPIO_Init(UART_GPIO_PORT, &GPIO_InitStruct);
UartHandle = (UART_HandleTypeDef){
.Instance = UARTx,
.Init.BaudRate = CFG_BOARD_UART_BAUDRATE,
.Init.WordLength = UART_WORDLENGTH_8B,
.Init.StopBits = UART_STOPBITS_1,
.Init.Parity = UART_PARITY_NONE,
.Init.HwFlowCtl = UART_HWCONTROL_NONE,
.Init.Mode = UART_MODE_TX_RX,
.Init.OverSampling = UART_OVERSAMPLING_16
};
HAL_UART_Init(&UartHandle);
// Enable USB OTG clock
__HAL_RCC_USB_OTG_FS_CLK_ENABLE();
// Enable VBUS sense (B device) via pin PA9
USB_OTG_FS->GCCFG &= ~USB_OTG_GCCFG_NOVBUSSENS;
USB_OTG_FS->GCCFG |= USB_OTG_GCCFG_VBUSBSEN;
}
//--------------------------------------------------------------------+
// Board porting API
//--------------------------------------------------------------------+
void board_led_write(bool state)
{
HAL_GPIO_WritePin(LED_PORT, LED_PIN, state ? LED_STATE_ON : (1-LED_STATE_ON));
}
uint32_t board_button_read(void)
{
return BUTTON_STATE_ACTIVE == HAL_GPIO_ReadPin(BUTTON_PORT, BUTTON_PIN);
}
int board_uart_read(uint8_t* buf, int len)
{
(void) buf; (void) len;
return 0;
}
int board_uart_write(void const * buf, int len)
{
HAL_UART_Transmit(&UartHandle, (uint8_t*) buf, len, 0xffff);
return len;
}
#if CFG_TUSB_OS == OPT_OS_NONE
volatile uint32_t system_ticks = 0;
void SysTick_Handler (void)
{
system_ticks++;
}
uint32_t board_millis(void)
{
return system_ticks;
}
#endif
void HardFault_Handler (void)
{
asm("bkpt");
}
// Required by __libc_init_array in startup code if we are compiling using
// -nostdlib/-nostartfiles.
void _init(void)
{
}

View File

@ -1,47 +0,0 @@
CFLAGS += \
-flto \
-mthumb \
-mabi=aapcs \
-mcpu=cortex-m4 \
-mfloat-abi=hard \
-mfpu=fpv4-sp-d16 \
-nostdlib -nostartfiles \
-DSTM32F411xE \
-DCFG_TUSB_MCU=OPT_MCU_STM32F4
ST_FAMILY = f4
ST_CMSIS = hw/mcu/st/cmsis_device_$(ST_FAMILY)
ST_HAL_DRIVER = hw/mcu/st/stm32$(ST_FAMILY)xx_hal_driver
# All source paths should be relative to the top level.
LD_FILE = hw/bsp/$(BOARD)/STM32F411CEUx_FLASH.ld
SRC_C += \
$(ST_CMSIS)/Source/Templates/system_stm32$(ST_FAMILY)xx.c \
$(ST_HAL_DRIVER)/Src/stm32$(ST_FAMILY)xx_hal.c \
$(ST_HAL_DRIVER)/Src/stm32$(ST_FAMILY)xx_hal_cortex.c \
$(ST_HAL_DRIVER)/Src/stm32$(ST_FAMILY)xx_hal_rcc.c \
$(ST_HAL_DRIVER)/Src/stm32$(ST_FAMILY)xx_hal_gpio.c
SRC_S += \
$(ST_CMSIS)/Source/Templates/gcc/startup_stm32f411xe.s
INC += \
$(TOP)/lib/CMSIS_5/CMSIS/Core/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 = stm32f411ce
# flash target ROM bootloader
flash: $(BUILD)/$(BOARD)-firmware.bin
dfu-util -R -a 0 --dfuse-address 0x08000000 -D $<

View File

@ -1,225 +0,0 @@
/*
* The MIT License (MIT)
*
* Copyright (c) 2019 Ha Thach (tinyusb.org)
*
* Permission is hereby granted, free of charge, to any person obtaining a copy
* of this software and associated documentation files (the "Software"), to deal
* in the Software without restriction, including without limitation the rights
* to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
* copies of the Software, and to permit persons to whom the Software is
* furnished to do so, subject to the following conditions:
*
* The above copyright notice and this permission notice shall be included in
* all copies or substantial portions of the Software.
*
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
* IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
* AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
* LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
* OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
* THE SOFTWARE.
*
* This file is part of the TinyUSB stack.
*/
#include "../board.h"
#include "stm32f4xx_hal.h"
//--------------------------------------------------------------------+
// Forward USB interrupt events to TinyUSB IRQ Handler
//--------------------------------------------------------------------+
void OTG_FS_IRQHandler(void)
{
tud_int_handler(0);
}
//--------------------------------------------------------------------+
// MACRO TYPEDEF CONSTANT ENUM
//--------------------------------------------------------------------+
#define LED_PORT GPIOC
#define LED_PIN GPIO_PIN_13
#define LED_STATE_ON 1
#define BUTTON_PORT GPIOA
#define BUTTON_PIN GPIO_PIN_0
#define BUTTON_STATE_ACTIVE 0
// enable all LED, Button, Uart, USB clock
static void all_rcc_clk_enable(void)
{
__HAL_RCC_GPIOA_CLK_ENABLE(); // USB D+, D-, Button
__HAL_RCC_GPIOC_CLK_ENABLE(); // LED
}
/**
* @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) = 25000000
* PLL_M = HSE_VALUE/1000000
* 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)
{
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 HSE Oscillator and activate PLL with HSE as source */
RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_HSE;
RCC_OscInitStruct.HSEState = RCC_HSE_ON;
RCC_OscInitStruct.PLL.PLLState = RCC_PLL_ON;
RCC_OscInitStruct.PLL.PLLSource = RCC_PLLSOURCE_HSE;
RCC_OscInitStruct.PLL.PLLM = HSE_VALUE/1000000;
RCC_OscInitStruct.PLL.PLLN = 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 */
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_2);
}
void board_init(void)
{
SystemClock_Config();
all_rcc_clk_enable();
#if CFG_TUSB_OS == OPT_OS_NONE
// 1ms tick timer
SysTick_Config(SystemCoreClock / 1000);
#elif CFG_TUSB_OS == OPT_OS_FREERTOS
// If freeRTOS is used, IRQ priority is limit by max syscall ( smaller is higher )
//NVIC_SetPriority(USB0_IRQn, configLIBRARY_MAX_SYSCALL_INTERRUPT_PRIORITY );
#endif
GPIO_InitTypeDef GPIO_InitStruct;
// LED
GPIO_InitStruct.Pin = LED_PIN;
GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_PP;
GPIO_InitStruct.Pull = GPIO_PULLUP;
GPIO_InitStruct.Speed = GPIO_SPEED_FAST;
HAL_GPIO_Init(LED_PORT, &GPIO_InitStruct);
board_led_write(false);
// Button
GPIO_InitStruct.Pin = BUTTON_PIN;
GPIO_InitStruct.Mode = GPIO_MODE_INPUT;
GPIO_InitStruct.Pull = BUTTON_STATE_ACTIVE ? GPIO_PULLDOWN : GPIO_PULLUP;
GPIO_InitStruct.Speed = GPIO_SPEED_FAST;
HAL_GPIO_Init(BUTTON_PORT, &GPIO_InitStruct);
/* Configure USB FS GPIOs */
/* Configure USB D+ D- 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);
// Enable USB OTG clock
__HAL_RCC_USB_OTG_FS_CLK_ENABLE();
// Blackpill doens't use VBUS sense (B device)
// explicitly disable it
USB_OTG_FS->GCCFG |= USB_OTG_GCCFG_NOVBUSSENS;
USB_OTG_FS->GCCFG &= ~USB_OTG_GCCFG_VBUSBSEN;
USB_OTG_FS->GCCFG &= ~USB_OTG_GCCFG_VBUSASEN;
}
//--------------------------------------------------------------------+
// Board porting API
//--------------------------------------------------------------------+
void board_led_write(bool state)
{
HAL_GPIO_WritePin(LED_PORT, LED_PIN, state ? LED_STATE_ON : (1-LED_STATE_ON));
}
uint32_t board_button_read(void)
{
return BUTTON_STATE_ACTIVE == HAL_GPIO_ReadPin(BUTTON_PORT, BUTTON_PIN);
}
int board_uart_read(uint8_t* buf, int len)
{
(void) buf; (void) len;
return 0;
}
int board_uart_write(void const * buf, int len)
{
(void) buf; (void) len;
return 0;
}
#if CFG_TUSB_OS == OPT_OS_NONE
volatile uint32_t system_ticks = 0;
void SysTick_Handler (void)
{
system_ticks++;
}
uint32_t board_millis(void)
{
return system_ticks;
}
#endif
void HardFault_Handler (void)
{
asm("bkpt");
}
// Required by __libc_init_array in startup code if we are compiling using
// -nostdlib/-nostartfiles.
void _init(void)
{
}

View File

@ -1,50 +0,0 @@
CFLAGS += \
-flto \
-mthumb \
-mabi=aapcs \
-mcpu=cortex-m4 \
-mfloat-abi=hard \
-mfpu=fpv4-sp-d16 \
-nostdlib -nostartfiles \
-DSTM32F411xE \
-DCFG_TUSB_MCU=OPT_MCU_STM32F4
# suppress warning caused by vendor mcu driver
CFLAGS += -Wno-error=cast-align
ST_FAMILY = f4
ST_CMSIS = hw/mcu/st/cmsis_device_$(ST_FAMILY)
ST_HAL_DRIVER = hw/mcu/st/stm32$(ST_FAMILY)xx_hal_driver
# All source paths should be relative to the top level.
LD_FILE = hw/bsp/$(BOARD)/STM32F411VETx_FLASH.ld
SRC_C += \
$(ST_CMSIS)/Source/Templates/system_stm32$(ST_FAMILY)xx.c \
$(ST_HAL_DRIVER)/Src/stm32$(ST_FAMILY)xx_hal.c \
$(ST_HAL_DRIVER)/Src/stm32$(ST_FAMILY)xx_hal_cortex.c \
$(ST_HAL_DRIVER)/Src/stm32$(ST_FAMILY)xx_hal_rcc.c \
$(ST_HAL_DRIVER)/Src/stm32$(ST_FAMILY)xx_hal_gpio.c \
$(ST_HAL_DRIVER)/Src/stm32$(ST_FAMILY)xx_hal_uart.c
SRC_S += \
$(ST_CMSIS)/Source/Templates/gcc/startup_stm32f411xe.s
INC += \
$(TOP)/lib/CMSIS_5/CMSIS/Core/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 = stm32f411ve
# flash target using on-board stlink
flash: flash-stlink

View File

@ -1,277 +0,0 @@
/*
* The MIT License (MIT)
*
* Copyright (c) 2019 Ha Thach (tinyusb.org)
*
* Permission is hereby granted, free of charge, to any person obtaining a copy
* of this software and associated documentation files (the "Software"), to deal
* in the Software without restriction, including without limitation the rights
* to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
* copies of the Software, and to permit persons to whom the Software is
* furnished to do so, subject to the following conditions:
*
* The above copyright notice and this permission notice shall be included in
* all copies or substantial portions of the Software.
*
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
* IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
* AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
* LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
* OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
* THE SOFTWARE.
*
* This file is part of the TinyUSB stack.
*/
#include "../board.h"
#include "stm32f4xx_hal.h"
//--------------------------------------------------------------------+
// Forward USB interrupt events to TinyUSB IRQ Handler
//--------------------------------------------------------------------+
void OTG_FS_IRQHandler(void)
{
tud_int_handler(0);
}
//--------------------------------------------------------------------+
// MACRO TYPEDEF CONSTANT ENUM
//--------------------------------------------------------------------+
#define LED_PORT GPIOE
#define LED_PIN GPIO_PIN_2
#define LED_STATE_ON 0
#define BUTTON_PORT GPIOA
#define BUTTON_PIN GPIO_PIN_0
#define BUTTON_STATE_ACTIVE 1
// Enable PA2 as the debug log UART
#define UARTx USART2
#define UART_GPIO_PORT GPIOA
#define UART_GPIO_AF GPIO_AF7_USART2
#define UART_TX_PIN GPIO_PIN_2
#define UART_RX_PIN GPIO_PIN_3
UART_HandleTypeDef UartHandle;
// enable all LED, Button, Uart, USB clock
static void all_rcc_clk_enable(void)
{
__HAL_RCC_GPIOA_CLK_ENABLE(); // USB D+, D-, Button
__HAL_RCC_GPIOE_CLK_ENABLE(); // LED
__HAL_RCC_USART2_CLK_ENABLE(); // Uart module
}
/**
* @brief System Clock Configuration
* The system Clock is configured as follow :
* System Clock source = PLL (HSE)
* SYSCLK(Hz) = 100000000
* HCLK(Hz) = 100000000
* AHB Prescaler = 1
* APB1 Prescaler = 2
* APB2 Prescaler = 1
* HSE Frequency(Hz) = 8000000
* PLL_M = HSE_VALUE/1000000
* PLL_N = 200
* PLL_P = 2
* PLL_Q = 7
* PLL_R = 2
* VDD(V) = 3.3
* Main regulator output voltage = Scale1 mode
* Flash Latency(WS) = 3
* The USB clock configuration from PLLI2S:
* PLLI2SM = 8
* PLLI2SN = 192
* PLLI2SQ = 4
* @param None
* @retval None
*/
static void SystemClock_Config(void)
{
RCC_ClkInitTypeDef RCC_ClkInitStruct;
RCC_OscInitTypeDef RCC_OscInitStruct;
RCC_PeriphCLKInitTypeDef PeriphClkInitStruct;
/* Enable Power Control clock */
__HAL_RCC_PWR_CLK_ENABLE();
/* The voltage scaling allows optimizing the power consumption when the
* device is clocked below the maximum system frequency, to update the
* voltage scaling value regarding system frequency refer to product
* datasheet. */
__HAL_PWR_VOLTAGESCALING_CONFIG(PWR_REGULATOR_VOLTAGE_SCALE1);
/* Enable HSE Oscillator and activate PLL with HSE as source */
RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_HSE;
RCC_OscInitStruct.HSEState = RCC_HSE_ON;
RCC_OscInitStruct.PLL.PLLState = RCC_PLL_ON;
RCC_OscInitStruct.PLL.PLLSource = RCC_PLLSOURCE_HSE;
RCC_OscInitStruct.PLL.PLLM = HSE_VALUE/1000000;
RCC_OscInitStruct.PLL.PLLN = 200;
RCC_OscInitStruct.PLL.PLLP = RCC_PLLP_DIV2;
RCC_OscInitStruct.PLL.PLLQ = 7;
RCC_OscInitStruct.PLL.PLLR = 2;
HAL_RCC_OscConfig(&RCC_OscInitStruct);
/* Select PLLSAI output as USB clock source */
PeriphClkInitStruct.PLLI2S.PLLI2SM = 8;
PeriphClkInitStruct.PLLI2S.PLLI2SQ = 4;
PeriphClkInitStruct.PLLI2S.PLLI2SN = 192;
PeriphClkInitStruct.PeriphClockSelection = RCC_PERIPHCLK_CK48;
PeriphClkInitStruct.Clk48ClockSelection = RCC_CK48CLKSOURCE_PLLI2SQ;
PeriphClkInitStruct.PLLI2SSelection = RCC_PLLI2SCLKSOURCE_PLLSRC;
PeriphClkInitStruct.PLLI2S.PLLI2SR = 7;
HAL_RCCEx_PeriphCLKConfig(&PeriphClkInitStruct);
/* Select PLL as system clock source and configure the HCLK, PCLK1 and PCLK2
* clocks dividers */
RCC_ClkInitStruct.ClockType = RCC_CLOCKTYPE_SYSCLK | RCC_CLOCKTYPE_HCLK |
RCC_CLOCKTYPE_PCLK1 | RCC_CLOCKTYPE_PCLK2;
RCC_ClkInitStruct.SYSCLKSource = RCC_SYSCLKSOURCE_PLLCLK;
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);
}
void board_init(void)
{
SystemClock_Config();
all_rcc_clk_enable();
#if CFG_TUSB_OS == OPT_OS_NONE
// 1ms tick timer
SysTick_Config(SystemCoreClock / 1000);
#elif CFG_TUSB_OS == OPT_OS_FREERTOS
// If freeRTOS is used, IRQ priority is limit by max syscall ( smaller is higher )
//NVIC_SetPriority(USB0_IRQn, configLIBRARY_MAX_SYSCALL_INTERRUPT_PRIORITY );
#endif
GPIO_InitTypeDef GPIO_InitStruct;
// LED
GPIO_InitStruct.Pin = LED_PIN;
GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_PP;
GPIO_InitStruct.Pull = GPIO_PULLUP;
GPIO_InitStruct.Speed = GPIO_SPEED_FAST;
HAL_GPIO_Init(LED_PORT, &GPIO_InitStruct);
board_led_write(false);
// Button
GPIO_InitStruct.Pin = BUTTON_PIN;
GPIO_InitStruct.Mode = GPIO_MODE_INPUT;
GPIO_InitStruct.Pull = GPIO_PULLDOWN;
GPIO_InitStruct.Speed = GPIO_SPEED_FAST;
HAL_GPIO_Init(BUTTON_PORT, &GPIO_InitStruct);
/* Configure USB FS GPIOs */
/* Configure USB D+ D- 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);
/* ID Pin */
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);
/* Configure POWER_SWITCH IO pin */
__HAL_RCC_GPIOG_CLK_ENABLE();
GPIO_InitStruct.Pin = GPIO_PIN_8;
GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_OD;
GPIO_InitStruct.Pull = GPIO_NOPULL;
HAL_GPIO_Init(GPIOG, &GPIO_InitStruct);
GPIO_InitStruct.Pin = UART_TX_PIN | UART_RX_PIN;
GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
GPIO_InitStruct.Pull = GPIO_PULLUP;
GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_HIGH;
GPIO_InitStruct.Alternate = UART_GPIO_AF;
HAL_GPIO_Init(UART_GPIO_PORT, &GPIO_InitStruct);
UartHandle = (UART_HandleTypeDef){
.Instance = UARTx,
.Init.BaudRate = CFG_BOARD_UART_BAUDRATE,
.Init.WordLength = UART_WORDLENGTH_8B,
.Init.StopBits = UART_STOPBITS_1,
.Init.Parity = UART_PARITY_NONE,
.Init.HwFlowCtl = UART_HWCONTROL_NONE,
.Init.Mode = UART_MODE_TX_RX,
.Init.OverSampling = UART_OVERSAMPLING_16
};
HAL_UART_Init(&UartHandle);
// Enable USB OTG clock
__HAL_RCC_USB_OTG_FS_CLK_ENABLE();
// Enable VBUS sense (B device) via pin PA9
USB_OTG_FS->GCCFG |= USB_OTG_GCCFG_VBDEN;
}
//--------------------------------------------------------------------+
// Board porting API
//--------------------------------------------------------------------+
void board_led_write(bool state)
{
HAL_GPIO_WritePin(LED_PORT, LED_PIN, state ? LED_STATE_ON : (1-LED_STATE_ON));
}
uint32_t board_button_read(void)
{
return BUTTON_STATE_ACTIVE == HAL_GPIO_ReadPin(BUTTON_PORT, BUTTON_PIN);
}
int board_uart_read(uint8_t* buf, int len)
{
(void) buf; (void) len;
return 0;
}
int board_uart_write(void const * buf, int len)
{
HAL_UART_Transmit(&UartHandle, (uint8_t*) buf, len, 0xffff);
return len;
}
#if CFG_TUSB_OS == OPT_OS_NONE
volatile uint32_t system_ticks = 0;
void SysTick_Handler (void)
{
system_ticks++;
}
uint32_t board_millis(void)
{
return system_ticks;
}
#endif
void HardFault_Handler (void)
{
asm("bkpt");
}
// Required by __libc_init_array in startup code if we are compiling using
// -nostdlib/-nostartfiles.
void _init(void)
{
}