Add support for the STM32C0 and the NUCLEO-C071RB.

This commit is contained in:
David (Pololu) 2024-10-08 12:30:44 -07:00 committed by hathach
parent dbc2c8d972
commit 568c785da1
No known key found for this signature in database
GPG Key ID: 26FAB84F615C3C52
16 changed files with 961 additions and 8 deletions

View File

@ -153,7 +153,7 @@ Following CPUs are supported, check out `Supported Devices`_ for comprehensive l
+--------------+------------------------------------------------------------+
| Sony | CXD56 |
+--------------+------------------------------------------------------------+
| ST STM32 | F0, F1, F2, F3, F4, F7, G0, G4, H5, H7, |
| ST STM32 | C0, F0, F1, F2, F3, F4, F7, G0, G4, H5, H7, |
| | |
| | L0, L1, L4, L4+, L5, U5, WB |
+--------------+------------------------------------------------------------+

View File

@ -97,7 +97,7 @@ Supported MCUs
| +-----------------------------+--------+------+-----------+------------------------+-------------------+
| | F3 | ✔ | ✖ | ✖ | stm32_fsdev | |
| +-----------------------------+--------+------+-----------+------------------------+-------------------+
| | G0, H5 | ✔ | ✖ | ✖ | stm32_fsdev | |
| | C0, G0, H5 | ✔ | | ✖ | stm32_fsdev | |
| +-----------------------------+--------+------+-----------+------------------------+-------------------+
| | G4 | ✔ | ✖ | ✖ | stm32_fsdev | |
| +-----------------------------+--------+------+-----------+------------------------+-------------------+

View File

@ -107,6 +107,9 @@
#elif CFG_TUSB_MCU == OPT_MCU_STM32G0
#include "stm32g0xx.h"
#elif CFG_TUSB_MCU == OPT_MCU_STM32C0
#include "stm32c0xx.h"
#elif CFG_TUSB_MCU == OPT_MCU_CXD56
// no header needed

View File

@ -0,0 +1,187 @@
/*
******************************************************************************
**
** @file : LinkerScript.ld
**
** @author : Auto-generated by STM32CubeIDE
**
** Abstract : Linker script for NUCLEO-C071RB Board embedding STM32C071RBTx Device from stm32c0 series
** 128KBytes FLASH
** 24KBytes 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.
**
******************************************************************************
** @attention
**
** Copyright (c) 2024 STMicroelectronics.
** All rights reserved.
**
** This software is licensed under terms that can be found in the LICENSE file
** in the root directory of this software component.
** If no LICENSE file comes with this software, it is provided AS-IS.
**
******************************************************************************
*/
/* Entry Point */
ENTRY(Reset_Handler)
/* Highest address of the user mode stack */
_estack = ORIGIN(RAM) + LENGTH(RAM); /* end of "RAM" Ram type memory */
_Min_Heap_Size = 0x200; /* required amount of heap */
_Min_Stack_Size = 0x400; /* required amount of stack */
/* Memories definition */
MEMORY
{
RAM (xrw) : ORIGIN = 0x20000000, LENGTH = 24K
FLASH (rx) : ORIGIN = 0x8000000, LENGTH = 128K
}
/* Sections */
SECTIONS
{
/* The startup code into "FLASH" Rom type memory */
.isr_vector :
{
. = ALIGN(4);
KEEP(*(.isr_vector)) /* Startup code */
. = ALIGN(4);
} >FLASH
/* The program code and other data into "FLASH" Rom type memory */
.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 into "FLASH" Rom type memory */
.rodata :
{
. = ALIGN(4);
*(.rodata) /* .rodata sections (constants, strings, etc.) */
*(.rodata*) /* .rodata* sections (constants, strings, etc.) */
. = ALIGN(4);
} >FLASH
.ARM.extab (READONLY) : /* The "READONLY" keyword is only supported in GCC11 and later, remove it if using GCC10 or earlier. */
{
. = ALIGN(4);
*(.ARM.extab* .gnu.linkonce.armextab.*)
. = ALIGN(4);
} >FLASH
.ARM (READONLY) : /* The "READONLY" keyword is only supported in GCC11 and later, remove it if using GCC10 or earlier. */
{
. = ALIGN(4);
__exidx_start = .;
*(.ARM.exidx*)
__exidx_end = .;
. = ALIGN(4);
} >FLASH
.preinit_array (READONLY) : /* The "READONLY" keyword is only supported in GCC11 and later, remove it if using GCC10 or earlier. */
{
. = ALIGN(4);
PROVIDE_HIDDEN (__preinit_array_start = .);
KEEP (*(.preinit_array*))
PROVIDE_HIDDEN (__preinit_array_end = .);
. = ALIGN(4);
} >FLASH
.init_array (READONLY) : /* The "READONLY" keyword is only supported in GCC11 and later, remove it if using GCC10 or earlier. */
{
. = ALIGN(4);
PROVIDE_HIDDEN (__init_array_start = .);
KEEP (*(SORT(.init_array.*)))
KEEP (*(.init_array*))
PROVIDE_HIDDEN (__init_array_end = .);
. = ALIGN(4);
} >FLASH
.fini_array (READONLY) : /* The "READONLY" keyword is only supported in GCC11 and later, remove it if using GCC10 or earlier. */
{
. = ALIGN(4);
PROVIDE_HIDDEN (__fini_array_start = .);
KEEP (*(SORT(.fini_array.*)))
KEEP (*(.fini_array*))
PROVIDE_HIDDEN (__fini_array_end = .);
. = ALIGN(4);
} >FLASH
/* Used by the startup to initialize data */
_sidata = LOADADDR(.data);
/* Initialized data sections into "RAM" Ram type memory */
.data :
{
. = ALIGN(4);
_sdata = .; /* create a global symbol at data start */
*(.data) /* .data sections */
*(.data*) /* .data* sections */
*(.RamFunc) /* .RamFunc sections */
*(.RamFunc*) /* .RamFunc* sections */
. = ALIGN(4);
_edata = .; /* define a global symbol at data end */
} >RAM AT> FLASH
/* Uninitialized data section into "RAM" Ram type memory */
. = ALIGN(4);
.bss :
{
/* This is used by the startup in order to initialize the .bss section */
_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" Ram type memory left */
._user_heap_stack :
{
. = ALIGN(8);
PROVIDE ( end = . );
PROVIDE ( _end = . );
. = . + _Min_Heap_Size;
. = . + _Min_Stack_Size;
. = ALIGN(8);
} >RAM
/* Remove information from the compiler libraries */
/DISCARD/ :
{
libc.a ( * )
libm.a ( * )
libgcc.a ( * )
}
.ARM.attributes 0 : { *(.ARM.attributes) }
}

View File

@ -0,0 +1,10 @@
set(MCU_VARIANT stm32c071xx)
set(JLINK_DEVICE stm32c071rb)
set(LD_FILE_GNU ${CMAKE_CURRENT_LIST_DIR}/STM32C071RBTx_FLASH.ld)
function(update_board TARGET)
target_compile_definitions(${TARGET} PUBLIC
STM32C071xx
)
endfunction()

View File

@ -0,0 +1,58 @@
/*
* The MIT License (MIT)
*
* Copyright (c) 2020, Ha Thach (tinyusb.org)
* Copyright (c) 2023, HiFiPhile
*
* 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_
// Green LED
#define GREEN_LED_PORT GPIOA
#define GREEN_LED_PIN GPIO_PIN_5
#define GREEN_LED_STATE_ON 1
// Blue LED
#define BLUE_LED_PORT GPIOC
#define BLUE_LED_PIN GPIO_PIN_9
#define BLUE_LED_STATE_ON 0
// Generic LED
#define LED_PORT GREEN_LED_PORT
#define LED_PIN GREEN_LED_PIN
#define LED_STATE_ON GREEN_LED_STATE_ON
// Button
#define BUTTON_PORT GPIOC
#define BUTTON_PIN GPIO_PIN_13
#define BUTTON_STATE_ACTIVE 0
// Enable UART serial communication with the ST-Link
#define UART_DEV USART2
#define UART_GPIO_PORT GPIOA
#define UART_GPIO_AF GPIO_AF1_USART2
#define UART_TX_PIN GPIO_PIN_2
#define UART_RX_PIN GPIO_PIN_3
#endif /* BOARD_H_ */

View File

@ -0,0 +1,13 @@
CFLAGS += \
-DSTM32C071xx
# GCC
SRC_S_GCC += $(ST_CMSIS)/Source/Templates/gcc/startup_stm32c071xx.s
LD_FILE_GCC = $(BOARD_PATH)/STM32C071RBTx_FLASH.ld
# IAR
SRC_S_IAR += $(ST_CMSIS)/Source/Templates/iar/startup_stm32c071xx.s
LD_FILE_IAR = $(ST_CMSIS)/Source/Templates/iar/linker/stm32c071xx_flash.icf
# For flash-jlink target
JLINK_DEVICE = stm32c071rb

199
hw/bsp/stm32c0/family.c Normal file
View File

@ -0,0 +1,199 @@
/*
* The MIT License (MIT)
*
* Copyright (c) 2019 Ha Thach (tinyusb.org)
* Copyright (c) 2023 HiFiPhile
*
* 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 "stm32c0xx_hal.h"
#include "bsp/board_api.h"
#include "board.h"
//--------------------------------------------------------------------+
// Forward USB interrupt events to TinyUSB IRQ Handler
//--------------------------------------------------------------------+
void USB_DRD_FS_IRQHandler(void) {
tud_int_handler(0);
}
// Startup code generated by STM32CubeIDE uses USB_IRQHandler, while
// stm32c071xx.s from cmsis_device_c0 uses USB_DRD_FS_IRQHandler.
void USB_IRQHandler(void) {
USB_DRD_FS_IRQHandler();
}
//--------------------------------------------------------------------+
// MACRO TYPEDEF CONSTANT ENUM
//--------------------------------------------------------------------+
UART_HandleTypeDef UartHandle;
void board_init(void) {
HAL_Init();
// Enable the HSIUSB48 48 MHz oscillator.
RCC->CR |= RCC_CR_HSIUSB48ON;
// Wait for HSIUSB48 to be ready.
while (!(RCC->CR & RCC_CR_HSIUSB48RDY)) { }
// Change the SYSCLK source to HSIUSB48.
RCC->CFGR = (RCC->CFGR & ~RCC_CFGR_SW) | RCC_SYSCLKSOURCE_HSIUSB48;
// Wait for the SYSCLK source to change.
while ((RCC->CFGR & RCC_CFGR_SWS) >> RCC_CFGR_SWS_Pos != RCC_SYSCLKSOURCE_HSIUSB48) { }
// Disable HSI48 to save power.
RCC->CR &= ~RCC_CR_HSION;
// Enable peripheral clocks.
RCC->APBENR1 = RCC_APBENR1_USBEN | RCC_APBENR1_CRSEN | RCC_APBENR1_USART2EN;
RCC->APBENR2 = RCC_APBENR2_USART1EN;
// Enable all GPIO clocks.
RCC->IOPENR = 0x2F;
// Turn on CRS to make the HSIUSB48 clock more precise when USB is connected.
CRS->CR |= CRS_CR_AUTOTRIMEN | CRS_CR_CEN;
#if CFG_TUSB_OS == OPT_OS_NONE
// 1ms tick timer
SysTick_Config(SystemCoreClock / 1000);
#elif CFG_TUSB_OS == OPT_OS_FREERTOS
// Explicitly disable systick to prevent its ISR runs before scheduler start
SysTick->CTRL &= ~1U;
// If freeRTOS is used, IRQ priority is limit by max syscall ( smaller is higher )
NVIC_SetPriority(USB_DRD_FS_IRQn, configLIBRARY_MAX_SYSCALL_INTERRUPT_PRIORITY);
#endif
// LED
{
GPIO_InitTypeDef gpio_init = { 0 };
gpio_init.Pin = LED_PIN;
gpio_init.Mode = GPIO_MODE_OUTPUT_PP;
HAL_GPIO_Init(LED_PORT, &gpio_init);
board_led_write(false);
}
// Button
{
GPIO_InitTypeDef gpio_init = { 0 };
gpio_init.Pin = BUTTON_PIN;
gpio_init.Mode = GPIO_MODE_INPUT;
gpio_init.Pull = BUTTON_STATE_ACTIVE ? GPIO_PULLDOWN : GPIO_PULLUP;
HAL_GPIO_Init(BUTTON_PORT, &gpio_init);
}
#ifdef UART_DEV
// UART
{
GPIO_InitTypeDef gpio_init = { 0 };
gpio_init.Pin = UART_TX_PIN | UART_RX_PIN;
gpio_init.Mode = GPIO_MODE_AF_PP;
gpio_init.Pull = GPIO_PULLUP;
gpio_init.Speed = GPIO_SPEED_FREQ_HIGH;
gpio_init.Alternate = UART_GPIO_AF;
HAL_GPIO_Init(UART_GPIO_PORT, &gpio_init);
}
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,
.AdvancedInit.AdvFeatureInit = UART_ADVFEATURE_NO_INIT
};
HAL_UART_Init(&UartHandle);
#endif
}
//--------------------------------------------------------------------+
// Board porting API
//--------------------------------------------------------------------+
void board_led_write(bool state) {
GPIO_PinState pin_state = (GPIO_PinState)(state ? LED_STATE_ON : (1 - LED_STATE_ON));
HAL_GPIO_WritePin(LED_PORT, LED_PIN, pin_state);
}
uint32_t board_button_read(void) {
return BUTTON_STATE_ACTIVE == HAL_GPIO_ReadPin(BUTTON_PORT, BUTTON_PIN);
}
size_t board_get_unique_id(uint8_t id[], size_t max_len) {
(void) max_len;
volatile uint32_t * stm32_uuid = (volatile uint32_t *) UID_BASE;
uint32_t* id32 = (uint32_t*) (uintptr_t) id;
uint8_t const len = 12;
id32[0] = stm32_uuid[0];
id32[1] = stm32_uuid[1];
id32[2] = stm32_uuid[2];
return len;
}
int board_uart_read(uint8_t *buf, int len) {
(void) buf;
(void) len;
return 0;
}
int board_uart_write(void const *buf, int len) {
#ifdef UART_DEV
HAL_UART_Transmit(&UartHandle, (uint8_t*)(uintptr_t) buf, len, 0xffff);
return len;
#else
(void) buf;
(void) len;
(void) UartHandle;
return 0;
#endif
}
#if CFG_TUSB_OS == OPT_OS_NONE
volatile uint32_t system_ticks = 0;
void SysTick_Handler(void) {
system_ticks++;
HAL_IncTick();
}
uint32_t board_millis(void) {
return system_ticks;
}
#endif
void HardFault_Handler(void) {
__asm("BKPT #0\n");
}
// Required by __libc_init_array in startup code if we are compiling using
// -nostdlib/-nostartfiles.
void _init(void) {
}

118
hw/bsp/stm32c0/family.cmake Normal file
View File

@ -0,0 +1,118 @@
include_guard()
set(ST_FAMILY c0)
set(ST_PREFIX stm32${ST_FAMILY}xx)
set(ST_HAL_DRIVER ${TOP}/hw/mcu/st/stm32${ST_FAMILY}xx_hal_driver)
set(ST_CMSIS ${TOP}/hw/mcu/st/cmsis_device_${ST_FAMILY})
set(CMSIS_5 ${TOP}/lib/CMSIS_5)
# include board specific
include(${CMAKE_CURRENT_LIST_DIR}/boards/${BOARD}/board.cmake)
# toolchain set up
set(CMAKE_SYSTEM_PROCESSOR cortex-m0plus CACHE INTERNAL "System Processor")
set(CMAKE_TOOLCHAIN_FILE ${TOP}/examples/build_system/cmake/toolchain/arm_${TOOLCHAIN}.cmake)
set(FAMILY_MCUS STM32C0 CACHE INTERNAL "")
set(OPENOCD_OPTION "-f interface/stlink.cfg -f target/stm32c0x.cfg")
#------------------------------------
# BOARD_TARGET
#------------------------------------
# only need to be built ONCE for all examples
function(add_board_target BOARD_TARGET)
if (TARGET ${BOARD_TARGET})
return()
endif ()
# Startup & Linker script
set(STARTUP_FILE_GNU ${ST_CMSIS}/Source/Templates/gcc/startup_${MCU_VARIANT}.s)
set(STARTUP_FILE_Clang ${STARTUP_FILE_GNU})
set(STARTUP_FILE_IAR ${ST_CMSIS}/Source/Templates/iar/startup_${MCU_VARIANT}.s)
set(LD_FILE_Clang ${LD_FILE_GNU})
set(LD_FILE_IAR ${ST_CMSIS}/Source/Templates/iar/linker/${MCU_VARIANT}_flash.icf)
add_library(${BOARD_TARGET} STATIC
${ST_CMSIS}/Source/Templates/system_${ST_PREFIX}.c
${ST_HAL_DRIVER}/Src/${ST_PREFIX}_hal.c
${ST_HAL_DRIVER}/Src/${ST_PREFIX}_hal_cortex.c
${ST_HAL_DRIVER}/Src/${ST_PREFIX}_hal_pwr.c
${ST_HAL_DRIVER}/Src/${ST_PREFIX}_hal_pwr_ex.c
${ST_HAL_DRIVER}/Src/${ST_PREFIX}_hal_rcc.c
${ST_HAL_DRIVER}/Src/${ST_PREFIX}_hal_rcc_ex.c
${ST_HAL_DRIVER}/Src/${ST_PREFIX}_hal_gpio.c
${ST_HAL_DRIVER}/Src/${ST_PREFIX}_hal_uart.c
${ST_HAL_DRIVER}/Src/${ST_PREFIX}_hal_uart_ex.c
${ST_HAL_DRIVER}/Src/${ST_PREFIX}_hal_dma.c
${STARTUP_FILE_${CMAKE_C_COMPILER_ID}}
)
target_include_directories(${BOARD_TARGET} PUBLIC
${CMAKE_CURRENT_FUNCTION_LIST_DIR}
${CMSIS_5}/CMSIS/Core/Include
${ST_CMSIS}/Include
${ST_HAL_DRIVER}/Inc
)
# target_compile_options(${BOARD_TARGET} PUBLIC)
# target_compile_definitions(${BOARD_TARGET} PUBLIC)
update_board(${BOARD_TARGET})
if (CMAKE_C_COMPILER_ID STREQUAL "GNU")
target_link_options(${BOARD_TARGET} PUBLIC
"LINKER:--script=${LD_FILE_GNU}"
-nostartfiles
--specs=nosys.specs --specs=nano.specs
)
elseif (CMAKE_C_COMPILER_ID STREQUAL "Clang")
target_link_options(${BOARD_TARGET} PUBLIC
"LINKER:--script=${LD_FILE_Clang}"
)
elseif (CMAKE_C_COMPILER_ID STREQUAL "IAR")
target_link_options(${BOARD_TARGET} PUBLIC
"LINKER:--config=${LD_FILE_IAR}"
)
endif ()
endfunction()
#------------------------------------
# Functions
#------------------------------------
function(family_configure_example TARGET RTOS)
family_configure_common(${TARGET} ${RTOS})
# Board target
add_board_target(board_${BOARD})
#---------- Port Specific ----------
# These files are built for each example since it depends on example's tusb_config.h
target_sources(${TARGET} PUBLIC
# BSP
${CMAKE_CURRENT_FUNCTION_LIST_DIR}/family.c
${CMAKE_CURRENT_FUNCTION_LIST_DIR}/../board.c
)
target_include_directories(${TARGET} PUBLIC
# family, hw, board
${CMAKE_CURRENT_FUNCTION_LIST_DIR}
${CMAKE_CURRENT_FUNCTION_LIST_DIR}/../../
${CMAKE_CURRENT_FUNCTION_LIST_DIR}/boards/${BOARD}
)
# Add TinyUSB target and port source
family_add_tinyusb(${TARGET} OPT_MCU_STM32C0 ${RTOS})
target_sources(${TARGET}-tinyusb PUBLIC
${TOP}/src/portable/st/stm32_fsdev/dcd_stm32_fsdev.c
${TOP}/src/portable/st/typec/typec_stm32.c
)
target_link_libraries(${TARGET}-tinyusb PUBLIC board_${BOARD})
# Link dependencies
target_link_libraries(${TARGET} PUBLIC board_${BOARD} ${TARGET}-tinyusb)
# Flashing
family_flash_jlink(${TARGET})
family_flash_stlink(${TARGET})
#family_flash_openocd(${TARGET})
endfunction()

52
hw/bsp/stm32c0/family.mk Normal file
View File

@ -0,0 +1,52 @@
ST_FAMILY = c0
DEPS_SUBMODULES += lib/CMSIS_5 hw/mcu/st/cmsis_device_$(ST_FAMILY) hw/mcu/st/stm32$(ST_FAMILY)xx_hal_driver
ST_CMSIS = hw/mcu/st/cmsis_device_$(ST_FAMILY)
ST_HAL_DRIVER = hw/mcu/st/stm32$(ST_FAMILY)xx_hal_driver
include $(TOP)/$(BOARD_PATH)/board.mk
CPU_CORE ?= cortex-m0plus
# --------------
# Compiler Flags
# --------------
CFLAGS += \
-DCFG_TUSB_MCU=OPT_MCU_STM32C0
# GCC Flags
CFLAGS_GCC += \
-flto \
# suppress warning caused by vendor mcu driver
CFLAGS_GCC += -Wno-error=cast-align -Wno-error=unused-parameter
LDFLAGS_GCC += \
-nostdlib -nostartfiles \
--specs=nosys.specs --specs=nano.specs
# -----------------
# Sources & Include
# -----------------
SRC_C += \
src/portable/st/stm32_fsdev/dcd_stm32_fsdev.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_pwr.c \
$(ST_HAL_DRIVER)/Src/stm32$(ST_FAMILY)xx_hal_pwr_ex.c \
$(ST_HAL_DRIVER)/Src/stm32$(ST_FAMILY)xx_hal_rcc.c \
$(ST_HAL_DRIVER)/Src/stm32$(ST_FAMILY)xx_hal_rcc_ex.c \
$(ST_HAL_DRIVER)/Src/stm32$(ST_FAMILY)xx_hal_uart.c \
$(ST_HAL_DRIVER)/Src/stm32$(ST_FAMILY)xx_hal_uart_ex.c \
$(ST_HAL_DRIVER)/Src/stm32$(ST_FAMILY)xx_hal_gpio.c \
$(ST_HAL_DRIVER)/Src/stm32$(ST_FAMILY)xx_hal_dma.c
INC += \
$(TOP)/$(BOARD_PATH) \
$(TOP)/lib/CMSIS_5/CMSIS/Core/Include \
$(TOP)/$(ST_CMSIS)/Include \
$(TOP)/$(ST_HAL_DRIVER)/Inc
# flash target using on-board stlink
flash: flash-stlink

View File

@ -0,0 +1,284 @@
/* USER CODE BEGIN Header */
/**
******************************************************************************
* @file stm32c0xx_hal_conf.h
* @author MCD Application Team
* @brief HAL configuration template file.
* This file should be copied to the application folder and renamed
* to stm32c0xx_hal_conf.h.
******************************************************************************
* @attention
*
* Copyright (c) 2021 STMicroelectronics.
* All rights reserved.
*
* This software is licensed under terms that can be found in the LICENSE file
* in the root directory of this software component.
* If no LICENSE file comes with this software, it is provided AS-IS.
*
******************************************************************************
*/
/* USER CODE END Header */
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef STM32C0xx_HAL_CONF_H
#define STM32C0xx_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_CRC_MODULE_ENABLED */
/* #define HAL_CRYP_MODULE_ENABLED */
/* #define HAL_I2C_MODULE_ENABLED */
/* #define HAL_I2S_MODULE_ENABLED */
/* #define HAL_IWDG_MODULE_ENABLED */
/* #define HAL_IRDA_MODULE_ENABLED */
/* #define HAL_PCD_MODULE_ENABLED */
/* #define HAL_HCD_MODULE_ENABLED */
/* #define HAL_RNG_MODULE_ENABLED */
/* #define HAL_RTC_MODULE_ENABLED */
/* #define HAL_SMARTCARD_MODULE_ENABLED */
/* #define HAL_SMBUS_MODULE_ENABLED */
/* #define HAL_SPI_MODULE_ENABLED */
/* #define HAL_TIM_MODULE_ENABLED */
/* #define HAL_USART_MODULE_ENABLED */
/* #define HAL_WWDG_MODULE_ENABLED */
#define HAL_GPIO_MODULE_ENABLED
#define HAL_EXTI_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
#define HAL_UART_MODULE_ENABLED
/* ########################## Register Callbacks selection ############################## */
/**
* @brief Set below the peripheral configuration to "1U" to add the support
* of HAL callback registration/unregistration feature for the HAL
* driver(s). This allows user application to provide specific callback
* functions thanks to HAL_PPP_RegisterCallback() rather than overwriting
* the default weak callback functions (see each stm32c0xx_hal_ppp.h file
* for possible callback identifiers defined in HAL_PPP_CallbackIDTypeDef
* for each PPP peripheral).
*/
#define USE_HAL_ADC_REGISTER_CALLBACKS 0U /* ADC register callback disabled */
#define USE_HAL_I2C_REGISTER_CALLBACKS 0U /* I2C register callback disabled */
#define USE_HAL_IRDA_REGISTER_CALLBACKS 0U /* IRDA register callback disabled */
#define USE_HAL_I2S_REGISTER_CALLBACKS 0U /* I2S register callback disabled */
#define USE_HAL_IWDG_REGISTER_CALLBACKS 0U /* IWDG register callback disabled */
#define USE_HAL_RTC_REGISTER_CALLBACKS 0U /* RTC register callback disabled */
#define USE_HAL_SMARTCARD_REGISTER_CALLBACKS 0U /* SMARTCARD register callback disabled */
#define USE_HAL_SMBUS_REGISTER_CALLBACKS 0U /* SMBUS register callback disabled */
#define USE_HAL_SPI_REGISTER_CALLBACKS 0U /* SPI register callback disabled */
#define USE_HAL_TIM_REGISTER_CALLBACKS 0U /* TIM register callback disabled */
#define USE_HAL_UART_REGISTER_CALLBACKS 0U /* UART register callback disabled */
#define USE_HAL_USART_REGISTER_CALLBACKS 0U /* USART register callback disabled */
#define USE_HAL_WWDG_REGISTER_CALLBACKS 0U /* WWDG register callback disabled */
/* ########################## Oscillator Values adaptation ####################*/
/**
* @brief Adjust the value of External High Speed oscillator (HSE) used in your application.
* This value is used by the RCC HAL module to compute the system frequency
* (when HSE is used as system clock source, directly or through the PLL).
*/
#if !defined (HSE_VALUE)
#define HSE_VALUE (8000000U) /*!< Value of the External oscillator in Hz */
#endif /* HSE_VALUE */
#if !defined (HSE_STARTUP_TIMEOUT)
#define HSE_STARTUP_TIMEOUT (100UL) /*!< 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 (48000000UL) /*!< Value of the Internal oscillator in Hz*/
#endif /* HSI_VALUE */
/**
* @brief Internal Low Speed oscillator (LSI) value.
*/
#if !defined (LSI_VALUE)
#define LSI_VALUE (32000UL) /*!< 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.*/
#if !defined (LSI_STARTUP_TIME)
#define LSI_STARTUP_TIME 130UL /*!< Time out for LSI start up, in ms */
#endif /* LSI_STARTUP_TIME */
/**
* @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 (32768UL) /*!< Value of the External oscillator in Hz*/
#endif /* LSE_VALUE */
#if !defined (LSE_STARTUP_TIMEOUT)
#define LSE_STARTUP_TIMEOUT (5000UL) /*!< Time out for LSE start up, in ms */
#endif /* LSE_STARTUP_TIMEOUT */
/**
* @brief External clock source for I2S1 peripheral
* This value is used by the RCC HAL module to compute the I2S1 clock source
* frequency.
*/
#if !defined (EXTERNAL_I2S1_CLOCK_VALUE)
#define EXTERNAL_I2S1_CLOCK_VALUE (12288000UL) /*!< Value of the I2S1 External clock source in Hz*/
#endif /* EXTERNAL_I2S1_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 (3300UL) /*!< Value of VDD in mv */
#define TICK_INT_PRIORITY 3U /*!< tick interrupt priority */
#define USE_RTOS 0U
#define PREFETCH_ENABLE 0U
#define INSTRUCTION_CACHE_ENABLE 1U
/* ########################## Assert Selection ############################## */
/**
* @brief Uncomment the line below to expanse the "assert_param" macro in the
* HAL drivers code
*/
/* #define USE_FULL_ASSERT 1U */
/* Includes ------------------------------------------------------------------*/
/**
* @brief Include modules header file
*/
#ifdef HAL_RCC_MODULE_ENABLED
#include "stm32c0xx_hal_rcc.h"
#endif /* HAL_RCC_MODULE_ENABLED */
#ifdef HAL_GPIO_MODULE_ENABLED
#include "stm32c0xx_hal_gpio.h"
#endif /* HAL_GPIO_MODULE_ENABLED */
#ifdef HAL_DMA_MODULE_ENABLED
#include "stm32c0xx_hal_dma.h"
#endif /* HAL_DMA_MODULE_ENABLED */
#ifdef HAL_CORTEX_MODULE_ENABLED
#include "stm32c0xx_hal_cortex.h"
#endif /* HAL_CORTEX_MODULE_ENABLED */
#ifdef HAL_ADC_MODULE_ENABLED
#include "stm32c0xx_hal_adc.h"
#include "stm32c0xx_hal_adc_ex.h"
#endif /* HAL_ADC_MODULE_ENABLED */
#ifdef HAL_CRC_MODULE_ENABLED
#include "stm32c0xx_hal_crc.h"
#endif /* HAL_CRC_MODULE_ENABLED */
#ifdef HAL_EXTI_MODULE_ENABLED
#include "stm32c0xx_hal_exti.h"
#endif /* HAL_EXTI_MODULE_ENABLED */
#ifdef HAL_FLASH_MODULE_ENABLED
#include "stm32c0xx_hal_flash.h"
#endif /* HAL_FLASH_MODULE_ENABLED */
#ifdef HAL_I2C_MODULE_ENABLED
#include "stm32c0xx_hal_i2c.h"
#endif /* HAL_I2C_MODULE_ENABLED */
#ifdef HAL_I2S_MODULE_ENABLED
#include "stm32c0xx_hal_i2s.h"
#endif /* HAL_I2S_MODULE_ENABLED */
#ifdef HAL_IRDA_MODULE_ENABLED
#include "stm32c0xx_hal_irda.h"
#endif /* HAL_IRDA_MODULE_ENABLED */
#ifdef HAL_IWDG_MODULE_ENABLED
#include "stm32c0xx_hal_iwdg.h"
#endif /* HAL_IWDG_MODULE_ENABLED */
#ifdef HAL_PWR_MODULE_ENABLED
#include "stm32c0xx_hal_pwr.h"
#endif /* HAL_PWR_MODULE_ENABLED */
#ifdef HAL_RTC_MODULE_ENABLED
#include "stm32c0xx_hal_rtc.h"
#endif /* HAL_RTC_MODULE_ENABLED */
#ifdef HAL_SMARTCARD_MODULE_ENABLED
#include "stm32c0xx_hal_smartcard.h"
#endif /* HAL_SMARTCARD_MODULE_ENABLED */
#ifdef HAL_SMBUS_MODULE_ENABLED
#include "stm32c0xx_hal_smbus.h"
#endif /* HAL_SMBUS_MODULE_ENABLED */
#ifdef HAL_SPI_MODULE_ENABLED
#include "stm32c0xx_hal_spi.h"
#endif /* HAL_SPI_MODULE_ENABLED */
#ifdef HAL_TIM_MODULE_ENABLED
#include "stm32c0xx_hal_tim.h"
#endif /* HAL_TIM_MODULE_ENABLED */
#ifdef HAL_UART_MODULE_ENABLED
#include "stm32c0xx_hal_uart.h"
#endif /* HAL_UART_MODULE_ENABLED */
#ifdef HAL_USART_MODULE_ENABLED
#include "stm32c0xx_hal_usart.h"
#endif /* HAL_USART_MODULE_ENABLED */
#ifdef HAL_WWDG_MODULE_ENABLED
#include "stm32c0xx_hal_wwdg.h"
#endif /* HAL_WWDG_MODULE_ENABLED */
#ifdef HAL_PCD_MODULE_ENABLED
#include "stm32c0xx_hal_pcd.h"
#endif /* HAL_PCD_MODULE_ENABLED */
#ifdef HAL_HCD_MODULE_ENABLED
#include "stm32c0xx_hal_hcd.h"
#endif /* HAL_HCD_MODULE_ENABLED */
/* Exported macro ------------------------------------------------------------*/
#ifdef USE_FULL_ASSERT
/**
* @brief The assert_param macro is used for functions 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 /* STM32C0xx_HAL_CONF_H */
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View File

@ -238,6 +238,11 @@
#define TUP_USBIP_FSDEV_STM32
#define TUP_DCD_ENDPOINT_MAX 8
#elif TU_CHECK_MCU(OPT_MCU_STM32C0)
#define TUP_USBIP_FSDEV
#define TUP_USBIP_FSDEV_STM32
#define TUP_DCD_ENDPOINT_MAX 8
#elif TU_CHECK_MCU(OPT_MCU_STM32L0, OPT_MCU_STM32L1)
#define TUP_USBIP_FSDEV
#define TUP_USBIP_FSDEV_STM32

View File

@ -40,6 +40,7 @@
* F102, F103 512 byte buffer; no internal D+ pull-up (maybe many more changes?)
* F302xB/C, F303xB/C, F373 512 byte buffer; no internal D+ pull-up
* F302x6/8, F302xD/E2, F303xD/E 1024 byte buffer; no internal D+ pull-up
* C0 2048 byte buffer; 32-bit bus; host mode
* G0 2048 byte buffer; 32-bit bus; host mode
* G4 1024 byte buffer
* H5 2048 byte buffer; 32-bit bus; host mode

View File

@ -104,6 +104,20 @@
#define USB_CNTR_LPMODE USB_CNTR_SUSPRDY
#define USB_CNTR_FSUSP USB_CNTR_SUSPEN
#elif CFG_TUSB_MCU == OPT_MCU_STM32C0
#include "stm32c0xx.h"
#define FSDEV_PMA_SIZE (2048u)
#define USB USB_DRD_FS
#define USB_EP_CTR_RX USB_CHEP_VTRX
#define USB_EP_CTR_TX USB_CHEP_VTTX
#define USB_EPREG_MASK USB_CHEP_REG_MASK
#define USB_CNTR_FRES USB_CNTR_USBRST
#define USB_CNTR_RESUME USB_CNTR_L2RES
#define USB_ISTR_EP_ID USB_ISTR_IDN
#define USB_EPADDR_FIELD USB_CHEP_ADDR
#define USB_CNTR_LPMODE USB_CNTR_SUSPRDY
#define USB_CNTR_FSUSP USB_CNTR_SUSPEN
#elif CFG_TUSB_MCU == OPT_MCU_STM32H5
#include "stm32h5xx.h"
#define FSDEV_PMA_SIZE (2048u)
@ -260,6 +274,8 @@ static const IRQn_Type fsdev_irq[] = {
#else
USB_UCPD1_2_IRQn,
#endif
#elif CFG_TUSB_MCU == OPT_MCU_STM32C0
USB_DRD_FS_IRQn,
#elif TU_CHECK_MCU(OPT_MCU_STM32G4, OPT_MCU_STM32L1)
USB_HP_IRQn,
USB_LP_IRQn,

View File

@ -93,6 +93,7 @@
#define OPT_MCU_STM32H5 315 ///< ST H5
#define OPT_MCU_STM32U0 316 ///< ST U0
#define OPT_MCU_STM32H7RS 317 ///< ST F7RS
#define OPT_MCU_STM32C0 318 ///< ST C0
// Sony
#define OPT_MCU_CXD56 400 ///< SONY CXD56

View File

@ -73,6 +73,9 @@ deps_optional = {
'hw/mcu/sony/cxd56/spresense-exported-sdk': ['https://github.com/sonydevworld/spresense-exported-sdk.git',
'2ec2a1538362696118dc3fdf56f33dacaf8f4067',
'spresense'],
'hw/mcu/st/cmsis_device_c0': ['https://github.com/STMicroelectronics/cmsis_device_c0.git',
'fb56b1b70c73b74eacda2a4bcc36886444364ab3',
'stm32c0'],
'hw/mcu/st/cmsis_device_f0': ['https://github.com/STMicroelectronics/cmsis_device_f0.git',
'2fc25ee22264bc27034358be0bd400b893ef837e',
'stm32f0'],
@ -124,6 +127,9 @@ deps_optional = {
'hw/mcu/st/stm32-mfxstm32l152': ['https://github.com/STMicroelectronics/stm32-mfxstm32l152.git',
'7f4389efee9c6a655b55e5df3fceef5586b35f9b',
'stm32h7'],
'hw/mcu/st/stm32c0xx_hal_driver': ['https://github.com/STMicroelectronics/stm32c0xx_hal_driver.git',
'41253e2f1d7ae4a4d0c379cf63f5bcf71fcf8eb3',
'stm32c0'],
'hw/mcu/st/stm32f0xx_hal_driver': ['https://github.com/STMicroelectronics/stm32f0xx_hal_driver.git',
'0e95cd88657030f640a11e690a8a5186c7712ea5',
'stm32f0'],
@ -189,12 +195,12 @@ deps_optional = {
'ch32f20x'],
'lib/CMSIS_5': ['https://github.com/ARM-software/CMSIS_5.git',
'20285262657d1b482d132d20d755c8c330d55c1f',
'imxrt kinetis_k32l2 kinetis_kl lpc51 lpc54 lpc55 mcx mm32 msp432e4 nrf ra saml2x'
'lpc11 lpc13 lpc15 lpc17 lpc18 lpc40 lpc43'
'stm32f0 stm32f1 stm32f2 stm32f3 stm32f4 stm32f7 stm32g0 stm32g4 stm32h5'
'stm32h7 stm32l0 stm32l1 stm32l4 stm32l5 stm32u5 stm32wb'
'sam3x samd11 samd21 samd51 samd5x_e5x same5x same7x saml2x samg'
'tm4c'],
'imxrt kinetis_k32l2 kinetis_kl lpc51 lpc54 lpc55 mcx mm32 msp432e4 nrf ra saml2x '
'lpc11 lpc13 lpc15 lpc17 lpc18 lpc40 lpc43 '
'stm32c0 stm32f0 stm32f1 stm32f2 stm32f3 stm32f4 stm32f7 stm32g0 stm32g4 stm32h5 '
'stm32h7 stm32l0 stm32l1 stm32l4 stm32l5 stm32u5 stm32wb '
'sam3x samd11 samd21 samd51 samd5x_e5x same5x same7x saml2x samg '
'tm4c '],
'lib/sct_neopixel': ['https://github.com/gsteiert/sct_neopixel.git',
'e73e04ca63495672d955f9268e003cffe168fcd8',
'lpc55'],