add ch32v103 bsp support, compile but does not run, probably due to compile/linker issue

This commit is contained in:
hathach 2024-06-14 16:06:37 +07:00
parent 969b06d77c
commit 33f5547ed4
No known key found for this signature in database
GPG Key ID: 26FAB84F615C3C52
18 changed files with 1295 additions and 15 deletions

View File

@ -0,0 +1,8 @@
set(LD_FLASH_SIZE 64K)
set(LD_RAM_SIZE 20K)
function(update_board TARGET)
target_compile_definitions(${TARGET} PUBLIC
CFG_EXAMPLE_MSC_DUAL_READONLY
)
endfunction()

View File

@ -0,0 +1,20 @@
#ifndef BOARD_H_
#define BOARD_H_
#ifdef __cplusplus
extern "C" {
#endif
#define LED_PORT GPIOA
#define LED_PIN GPIO_Pin_10
#define LED_STATE_ON 0
#define BUTTON_PORT GPIOA
#define BUTTON_PIN GPIO_Pin_1
#define BUTTON_STATE_ACTIVE 0
#ifdef __cplusplus
}
#endif
#endif

View File

@ -0,0 +1,7 @@
MCU_VARIANT = D6
CFLAGS += -DCFG_EXAMPLE_MSC_DUAL_READONLY
LDFLAGS += \
-Wl,--defsym=__flash_size=64K \
-Wl,--defsym=__ram_size=20K \

View File

@ -0,0 +1,37 @@
/********************************** (C) COPYRIGHT *******************************
* File Name : ch32v10x_conf.h
* Author : WCH
* Version : V1.0.0
* Date : 2020/04/30
* Description : Library configuration file.
*********************************************************************************
* Copyright (c) 2021 Nanjing Qinheng Microelectronics Co., Ltd.
* Attention: This software (modified or not) and binary are used for
* microcontroller manufactured by Nanjing Qinheng Microelectronics.
*******************************************************************************/
#ifndef __CH32V10x_CONF_H
#define __CH32V10x_CONF_H
#include "ch32v10x_adc.h"
#include "ch32v10x_bkp.h"
#include "ch32v10x_crc.h"
#include "ch32v10x_dbgmcu.h"
#include "ch32v10x_dma.h"
#include "ch32v10x_exti.h"
#include "ch32v10x_flash.h"
#include "ch32v10x_gpio.h"
#include "ch32v10x_i2c.h"
#include "ch32v10x_iwdg.h"
#include "ch32v10x_pwr.h"
#include "ch32v10x_rcc.h"
#include "ch32v10x_rtc.h"
#include "ch32v10x_spi.h"
#include "ch32v10x_tim.h"
#include "ch32v10x_usart.h"
#include "ch32v10x_wwdg.h"
#include "ch32v10x_usb.h"
#include "ch32v10x_usb_host.h"
#include "ch32v10x_it.h"
#include "ch32v10x_misc.h"
#endif /* __CH32V10x_CONF_H */

View File

@ -0,0 +1,15 @@
/********************************** (C) COPYRIGHT *******************************
* File Name : ch32v10x_it.h
* Author : WCH
* Version : V1.0.0
* Date : 2022/08/20
* Description : This file contains the headers of the interrupt handlers.
*********************************************************************************
* Copyright (c) 2021 Nanjing Qinheng Microelectronics Co., Ltd.
* Attention: This software (modified or not) and binary are used for
* microcontroller manufactured by Nanjing Qinheng Microelectronics.
*******************************************************************************/
#ifndef __CH32V10x_IT_H
#define __CH32V10x_IT_H
#endif /* __CH32V10x_IT_H */

147
hw/bsp/ch32v10x/family.c Normal file
View File

@ -0,0 +1,147 @@
#include <stdio.h>
// https://github.com/openwch/ch32v307/pull/90
// https://github.com/openwch/ch32v20x/pull/12
#ifdef __GNUC__
#pragma GCC diagnostic push
#pragma GCC diagnostic ignored "-Wstrict-prototypes"
#endif
#include "ch32v10x.h"
#ifdef __GNUC__
#pragma GCC diagnostic pop
#endif
#include "bsp/board_api.h"
#include "board.h"
__attribute__((interrupt)) __attribute__((used))
void USBHD_IRQHandler(void) {
#if CFG_TUD_WCH_USBIP_USBFS
tud_int_handler(0);
#endif
}
__attribute__((interrupt)) __attribute__((used))
void USBHDWakeUp_IRQHandler(void) {
#if CFG_TUD_WCH_USBIP_USBFS
tud_int_handler(0);
#endif
}
#if CFG_TUSB_OS == OPT_OS_NONE
volatile uint32_t system_ticks = 0;
__attribute__((interrupt)) __attribute__((used))
void SysTick_Handler(void) {
SysTick->CNTL0 = SysTick->CNTL1 = SysTick->CNTL2 = SysTick->CNTL3 = 0;
SysTick->CNTH0 = SysTick->CNTH1 = SysTick->CNTH2 = SysTick->CNTH3 = 0;
system_ticks++;
}
uint32_t SysTick_Config(uint32_t ticks) {
NVIC_EnableIRQ(SysTicK_IRQn);
SysTick->CTLR = 0;
SysTick->CNTL0 = SysTick->CNTL1 = SysTick->CNTL2 = SysTick->CNTL3 = 0;
SysTick->CNTH0 = SysTick->CNTH1 = SysTick->CNTH2 = SysTick->CNTH3 = 0;
SysTick->CMPLR0 = (u8)(ticks & 0xFF);
SysTick->CMPLR1 = (u8)(ticks >> 8);
SysTick->CMPLR2 = (u8)(ticks >> 16);
SysTick->CMPLR3 = (u8)(ticks >> 24);
SysTick->CMPHR0 = SysTick->CMPHR1 = SysTick->CMPHR2 = SysTick->CMPHR3 = 0;
SysTick->CTLR = 1;
return 0;
}
uint32_t board_millis(void) {
return system_ticks;
}
#endif
void board_init(void) {
__disable_irq();
#if CFG_TUSB_OS == OPT_OS_NONE
SysTick_Config(SystemCoreClock / 1000);
#endif
uint8_t usb_div;
switch (SystemCoreClock) {
case 48000000: usb_div = RCC_USBCLKSource_PLLCLK_Div1; break;
case 72000000: usb_div = RCC_USBCLKSource_PLLCLK_1Div5; break;
default: TU_ASSERT(0,); break;
}
RCC_USBCLKConfig(usb_div);
RCC_APB1PeriphClockCmd(RCC_APB1Periph_USB, ENABLE);
RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOA, ENABLE);
#ifdef LED_PIN
GPIO_InitTypeDef led_init = {
.GPIO_Pin = LED_PIN,
.GPIO_Mode = GPIO_Mode_Out_OD,
.GPIO_Speed = GPIO_Speed_50MHz,
};
GPIO_Init(LED_PORT, &led_init);
#endif
#ifdef BUTTON_PIN
GPIO_InitTypeDef button_init = {
.GPIO_Pin = BUTTON_PIN,
.GPIO_Mode = GPIO_Mode_IPU,
.GPIO_Speed = GPIO_Speed_50MHz,
};
GPIO_Init(BUTTON_PORT, &button_init);
#endif
// UART TX is PA9
RCC_APB2PeriphClockCmd(RCC_APB2Periph_USART1, ENABLE);
GPIO_InitTypeDef usart_init = {
.GPIO_Pin = GPIO_Pin_9,
.GPIO_Speed = GPIO_Speed_50MHz,
.GPIO_Mode = GPIO_Mode_AF_PP,
};
GPIO_Init(GPIOA, &usart_init);
USART_InitTypeDef usart = {
.USART_BaudRate = 115200,
.USART_WordLength = USART_WordLength_8b,
.USART_StopBits = USART_StopBits_1,
.USART_Parity = USART_Parity_No,
.USART_Mode = USART_Mode_Tx,
.USART_HardwareFlowControl = USART_HardwareFlowControl_None,
};
USART_Init(USART1, &usart);
USART_Cmd(USART1, ENABLE);
__enable_irq();
board_led_write(true);
}
void board_led_write(bool state) {
GPIO_WriteBit(LED_PORT, LED_PIN, state ? LED_STATE_ON : (1-LED_STATE_ON));
}
uint32_t board_button_read(void) {
return BUTTON_STATE_ACTIVE == GPIO_ReadInputDataBit(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) {
const char *bufc = (const char *) buf;
for (int i = 0; i < len; i++) {
while (USART_GetFlagStatus(USART1, USART_FLAG_TC) == RESET);
USART_SendData(USART1, *bufc++);
}
return len;
}

View File

@ -0,0 +1,117 @@
include_guard()
#set(UF2_FAMILY_ID 0x699b62ec)
set(CH32_FAMILY ch32v10x)
set(SDK_DIR ${TOP}/hw/mcu/wch/ch32v103)
set(SDK_SRC_DIR ${SDK_DIR}/EVT/EXAM/SRC)
# include board specific
include(${CMAKE_CURRENT_LIST_DIR}/boards/${BOARD}/board.cmake)
# toolchain set up
set(CMAKE_SYSTEM_PROCESSOR rv32imac-ilp32 CACHE INTERNAL "System Processor")
set(CMAKE_TOOLCHAIN_FILE ${TOP}/examples/build_system/cmake/toolchain/riscv_${TOOLCHAIN}.cmake)
set(FAMILY_MCUS CH32V103 CACHE INTERNAL "")
set(OPENOCD_OPTION "-f ${CMAKE_CURRENT_LIST_DIR}/wch-riscv.cfg")
#------------------------------------
# BOARD_TARGET
#------------------------------------
# only need to be built ONCE for all examples
function(add_board_target BOARD_TARGET)
if (TARGET ${BOARD_TARGET})
return()
endif()
if (NOT DEFINED LD_FILE_GNU)
set(LD_FILE_GNU ${CMAKE_CURRENT_FUNCTION_LIST_DIR}/linker/${CH32_FAMILY}.ld)
endif ()
set(LD_FILE_Clang ${LD_FILE_GNU})
if (NOT DEFINED STARTUP_FILE_GNU)
set(STARTUP_FILE_GNU ${SDK_SRC_DIR}/Startup/startup_${CH32_FAMILY}.S)
endif ()
set(STARTUP_FILE_Clang ${STARTUP_FILE_GNU})
add_library(${BOARD_TARGET} STATIC
${SDK_SRC_DIR}/Core/core_riscv.c
${SDK_SRC_DIR}/Peripheral/src/${CH32_FAMILY}_gpio.c
${SDK_SRC_DIR}/Peripheral/src/${CH32_FAMILY}_misc.c
${SDK_SRC_DIR}/Peripheral/src/${CH32_FAMILY}_rcc.c
${SDK_SRC_DIR}/Peripheral/src/${CH32_FAMILY}_usart.c
${CMAKE_CURRENT_FUNCTION_LIST_DIR}/system_${CH32_FAMILY}.c
${STARTUP_FILE_${CMAKE_C_COMPILER_ID}}
)
target_include_directories(${BOARD_TARGET} PUBLIC
${SDK_SRC_DIR}/Core
${SDK_SRC_DIR}/Peripheral/inc
${CMAKE_CURRENT_FUNCTION_LIST_DIR}
)
target_compile_definitions(${BOARD_TARGET} PUBLIC
)
update_board(${BOARD_TARGET})
if (CMAKE_C_COMPILER_ID STREQUAL "GNU")
target_compile_options(${BOARD_TARGET} PUBLIC
-mcmodel=medany
)
target_link_options(${BOARD_TARGET} PUBLIC
"LINKER:--script=${LD_FILE_GNU}"
-Wl,--defsym=__flash_size=${LD_FLASH_SIZE}
-Wl,--defsym=__ram_size=${LD_RAM_SIZE}
-nostartfiles
--specs=nosys.specs --specs=nano.specs
)
elseif (CMAKE_C_COMPILER_ID STREQUAL "Clang")
message(FATAL_ERROR "Clang is not supported for MSP432E4")
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_CH32V103 ${RTOS})
target_sources(${TARGET}-tinyusb PUBLIC
${TOP}/src/portable/wch/dcd_ch32_usbfs.c
)
target_link_libraries(${TARGET}-tinyusb PUBLIC board_${BOARD})
# Link dependencies
target_link_libraries(${TARGET} PUBLIC board_${BOARD} ${TARGET}-tinyusb)
# Flashing
family_add_bin_hex(${TARGET})
family_flash_openocd_wch(${TARGET})
#family_add_uf2(${TARGET} ${UF2_FAMILY_ID})
#family_flash_uf2(${TARGET} ${UF2_FAMILY_ID})
endfunction()

53
hw/bsp/ch32v10x/family.mk Normal file
View File

@ -0,0 +1,53 @@
# https://www.embecosm.com/resources/tool-chain-downloads/#riscv-stable
#CROSS_COMPILE ?= riscv32-unknown-elf-
# Toolchain from https://nucleisys.com/download.php
#CROSS_COMPILE ?= riscv-nuclei-elf-
# Toolchain from https://github.com/xpack-dev-tools/riscv-none-elf-gcc-xpack
CROSS_COMPILE ?= riscv-none-elf-
CH32_FAMILY = ch32v10x
SDK_DIR = hw/mcu/wch/ch32v103
SDK_SRC_DIR = $(SDK_DIR)/EVT/EXAM/SRC
include $(TOP)/$(BOARD_PATH)/board.mk
CPU_CORE ?= rv32imac-ilp32
# Port0 use FSDev, Port1 use USBFS
PORT ?= 0
CFLAGS += \
-mcmodel=medany \
-ffat-lto-objects \
-flto \
-DCFG_TUSB_MCU=OPT_MCU_CH32V103
# https://github.com/openwch/ch32v20x/pull/12
CFLAGS += -Wno-error=strict-prototypes
LDFLAGS_GCC += \
-nostdlib -nostartfiles \
--specs=nosys.specs --specs=nano.specs \
LD_FILE = $(FAMILY_PATH)/linker/${CH32_FAMILY}.ld
SRC_C += \
src/portable/wch/dcd_ch32_usbfs.c \
$(SDK_SRC_DIR)/Core/core_riscv.c \
$(SDK_SRC_DIR)/Peripheral/src/${CH32_FAMILY}_gpio.c \
$(SDK_SRC_DIR)/Peripheral/src/${CH32_FAMILY}_misc.c \
$(SDK_SRC_DIR)/Peripheral/src/${CH32_FAMILY}_rcc.c \
$(SDK_SRC_DIR)/Peripheral/src/${CH32_FAMILY}_usart.c \
SRC_S += $(SDK_SRC_DIR)/Startup/startup_${CH32_FAMILY}.S
INC += \
$(TOP)/$(BOARD_PATH) \
$(TOP)/$(SDK_SRC_DIR)/Core \
$(TOP)/$(SDK_SRC_DIR)/Peripheral/inc \
FREERTOS_PORTABLE_SRC = $(FREERTOS_PORTABLE_PATH)/RISC-V
OPENOCD_WCH_OPTION=-f $(TOP)/$(FAMILY_PATH)/wch-riscv.cfg
flash: flash-openocd-wch

View File

@ -0,0 +1,165 @@
/* Define default values if not already defined */
__FLASH_SIZE = DEFINED(__flash_size) ? __flash_size : 64K;
__RAM_SIZE = DEFINED(__ram_size) ? __ram_size : 20K;
MEMORY
{
FLASH (rx) : ORIGIN = 0x00000000, LENGTH = __FLASH_SIZE
RAM (xrw) : ORIGIN = 0x20000000, LENGTH = __RAM_SIZE
}
ENTRY( _start )
__stack_size = 2048;
PROVIDE( _stack_size = __stack_size );
SECTIONS
{
.init :
{
_sinit = .;
. = ALIGN(4);
KEEP(*(SORT_NONE(.init)))
. = ALIGN(4);
_einit = .;
} >FLASH AT>FLASH
.vector :
{
*(.vector);
. = ALIGN(64);
} >FLASH AT>FLASH
.text :
{
. = ALIGN(4);
*(.text)
*(.text.*)
*(.rodata)
*(.rodata*)
*(.gnu.linkonce.t.*)
. = ALIGN(4);
} >FLASH AT>FLASH
.fini :
{
KEEP(*(SORT_NONE(.fini)))
. = ALIGN(4);
} >FLASH AT>FLASH
PROVIDE( _etext = . );
PROVIDE( _eitcm = . );
.preinit_array :
{
PROVIDE_HIDDEN (__preinit_array_start = .);
KEEP (*(.preinit_array))
PROVIDE_HIDDEN (__preinit_array_end = .);
} >FLASH AT>FLASH
.init_array :
{
PROVIDE_HIDDEN (__init_array_start = .);
KEEP (*(SORT_BY_INIT_PRIORITY(.init_array.*) SORT_BY_INIT_PRIORITY(.ctors.*)))
KEEP (*(.init_array EXCLUDE_FILE (*crtbegin.o *crtbegin?.o *crtend.o *crtend?.o ) .ctors))
PROVIDE_HIDDEN (__init_array_end = .);
} >FLASH AT>FLASH
.fini_array :
{
PROVIDE_HIDDEN (__fini_array_start = .);
KEEP (*(SORT_BY_INIT_PRIORITY(.fini_array.*) SORT_BY_INIT_PRIORITY(.dtors.*)))
KEEP (*(.fini_array EXCLUDE_FILE (*crtbegin.o *crtbegin?.o *crtend.o *crtend?.o ) .dtors))
PROVIDE_HIDDEN (__fini_array_end = .);
} >FLASH AT>FLASH
.ctors :
{
/* gcc uses crtbegin.o to find the start of
the constructors, so we make sure it is
first. Because this is a wildcard, it
doesn't matter if the user does not
actually link against crtbegin.o; the
linker won't look for a file to match a
wildcard. The wildcard also means that it
doesn't matter which directory crtbegin.o
is in. */
KEEP (*crtbegin.o(.ctors))
KEEP (*crtbegin?.o(.ctors))
/* We don't want to include the .ctor section from
the crtend.o file until after the sorted ctors.
The .ctor section from the crtend file contains the
end of ctors marker and it must be last */
KEEP (*(EXCLUDE_FILE (*crtend.o *crtend?.o ) .ctors))
KEEP (*(SORT(.ctors.*)))
KEEP (*(.ctors))
} >FLASH AT>FLASH
.dtors :
{
KEEP (*crtbegin.o(.dtors))
KEEP (*crtbegin?.o(.dtors))
KEEP (*(EXCLUDE_FILE (*crtend.o *crtend?.o ) .dtors))
KEEP (*(SORT(.dtors.*)))
KEEP (*(.dtors))
} >FLASH AT>FLASH
.dalign :
{
. = ALIGN(4);
PROVIDE(_data_vma = .);
} >RAM AT>FLASH
.dlalign :
{
. = ALIGN(4);
PROVIDE(_data_lma = .);
} >FLASH AT>FLASH
.data :
{
*(.gnu.linkonce.r.*)
*(.data .data.*)
*(.gnu.linkonce.d.*)
. = ALIGN(8);
PROVIDE( __global_pointer$ = . + 0x800 );
*(.sdata .sdata.*)
*(.sdata2.*)
*(.gnu.linkonce.s.*)
. = ALIGN(8);
*(.srodata.cst16)
*(.srodata.cst8)
*(.srodata.cst4)
*(.srodata.cst2)
*(.srodata .srodata.*)
. = ALIGN(4);
PROVIDE( _edata = .);
} >RAM AT>FLASH
.bss :
{
. = ALIGN(4);
PROVIDE( _sbss = .);
*(.sbss*)
*(.gnu.linkonce.sb.*)
*(.bss*)
*(.gnu.linkonce.b.*)
*(COMMON*)
. = ALIGN(4);
PROVIDE( _ebss = .);
} >RAM AT>FLASH
PROVIDE( _end = _ebss);
PROVIDE( end = . );
.stack ORIGIN(RAM) + LENGTH(RAM) - __stack_size :
{
PROVIDE( _heap_end = . );
. = ALIGN(4);
PROVIDE(_susrstack = . );
. = . + __stack_size;
PROVIDE( _eusrstack = .);
} >RAM
}

View File

@ -0,0 +1,600 @@
/********************************** (C) COPYRIGHT *******************************
* File Name : system_ch32v10x.c
* Author : WCH
* Version : V1.0.0
* Date : 2020/04/30
* Description : CH32V10x Device Peripheral Access Layer System Source File.
*********************************************************************************
* Copyright (c) 2021 Nanjing Qinheng Microelectronics Co., Ltd.
* Attention: This software (modified or not) and binary are used for
* microcontroller manufactured by Nanjing Qinheng Microelectronics.
*******************************************************************************/
#include "ch32v10x.h"
/*
* Uncomment the line corresponding to the desired System clock (SYSCLK) frequency (after
* reset the HSI is used as SYSCLK source).
* If none of the define below is enabled, the HSI is used as System clock source.
*/
//#define SYSCLK_FREQ_HSE HSE_VALUE
//#define SYSCLK_FREQ_48MHz_HSE 48000000
//#define SYSCLK_FREQ_56MHz_HSE 56000000
#define SYSCLK_FREQ_72MHz_HSE 72000000
//#define SYSCLK_FREQ_HSI HSI_VALUE
//#define SYSCLK_FREQ_48MHz_HSI 48000000
//#define SYSCLK_FREQ_56MHz_HSI 56000000
//#define SYSCLK_FREQ_72MHz_HSI 72000000
/* Clock Definitions */
#ifdef SYSCLK_FREQ_HSE
uint32_t SystemCoreClock = SYSCLK_FREQ_HSE; /* System Clock Frequency (Core Clock) */
#elif defined SYSCLK_FREQ_48MHz_HSE
uint32_t SystemCoreClock = SYSCLK_FREQ_48MHz_HSE; /* System Clock Frequency (Core Clock) */
#elif defined SYSCLK_FREQ_56MHz_HSE
uint32_t SystemCoreClock = SYSCLK_FREQ_56MHz_HSE; /* System Clock Frequency (Core Clock) */
#elif defined SYSCLK_FREQ_72MHz_HSE
uint32_t SystemCoreClock = SYSCLK_FREQ_72MHz_HSE; /* System Clock Frequency (Core Clock) */
#elif defined SYSCLK_FREQ_48MHz_HSI
uint32_t SystemCoreClock = SYSCLK_FREQ_48MHz_HSI; /* System Clock Frequency (Core Clock) */
#elif defined SYSCLK_FREQ_56MHz_HSI
uint32_t SystemCoreClock = SYSCLK_FREQ_56MHz_HSI; /* System Clock Frequency (Core Clock) */
#elif defined SYSCLK_FREQ_72MHz_HSI
uint32_t SystemCoreClock = SYSCLK_FREQ_72MHz_HSI; /* System Clock Frequency (Core Clock) */
#else
uint32_t SystemCoreClock = HSI_VALUE; /* System Clock Frequency (Core Clock) */
#endif
__I uint8_t AHBPrescTable[16] = {0, 0, 0, 0, 0, 0, 0, 0, 1, 2, 3, 4, 6, 7, 8, 9};
/* ch32v10x_system_private_function_proto_types */
static void SetSysClock(void);
#ifdef SYSCLK_FREQ_HSE
static void SetSysClockToHSE( void );
#elif defined SYSCLK_FREQ_48MHz_HSE
static void SetSysClockTo48_HSE( void );
#elif defined SYSCLK_FREQ_56MHz_HSE
static void SetSysClockTo56_HSE( void );
#elif defined SYSCLK_FREQ_72MHz_HSE
static void SetSysClockTo72_HSE( void );
#elif defined SYSCLK_FREQ_48MHz_HSI
static void SetSysClockTo48_HSI( void );
#elif defined SYSCLK_FREQ_56MHz_HSI
static void SetSysClockTo56_HSI( void );
#elif defined SYSCLK_FREQ_72MHz_HSI
static void SetSysClockTo72_HSI( void );
#endif
/*********************************************************************
* @fn SystemInit
*
* @brief Setup the microcontroller system Initialize the Embedded Flash Interface,
* the PLL and update the SystemCoreClock variable.
*
* @return none
*/
void SystemInit(void)
{
RCC->CTLR |= (uint32_t)0x00000001;
RCC->CFGR0 &= (uint32_t)0xF8FF0000;
RCC->CTLR &= (uint32_t)0xFEF6FFFF;
RCC->CTLR &= (uint32_t)0xFFFBFFFF;
RCC->CFGR0 &= (uint32_t)0xFF80FFFF;
RCC->INTR = 0x009F0000;
SetSysClock();
}
/*********************************************************************
* @fn SystemCoreClockUpdate
*
* @brief Update SystemCoreClock variable according to Clock Register Values.
*
* @return none
*/
void SystemCoreClockUpdate(void)
{
uint32_t tmp = 0, pllmull = 0, pllsource = 0;
tmp = RCC->CFGR0 & RCC_SWS;
switch(tmp)
{
case 0x00:
SystemCoreClock = HSI_VALUE;
break;
case 0x04:
SystemCoreClock = HSE_VALUE;
break;
case 0x08:
pllmull = RCC->CFGR0 & RCC_PLLMULL;
pllsource = RCC->CFGR0 & RCC_PLLSRC;
pllmull = (pllmull >> 18) + 2;
if(pllsource == 0x00)
{
if( EXTEN->EXTEN_CTR & EXTEN_PLL_HSI_PRE )
{
SystemCoreClock = ( HSI_VALUE ) * pllmull;
}
else
{
SystemCoreClock = ( HSI_VALUE >> 1 ) * pllmull;
}
}
else
{
if((RCC->CFGR0 & RCC_PLLXTPRE) != (uint32_t)RESET)
{
SystemCoreClock = (HSE_VALUE >> 1) * pllmull;
}
else
{
SystemCoreClock = HSE_VALUE * pllmull;
}
}
break;
default:
SystemCoreClock = HSI_VALUE;
break;
}
tmp = AHBPrescTable[((RCC->CFGR0 & RCC_HPRE) >> 4)];
SystemCoreClock >>= tmp;
}
/*********************************************************************
* @fn SetSysClock
*
* @brief Configures the System clock frequency, HCLK, PCLK2 and PCLK1 prescalers.
*
* @return none
*/
static void SetSysClock(void)
{
//GPIO_IPD_Unused();
#ifdef SYSCLK_FREQ_HSE
SetSysClockToHSE();
#elif defined SYSCLK_FREQ_48MHz_HSE
SetSysClockTo48_HSE();
#elif defined SYSCLK_FREQ_56MHz_HSE
SetSysClockTo56_HSE();
#elif defined SYSCLK_FREQ_72MHz_HSE
SetSysClockTo72_HSE();
#elif defined SYSCLK_FREQ_48MHz_HSI
SetSysClockTo48_HSI();
#elif defined SYSCLK_FREQ_56MHz_HSI
SetSysClockTo56_HSI();
#elif defined SYSCLK_FREQ_72MHz_HSI
SetSysClockTo72_HSI();
#endif
/* If none of the define above is enabled, the HSI is used as System clock
* source (default after reset)
*/
}
#ifdef SYSCLK_FREQ_HSE
/*********************************************************************
* @fn SetSysClockToHSE
*
* @brief Sets HSE as System clock source and configure HCLK, PCLK2 and PCLK1 prescalers.
*
* @return none
*/
static void SetSysClockToHSE(void)
{
__IO uint32_t StartUpCounter = 0, HSEStatus = 0;
RCC->CTLR |= ((uint32_t)RCC_HSEON);
/* Wait till HSE is ready and if Time out is reached exit */
do
{
HSEStatus = RCC->CTLR & RCC_HSERDY;
StartUpCounter++;
} while((HSEStatus == 0) && (StartUpCounter != HSE_STARTUP_TIMEOUT));
if((RCC->CTLR & RCC_HSERDY) != RESET)
{
HSEStatus = (uint32_t)0x01;
}
else
{
HSEStatus = (uint32_t)0x00;
}
if(HSEStatus == (uint32_t)0x01)
{
FLASH->ACTLR |= FLASH_ACTLR_PRFTBE;
/* Flash 0 wait state */
FLASH->ACTLR &= (uint32_t)((uint32_t)~FLASH_ACTLR_LATENCY);
FLASH->ACTLR |= (uint32_t)FLASH_ACTLR_LATENCY_0;
/* HCLK = SYSCLK */
RCC->CFGR0 |= (uint32_t)RCC_HPRE_DIV1;
/* PCLK2 = HCLK */
RCC->CFGR0 |= (uint32_t)RCC_PPRE2_DIV1;
/* PCLK1 = HCLK */
RCC->CFGR0 |= (uint32_t)RCC_PPRE1_DIV1;
/* Select HSE as system clock source */
RCC->CFGR0 &= (uint32_t)((uint32_t) ~(RCC_SW));
RCC->CFGR0 |= (uint32_t)RCC_SW_HSE;
/* Wait till HSE is used as system clock source */
while((RCC->CFGR0 & (uint32_t)RCC_SWS) != (uint32_t)0x04)
{
}
}
else
{
/* If HSE fails to start-up, the application will have wrong clock
* configuration. User can add here some code to deal with this error
*/
}
}
#elif defined SYSCLK_FREQ_48MHz_HSE
/*********************************************************************
* @fn SetSysClockTo48_HSE
*
* @brief Sets System clock frequency to 48MHz and configure HCLK, PCLK2 and PCLK1 prescalers.
*
* @return none
*/
static void SetSysClockTo48_HSE(void)
{
__IO uint32_t StartUpCounter = 0, HSEStatus = 0;
RCC->CTLR |= ((uint32_t)RCC_HSEON);
/* Wait till HSE is ready and if Time out is reached exit */
do
{
HSEStatus = RCC->CTLR & RCC_HSERDY;
StartUpCounter++;
} while((HSEStatus == 0) && (StartUpCounter != HSE_STARTUP_TIMEOUT));
if((RCC->CTLR & RCC_HSERDY) != RESET)
{
HSEStatus = (uint32_t)0x01;
}
else
{
HSEStatus = (uint32_t)0x00;
}
if(HSEStatus == (uint32_t)0x01)
{
/* Enable Prefetch Buffer */
FLASH->ACTLR |= FLASH_ACTLR_PRFTBE;
/* Flash 1 wait state */
FLASH->ACTLR &= (uint32_t)((uint32_t)~FLASH_ACTLR_LATENCY);
FLASH->ACTLR |= (uint32_t)FLASH_ACTLR_LATENCY_1;
/* HCLK = SYSCLK */
RCC->CFGR0 |= (uint32_t)RCC_HPRE_DIV1;
/* PCLK2 = HCLK */
RCC->CFGR0 |= (uint32_t)RCC_PPRE2_DIV1;
/* PCLK1 = HCLK */
RCC->CFGR0 |= (uint32_t)RCC_PPRE1_DIV2;
/* PLL configuration: PLLCLK = HSE * 6 = 48 MHz */
RCC->CFGR0 &= (uint32_t)((uint32_t) ~(RCC_PLLSRC | RCC_PLLXTPRE | RCC_PLLMULL));
RCC->CFGR0 |= (uint32_t)(RCC_PLLSRC_HSE | RCC_PLLMULL6);
/* Enable PLL */
RCC->CTLR |= RCC_PLLON;
/* Wait till PLL is ready */
while((RCC->CTLR & RCC_PLLRDY) == 0)
{
}
/* Select PLL as system clock source */
RCC->CFGR0 &= (uint32_t)((uint32_t) ~(RCC_SW));
RCC->CFGR0 |= (uint32_t)RCC_SW_PLL;
/* Wait till PLL is used as system clock source */
while((RCC->CFGR0 & (uint32_t)RCC_SWS) != (uint32_t)0x08)
{
}
}
else
{
/*
* If HSE fails to start-up, the application will have wrong clock
* configuration. User can add here some code to deal with this error
*/
}
}
#elif defined SYSCLK_FREQ_56MHz_HSE
/*********************************************************************
* @fn SetSysClockTo56_HSE
*
* @brief Sets System clock frequency to 56MHz and configure HCLK, PCLK2 and PCLK1 prescalers.
*
* @return none
*/
static void SetSysClockTo56_HSE(void)
{
__IO uint32_t StartUpCounter = 0, HSEStatus = 0;
RCC->CTLR |= ((uint32_t)RCC_HSEON);
/* Wait till HSE is ready and if Time out is reached exit */
do
{
HSEStatus = RCC->CTLR & RCC_HSERDY;
StartUpCounter++;
} while((HSEStatus == 0) && (StartUpCounter != HSE_STARTUP_TIMEOUT));
if((RCC->CTLR & RCC_HSERDY) != RESET)
{
HSEStatus = (uint32_t)0x01;
}
else
{
HSEStatus = (uint32_t)0x00;
}
if(HSEStatus == (uint32_t)0x01)
{
/* Enable Prefetch Buffer */
FLASH->ACTLR |= FLASH_ACTLR_PRFTBE;
/* Flash 2 wait state */
FLASH->ACTLR &= (uint32_t)((uint32_t)~FLASH_ACTLR_LATENCY);
FLASH->ACTLR |= (uint32_t)FLASH_ACTLR_LATENCY_2;
/* HCLK = SYSCLK */
RCC->CFGR0 |= (uint32_t)RCC_HPRE_DIV1;
/* PCLK2 = HCLK */
RCC->CFGR0 |= (uint32_t)RCC_PPRE2_DIV1;
/* PCLK1 = HCLK */
RCC->CFGR0 |= (uint32_t)RCC_PPRE1_DIV2;
/* PLL configuration: PLLCLK = HSE * 7 = 56 MHz */
RCC->CFGR0 &= (uint32_t)((uint32_t) ~(RCC_PLLSRC | RCC_PLLXTPRE | RCC_PLLMULL));
RCC->CFGR0 |= (uint32_t)(RCC_PLLSRC_HSE | RCC_PLLMULL7);
/* Enable PLL */
RCC->CTLR |= RCC_PLLON;
/* Wait till PLL is ready */
while((RCC->CTLR & RCC_PLLRDY) == 0)
{
}
/* Select PLL as system clock source */
RCC->CFGR0 &= (uint32_t)((uint32_t) ~(RCC_SW));
RCC->CFGR0 |= (uint32_t)RCC_SW_PLL;
/* Wait till PLL is used as system clock source */
while((RCC->CFGR0 & (uint32_t)RCC_SWS) != (uint32_t)0x08)
{
}
}
else
{
/*
* If HSE fails to start-up, the application will have wrong clock
* configuration. User can add here some code to deal with this error
*/
}
}
#elif defined SYSCLK_FREQ_72MHz_HSE
/*********************************************************************
* @fn SetSysClockTo72_HSE
*
* @brief Sets System clock frequency to 72MHz and configure HCLK, PCLK2 and PCLK1 prescalers.
*
* @return none
*/
static void SetSysClockTo72_HSE(void)
{
__IO uint32_t StartUpCounter = 0, HSEStatus = 0;
RCC->CTLR |= ((uint32_t)RCC_HSEON);
/* Wait till HSE is ready and if Time out is reached exit */
do
{
HSEStatus = RCC->CTLR & RCC_HSERDY;
StartUpCounter++;
} while((HSEStatus == 0) && (StartUpCounter != HSE_STARTUP_TIMEOUT));
if((RCC->CTLR & RCC_HSERDY) != RESET)
{
HSEStatus = (uint32_t)0x01;
}
else
{
HSEStatus = (uint32_t)0x00;
}
if(HSEStatus == (uint32_t)0x01)
{
/* Enable Prefetch Buffer */
FLASH->ACTLR |= FLASH_ACTLR_PRFTBE;
/* Flash 2 wait state */
FLASH->ACTLR &= (uint32_t)((uint32_t)~FLASH_ACTLR_LATENCY);
FLASH->ACTLR |= (uint32_t)FLASH_ACTLR_LATENCY_2;
/* HCLK = SYSCLK */
RCC->CFGR0 |= (uint32_t)RCC_HPRE_DIV1;
/* PCLK2 = HCLK */
RCC->CFGR0 |= (uint32_t)RCC_PPRE2_DIV1;
/* PCLK1 = HCLK */
RCC->CFGR0 |= (uint32_t)RCC_PPRE1_DIV2;
/* PLL configuration: PLLCLK = HSE * 9 = 72 MHz */
RCC->CFGR0 &= (uint32_t)((uint32_t) ~(RCC_PLLSRC | RCC_PLLXTPRE |
RCC_PLLMULL));
RCC->CFGR0 |= (uint32_t)(RCC_PLLSRC_HSE | RCC_PLLMULL9);
/* Enable PLL */
RCC->CTLR |= RCC_PLLON;
/* Wait till PLL is ready */
while((RCC->CTLR & RCC_PLLRDY) == 0)
{
}
/* Select PLL as system clock source */
RCC->CFGR0 &= (uint32_t)((uint32_t) ~(RCC_SW));
RCC->CFGR0 |= (uint32_t)RCC_SW_PLL;
/* Wait till PLL is used as system clock source */
while((RCC->CFGR0 & (uint32_t)RCC_SWS) != (uint32_t)0x08)
{
}
}
else
{
/*
* If HSE fails to start-up, the application will have wrong clock
* configuration. User can add here some code to deal with this error
*/
}
}
#elif defined SYSCLK_FREQ_48MHz_HSI
/*********************************************************************
* @fn SetSysClockTo48_HSI
*
* @brief Sets System clock frequency to 48MHz and configure HCLK, PCLK2 and PCLK1 prescalers.
*
* @return none
*/
static void SetSysClockTo48_HSI(void)
{
EXTEN->EXTEN_CTR |= EXTEN_PLL_HSI_PRE;
/* Enable Prefetch Buffer */
FLASH->ACTLR |= FLASH_ACTLR_PRFTBE;
/* Flash 1 wait state */
FLASH->ACTLR &= (uint32_t)((uint32_t)~FLASH_ACTLR_LATENCY);
FLASH->ACTLR |= (uint32_t)FLASH_ACTLR_LATENCY_1;
/* HCLK = SYSCLK */
RCC->CFGR0 |= (uint32_t)RCC_HPRE_DIV1;
/* PCLK2 = HCLK */
RCC->CFGR0 |= (uint32_t)RCC_PPRE2_DIV1;
/* PCLK1 = HCLK */
RCC->CFGR0 |= (uint32_t)RCC_PPRE1_DIV2;
/* PLL configuration: PLLCLK = HSI * 6 = 48 MHz */
RCC->CFGR0 &= (uint32_t)((uint32_t) ~(RCC_PLLSRC | RCC_PLLXTPRE | RCC_PLLMULL));
RCC->CFGR0 |= (uint32_t)(RCC_PLLSRC_HSI_Div2 | RCC_PLLMULL6);
/* Enable PLL */
RCC->CTLR |= RCC_PLLON;
/* Wait till PLL is ready */
while((RCC->CTLR & RCC_PLLRDY) == 0)
{
}
/* Select PLL as system clock source */
RCC->CFGR0 &= (uint32_t)((uint32_t) ~(RCC_SW));
RCC->CFGR0 |= (uint32_t)RCC_SW_PLL;
/* Wait till PLL is used as system clock source */
while((RCC->CFGR0 & (uint32_t)RCC_SWS) != (uint32_t)0x08)
{
}
}
#elif defined SYSCLK_FREQ_56MHz_HSI
/*********************************************************************
* @fn SetSysClockTo56_HSI
*
* @brief Sets System clock frequency to 56MHz and configure HCLK, PCLK2 and PCLK1 prescalers.
*
* @return none
*/
static void SetSysClockTo56_HSI(void)
{
EXTEN->EXTEN_CTR |= EXTEN_PLL_HSI_PRE;
/* Enable Prefetch Buffer */
FLASH->ACTLR |= FLASH_ACTLR_PRFTBE;
/* Flash 1 wait state */
FLASH->ACTLR &= (uint32_t)((uint32_t)~FLASH_ACTLR_LATENCY);
FLASH->ACTLR |= (uint32_t)FLASH_ACTLR_LATENCY_1;
/* HCLK = SYSCLK */
RCC->CFGR0 |= (uint32_t)RCC_HPRE_DIV1;
/* PCLK2 = HCLK */
RCC->CFGR0 |= (uint32_t)RCC_PPRE2_DIV1;
/* PCLK1 = HCLK */
RCC->CFGR0 |= (uint32_t)RCC_PPRE1_DIV2;
/* PLL configuration: PLLCLK = HSI * 7 = 56 MHz */
RCC->CFGR0 &= (uint32_t)((uint32_t) ~(RCC_PLLSRC | RCC_PLLXTPRE | RCC_PLLMULL));
RCC->CFGR0 |= (uint32_t)(RCC_PLLSRC_HSI_Div2 | RCC_PLLMULL7);
/* Enable PLL */
RCC->CTLR |= RCC_PLLON;
/* Wait till PLL is ready */
while((RCC->CTLR & RCC_PLLRDY) == 0)
{
}
/* Select PLL as system clock source */
RCC->CFGR0 &= (uint32_t)((uint32_t) ~(RCC_SW));
RCC->CFGR0 |= (uint32_t)RCC_SW_PLL;
/* Wait till PLL is used as system clock source */
while((RCC->CFGR0 & (uint32_t)RCC_SWS) != (uint32_t)0x08)
{
}
}
#elif defined SYSCLK_FREQ_72MHz_HSI
/*********************************************************************
* @fn SetSysClockTo72_HSI
*
* @brief Sets System clock frequency to 72MHz and configure HCLK, PCLK2 and PCLK1 prescalers.
*
* @return none
*/
static void SetSysClockTo72_HSI(void)
{
EXTEN->EXTEN_CTR |= EXTEN_PLL_HSI_PRE;
/* Enable Prefetch Buffer */
FLASH->ACTLR |= FLASH_ACTLR_PRFTBE;
/* Flash 1 wait state */
FLASH->ACTLR &= (uint32_t)((uint32_t)~FLASH_ACTLR_LATENCY);
FLASH->ACTLR |= (uint32_t)FLASH_ACTLR_LATENCY_1;
/* HCLK = SYSCLK */
RCC->CFGR0 |= (uint32_t)RCC_HPRE_DIV1;
/* PCLK2 = HCLK */
RCC->CFGR0 |= (uint32_t)RCC_PPRE2_DIV1;
/* PCLK1 = HCLK */
RCC->CFGR0 |= (uint32_t)RCC_PPRE1_DIV2;
/* PLL configuration: PLLCLK = HSI * 9 = 72 MHz */
RCC->CFGR0 &= (uint32_t)((uint32_t) ~(RCC_PLLSRC | RCC_PLLXTPRE | RCC_PLLMULL));
RCC->CFGR0 |= (uint32_t)(RCC_PLLSRC_HSI_Div2 | RCC_PLLMULL9);
/* Enable PLL */
RCC->CTLR |= RCC_PLLON;
/* Wait till PLL is ready */
while((RCC->CTLR & RCC_PLLRDY) == 0)
{
}
/* Select PLL as system clock source */
RCC->CFGR0 &= (uint32_t)((uint32_t) ~(RCC_SW));
RCC->CFGR0 |= (uint32_t)RCC_SW_PLL;
/* Wait till PLL is used as system clock source */
while((RCC->CFGR0 & (uint32_t)RCC_SWS) != (uint32_t)0x08)
{
}
}
#endif

View File

@ -0,0 +1,29 @@
/********************************** (C) COPYRIGHT *******************************
* File Name : system_ch32v10x.h
* Author : WCH
* Version : V1.0.0
* Date : 2020/04/30
* Description : CH32V10x Device Peripheral Access Layer System Header File.
*********************************************************************************
* Copyright (c) 2021 Nanjing Qinheng Microelectronics Co., Ltd.
* Attention: This software (modified or not) and binary are used for
* microcontroller manufactured by Nanjing Qinheng Microelectronics.
*******************************************************************************/
#ifndef __SYSTEM_CH32V10x_H
#define __SYSTEM_CH32V10x_H
#ifdef __cplusplus
extern "C" {
#endif
extern uint32_t SystemCoreClock; /* System Clock Frequency (Core Clock) */
/* System_Exported_Functions */
extern void SystemInit(void);
extern void SystemCoreClockUpdate(void);
#ifdef __cplusplus
}
#endif
#endif /*__CH32V10x_SYSTEM_H */

View File

@ -0,0 +1,17 @@
adapter driver wlinke
adapter speed 6000
transport select sdi
wlink_set_address 0x00000000
set _CHIPNAME wch_riscv
sdi newtap $_CHIPNAME cpu -irlen 5 -expected-id 0x00001
set _TARGETNAME $_CHIPNAME.cpu
target create $_TARGETNAME.0 wch_riscv -chain-position $_TARGETNAME
$_TARGETNAME.0 configure -work-area-phys 0x20000000 -work-area-size 10000 -work-area-backup 1
set _FLASHNAME $_CHIPNAME.flash
flash bank $_FLASHNAME wch_riscv 0x00000000 0 0 0 $_TARGETNAME.0
echo "Ready for Remote Connections"

View File

@ -45,12 +45,12 @@ SRC_C += \
src/portable/wch/dcd_ch32_usbfs.c \
src/portable/st/stm32_fsdev/dcd_stm32_fsdev.c \
$(SDK_SRC_DIR)/Core/core_riscv.c \
$(SDK_SRC_DIR)/Peripheral/src/ch32v20x_gpio.c \
$(SDK_SRC_DIR)/Peripheral/src/ch32v20x_misc.c \
$(SDK_SRC_DIR)/Peripheral/src/ch32v20x_rcc.c \
$(SDK_SRC_DIR)/Peripheral/src/ch32v20x_usart.c \
$(SDK_SRC_DIR)/Peripheral/src/${CH32_FAMILY}_gpio.c \
$(SDK_SRC_DIR)/Peripheral/src/${CH32_FAMILY}_misc.c \
$(SDK_SRC_DIR)/Peripheral/src/${CH32_FAMILY}_rcc.c \
$(SDK_SRC_DIR)/Peripheral/src/${CH32_FAMILY}_usart.c \
SRC_S += $(SDK_SRC_DIR)/Startup/startup_ch32v20x_${MCU_VARIANT}.S
SRC_S += $(SDK_SRC_DIR)/Startup/startup_${CH32_FAMILY}_${MCU_VARIANT}.S
INC += \
$(TOP)/$(BOARD_PATH) \

View File

@ -443,7 +443,7 @@ function(family_flash_openocd TARGET)
# note skip verify since it has issue with rp2040
add_custom_target(${TARGET}-openocd
DEPENDS ${TARGET}
COMMAND ${OPENOCD} ${OPTION_LIST} -c "program $<TARGET_FILE:${TARGET}> reset" ${OPTION_LIST2} -c exit
COMMAND ${OPENOCD} ${OPTION_LIST} -c init -c halt -c "program $<TARGET_FILE:${TARGET}> reset" ${OPTION_LIST2} -c exit
VERBATIM
)
endfunction()

View File

@ -420,6 +420,15 @@
#define TUP_RHPORT_HIGHSPEED CFG_TUD_WCH_USBIP_USBHS
#define TUP_DCD_ENDPOINT_MAX (CFG_TUD_WCH_USBIP_USBHS ? 16 : 8)
#elif TU_CHECK_MCU(OPT_MCU_CH32V103)
#define TUP_USBIP_WCH_USBFS
#if !defined(CFG_TUD_WCH_USBIP_USBFS)
#define CFG_TUD_WCH_USBIP_USBFS 1
#endif
#define TUP_DCD_ENDPOINT_MAX 8
#elif TU_CHECK_MCU(OPT_MCU_CH32V20X)
// v20x support both FSDEV (USBD) and USBFS, default to FSDEV
#define TUP_USBIP_WCH_USBFS

View File

@ -35,15 +35,68 @@
#pragma GCC diagnostic ignored "-Wstrict-prototypes"
#endif
#if CFG_TUSB_MCU == OPT_MCU_CH32V307
#include <ch32v30x.h>
#define USBHD_IRQn OTG_FS_IRQn
#if CFG_TUSB_MCU == OPT_MCU_CH32F20X
#include <ch32f20x.h>
#elif CFG_TUSB_MCU == OPT_MCU_CH32V103
#include <ch32v10x.h>
typedef struct
{
__IO uint8_t BASE_CTRL;
__IO uint8_t UDEV_CTRL;
__IO uint8_t INT_EN;
__IO uint8_t DEV_ADDR;
__IO uint8_t Reserve0;
__IO uint8_t MIS_ST;
__IO uint8_t INT_FG;
__IO uint8_t INT_ST;
__IO uint32_t RX_LEN;
__IO uint8_t UEP4_1_MOD;
__IO uint8_t UEP2_3_MOD;
__IO uint8_t UEP5_6_MOD;
__IO uint8_t UEP7_MOD;
__IO uint32_t UEP0_DMA;
__IO uint32_t UEP1_DMA;
__IO uint32_t UEP2_DMA;
__IO uint32_t UEP3_DMA;
__IO uint32_t UEP4_DMA;
__IO uint32_t UEP5_DMA;
__IO uint32_t UEP6_DMA;
__IO uint32_t UEP7_DMA;
__IO uint16_t UEP0_TX_LEN;
__IO uint8_t UEP0_TX_CTRL;
__IO uint8_t UEP0_RX_CTRL;
__IO uint16_t UEP1_TX_LEN;
__IO uint8_t UEP1_TX_CTRL;
__IO uint8_t UEP1_RX_CTRL;
__IO uint16_t UEP2_TX_LEN;
__IO uint8_t UEP2_TX_CTRL;
__IO uint8_t UEP2_RX_CTRL;
__IO uint16_t UEP3_TX_LEN;
__IO uint8_t UEP3_TX_CTRL;
__IO uint8_t UEP3_RX_CTRL;
__IO uint16_t UEP4_TX_LEN;
__IO uint8_t UEP4_TX_CTRL;
__IO uint8_t UEP4_RX_CTRL;
__IO uint16_t UEP5_TX_LEN;
__IO uint8_t UEP5_TX_CTRL;
__IO uint8_t UEP5_RX_CTRL;
__IO uint16_t UEP6_TX_LEN;
__IO uint8_t UEP6_TX_CTRL;
__IO uint8_t UEP6_RX_CTRL;
__IO uint16_t UEP7_TX_LEN;
__IO uint8_t UEP7_TX_CTRL;
__IO uint8_t UEP7_RX_CTRL;
__IO uint32_t Reserve1;
__IO uint32_t OTG_CR;
__IO uint32_t OTG_SR;
} USBOTG_FS_TypeDef;
#define USBOTG_FS ((USBOTG_FS_TypeDef *) 0x40023400)
#elif CFG_TUSB_MCU == OPT_MCU_CH32V20X
#include <ch32v20x.h>
#elif CFG_TUSB_MCU == OPT_MCU_CH32F20X
#include <ch32f20x.h>
#elif CFG_TUSB_MCU == OPT_MCU_CH32V307
#include <ch32v30x.h>
#define USBHD_IRQn OTG_FS_IRQn
#endif
#ifdef __GNUC__

View File

@ -24,8 +24,8 @@
* This file is part of the TinyUSB stack.
*/
#ifndef _TUSB_OPTION_H_
#define _TUSB_OPTION_H_
#ifndef TUSB_OPTION_H_
#define TUSB_OPTION_H_
#include "common/tusb_compiler.h"
@ -182,7 +182,7 @@
#define OPT_MCU_CH32V307 2200 ///< WCH CH32V307
#define OPT_MCU_CH32F20X 2210 ///< WCH CH32F20x
#define OPT_MCU_CH32V20X 2220 ///< WCH CH32V20X
#define OPT_MCU_CH32V103 2230 ///< WCH CH32V103
// NXP LPC MCX
#define OPT_MCU_MCXN9 2300 ///< NXP MCX N9 Series

View File

@ -168,6 +168,9 @@ deps_optional = {
'hw/mcu/ti': ['https://github.com/hathach/ti_driver.git',
'143ed6cc20a7615d042b03b21e070197d473e6e5',
'msp430 msp432e4 tm4c'],
'hw/mcu/wch/ch32v103': ['https://github.com/openwch/ch32v103.git',
'7578cae0b21f86dd053a1f781b2fc6ab99d0ec17',
'ch32v10x'],
'hw/mcu/wch/ch32v20x': ['https://github.com/openwch/ch32v20x.git',
'de6d68c654340d7f27b00cebbfc9aa2740a1abc2',
'ch32v20x'],