From ce627f431831e1fbaa3bb7bad35a489b8006b749 Mon Sep 17 00:00:00 2001 From: "denis.krasutski" Date: Fri, 6 Oct 2023 13:04:54 +0300 Subject: [PATCH 1/2] feat(ch32f20x): add support of ch32f20x --- .gitignore | 1 + README.rst | 2 +- docs/reference/dependencies.rst | 1 + docs/reference/supported.rst | 5 +- hw/bsp/board_mcu.h | 3 + hw/bsp/ch32f20x/boards/ch32f205r-r0/board.h | 59 + hw/bsp/ch32f20x/boards/ch32f205r-r0/board.mk | 7 + hw/bsp/ch32f20x/ch32f205.ld | 111 ++ hw/bsp/ch32f20x/ch32f20x_conf.h | 40 + hw/bsp/ch32f20x/ch32f20x_it.c | 35 + hw/bsp/ch32f20x/ch32f20x_it.h | 25 + hw/bsp/ch32f20x/core_cm3.h | 11 + hw/bsp/ch32f20x/debug_uart.c | 105 ++ hw/bsp/ch32f20x/debug_uart.h | 31 + hw/bsp/ch32f20x/family.c | 141 +++ hw/bsp/ch32f20x/family.mk | 30 + hw/bsp/ch32f20x/startup_gcc_ch32f20x_d8c.s | 493 ++++++++ hw/bsp/ch32f20x/system_ch32f20x.c | 1122 +++++++++++++++++ hw/bsp/ch32f20x/system_ch32f20x.h | 28 + hw/bsp/ch32v307/family.mk | 2 +- src/common/tusb_mcu.h | 4 + .../wch/{ch32v307 => }/ch32_usbhs_reg.h | 4 + .../dcd_usbhs.c => dcd_ch32_usbhs.c} | 6 +- src/tusb_option.h | 1 + tools/get_deps.py | 3 + tools/iar_template.ipcf | 4 +- 26 files changed, 2266 insertions(+), 8 deletions(-) create mode 100644 hw/bsp/ch32f20x/boards/ch32f205r-r0/board.h create mode 100644 hw/bsp/ch32f20x/boards/ch32f205r-r0/board.mk create mode 100644 hw/bsp/ch32f20x/ch32f205.ld create mode 100644 hw/bsp/ch32f20x/ch32f20x_conf.h create mode 100644 hw/bsp/ch32f20x/ch32f20x_it.c create mode 100644 hw/bsp/ch32f20x/ch32f20x_it.h create mode 100644 hw/bsp/ch32f20x/core_cm3.h create mode 100644 hw/bsp/ch32f20x/debug_uart.c create mode 100644 hw/bsp/ch32f20x/debug_uart.h create mode 100644 hw/bsp/ch32f20x/family.c create mode 100644 hw/bsp/ch32f20x/family.mk create mode 100644 hw/bsp/ch32f20x/startup_gcc_ch32f20x_d8c.s create mode 100644 hw/bsp/ch32f20x/system_ch32f20x.c create mode 100644 hw/bsp/ch32f20x/system_ch32f20x.h rename src/portable/wch/{ch32v307 => }/ch32_usbhs_reg.h (98%) rename src/portable/wch/{ch32v307/dcd_usbhs.c => dcd_ch32_usbhs.c} (98%) diff --git a/.gitignore b/.gitignore index c665d6c737..e6ccec736e 100644 --- a/.gitignore +++ b/.gitignore @@ -81,6 +81,7 @@ hw/mcu/st/stm32u5xx_hal_driver hw/mcu/st/stm32wbxx_hal_driver hw/mcu/ti hw/mcu/wch/ch32v307 +hw/mcu/wch/ch32f20x lib/CMSIS_5 lib/FreeRTOS-Kernel lib/lwip diff --git a/README.rst b/README.rst index aef310b984..919596e676 100644 --- a/README.rst +++ b/README.rst @@ -60,7 +60,7 @@ The stack supports the following MCUs: - **ST:** STM32 series: F0, F1, F2, F3, F4, F7, H7, G0, G4, L0, L1, L4, L4+, WB - **TI:** MSP430, MSP432E4, TM4C123 - **ValentyUSB:** eptri -- **WCH:** CH32V307 +- **WCH:** CH32V307, CH32F20x Here is the list of `Supported Devices`_ that can be used with provided examples. diff --git a/docs/reference/dependencies.rst b/docs/reference/dependencies.rst index 130527e2c1..d532a3a1ed 100644 --- a/docs/reference/dependencies.rst +++ b/docs/reference/dependencies.rst @@ -56,6 +56,7 @@ hw/mcu/st/stm32u5xx_hal_driver https://github.com/STMicroelectronics/ hw/mcu/st/stm32wbxx_hal_driver https://github.com/STMicroelectronics/stm32wbxx_hal_driver.git 2c5f06638be516c1b772f768456ba637f077bac8 hw/mcu/ti https://github.com/hathach/ti_driver.git 143ed6cc20a7615d042b03b21e070197d473e6e5 hw/mcu/wch/ch32v307 https://github.com/openwch/ch32v307.git 17761f5cf9dbbf2dcf665b7c04934188add20082 +hw/mcu/wch/ch32f20x https://github.com/openwch/ch32f20x.git 77c4095087e5ed2c548ec9058e655d0b8757663b lib/CMSIS_5 https://github.com/ARM-software/CMSIS_5.git 20285262657d1b482d132d20d755c8c330d55c1f lib/FreeRTOS-Kernel https://github.com/FreeRTOS/FreeRTOS-Kernel.git def7d2df2b0506d3d249334974f51e427c17a41c lib/lwip https://github.com/lwip-tcpip/lwip.git 159e31b689577dbf69cf0683bbaffbd71fa5ee10 diff --git a/docs/reference/supported.rst b/docs/reference/supported.rst index aed64782ce..8843dd405f 100644 --- a/docs/reference/supported.rst +++ b/docs/reference/supported.rst @@ -109,6 +109,8 @@ Supported MCUs | ValentyUSB | eptri | ✔ | ✖ | ✖ | eptri | | +--------------+-----------------------+--------+------+-----------+-------------------+--------------+ | WCH | CH32V307 | ✔ | | ✔ | ch32v307 | | +| +-----------------------+--------+------+-----------+-------------------+--------------+ +| | CH32F20x | ✔ | | ✔ | ch32f205 | | +--------------+-----------------------+--------+------+-----------+-------------------+--------------+ @@ -415,4 +417,5 @@ Tomu WCH --- -- `CH32V307V-R1-1v0 ` +- `CH32V307V-R1-1v0 `__ +- `CH32F205R-R0-1v0 `__ diff --git a/hw/bsp/board_mcu.h b/hw/bsp/board_mcu.h index e5d2bb608b..4ce5c41396 100644 --- a/hw/bsp/board_mcu.h +++ b/hw/bsp/board_mcu.h @@ -161,6 +161,9 @@ #elif CFG_TUSB_MCU == OPT_MCU_TM4C123 #include "TM4C123.h" +#elif CFG_TUSB_MCU == OPT_MCU_CH32F20X + #include "ch32f20x.h" + #elif TU_CHECK_MCU(OPT_MCU_BCM2711, OPT_MCU_BCM2835, OPT_MCU_BCM2837) // no header needed diff --git a/hw/bsp/ch32f20x/boards/ch32f205r-r0/board.h b/hw/bsp/ch32f20x/boards/ch32f205r-r0/board.h new file mode 100644 index 0000000000..d5849bddb7 --- /dev/null +++ b/hw/bsp/ch32f20x/boards/ch32f205r-r0/board.h @@ -0,0 +1,59 @@ +/* + * The MIT License (MIT) + * + * Copyright (c) 2023, Denis Krasutski + * + * 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. + */ + +#ifndef BOARD_H_ +#define BOARD_H_ + +#ifdef __cplusplus + extern "C" { +#endif + +// LED: need to wire pin LED1 to PC0 in the P1 header +#define LED_PORT GPIOC +#define LED_PIN GPIO_Pin_1 +#define LED_STATE_ON 0 +#define LED_CLOCK_EN() RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOC, ENABLE) + +// Button: need to wire pin KEY to PC1 in the P1 header +#define BUTTON_PORT GPIOC +#define BUTTON_PIN GPIO_Pin_0 +#define BUTTON_STATE_ACTIVE 0 +#define BUTTON_CLOCK_EN() RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOC, ENABLE) + +// UART +#define UART_DEV USART2 +#define UART_DEV_IRQn USART2_IRQn +#define UART_DEV_IRQHandler USART2_IRQHandler +#define UART_DEV_GPIO_PORT GPIOA +#define UART_DEV_TX_PIN GPIO_Pin_2 +#define UART_DEV_CLK_EN() do { \ + RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOA, ENABLE); \ + RCC_APB1PeriphClockCmd(RCC_APB1Periph_USART2, ENABLE); \ + } while(0) + +#ifdef __cplusplus + } +#endif + +#endif diff --git a/hw/bsp/ch32f20x/boards/ch32f205r-r0/board.mk b/hw/bsp/ch32f20x/boards/ch32f205r-r0/board.mk new file mode 100644 index 0000000000..f0e9bf30fe --- /dev/null +++ b/hw/bsp/ch32f20x/boards/ch32f205r-r0/board.mk @@ -0,0 +1,7 @@ +LD_FILE = $(FAMILY_PATH)/ch32f205.ld + +SRC_S += \ + $(FAMILY_PATH)/startup_gcc_ch32f20x_d8c.s + +CFLAGS += \ + -DCH32F20x_D8C diff --git a/hw/bsp/ch32f20x/ch32f205.ld b/hw/bsp/ch32f20x/ch32f205.ld new file mode 100644 index 0000000000..7c8d04cc51 --- /dev/null +++ b/hw/bsp/ch32f20x/ch32f205.ld @@ -0,0 +1,111 @@ +ENTRY(Reset_Handler) + +_Min_Heap_Size = 0x200; +_Min_Stack_Size = 0x400; + +MEMORY +{ + FLASH (rx) : ORIGIN = 0x08000000, LENGTH = 128K + RAM (xrw) : ORIGIN = 0x20000000, LENGTH = 32K +} +SECTIONS +{ + .isr_vector : + { + . = ALIGN(4); + KEEP(*(.isr_vector)) + . = ALIGN(4); + } >FLASH + + .text : + { + . = ALIGN(4); + _stext = .; + *(.text) + *(.text*) + *(.glue_7) + *(.glue_7t) + *(.eh_frame) + KEEP (*(.init)) + KEEP (*(.fini)) + . = ALIGN(4); + _etext = .; + } >FLASH + .rodata : + { + . = ALIGN(4); + *(.rodata) + *(.rodata*) + . = ALIGN(4); + } >FLASH + .ARM.extab : { *(.ARM.extab* .gnu.linkonce.armextab.*) } >FLASH + .ARM : { + __exidx_start = .; + *(.ARM.exidx*) + __exidx_end = .; + } >FLASH + .preinit_array : + { + PROVIDE_HIDDEN (__preinit_array_start = .); + KEEP (*(.preinit_array*)) + PROVIDE_HIDDEN (__preinit_array_end = .); + } >FLASH + .init_array : + { + PROVIDE_HIDDEN (__init_array_start = .); + KEEP (*(SORT(.init_array.*))) + KEEP (*(.init_array*)) + PROVIDE_HIDDEN (__init_array_end = .); + } >FLASH + .fini_array : + { + PROVIDE_HIDDEN (__fini_array_start = .); + KEEP (*(SORT(.fini_array.*))) + KEEP (*(.fini_array*)) + PROVIDE_HIDDEN (__fini_array_end = .); + } >FLASH + _sidata = LOADADDR(.data); + .data : + { + . = ALIGN(4); + _sdata = .; + *(.data) + *(.data*) + . = ALIGN(4); + _edata = .; + } >RAM AT> FLASH + . = ALIGN(4); + .bss : + { + _sbss = .; + __bss_start__ = _sbss; + *(.bss) + *(.bss*) + *(COMMON) + . = ALIGN(4); + _ebss = .; + __bss_end__ = _ebss; + } >RAM + ._user_heap_stack : + { + . = ALIGN(4); + PROVIDE ( end = . ); + PROVIDE ( _end = . ); + __HeapStart = .; + . = . + _Min_Heap_Size; + __HeapEnd = .; + __StackLimit = .; + . = . + _Min_Stack_Size; + __StackTop = .; + . = ALIGN(4); + } >RAM +_estack = __StackTop; +_sstack = __StackLimit; + /DISCARD/ : + { + libc.a ( * ) + libm.a ( * ) + libgcc.a ( * ) + } + .ARM.attributes 0 : { *(.ARM.attributes) } +} diff --git a/hw/bsp/ch32f20x/ch32f20x_conf.h b/hw/bsp/ch32f20x/ch32f20x_conf.h new file mode 100644 index 0000000000..f94da5dec4 --- /dev/null +++ b/hw/bsp/ch32f20x/ch32f20x_conf.h @@ -0,0 +1,40 @@ +/********************************** (C) COPYRIGHT ******************************* + * File Name : ch32f20x_conf.h + * Author : WCH + * Version : V1.0.0 + * Date : 2021/08/08 + * 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 __CH32F20x_CONF_H +#define __CH32F20x_CONF_H + +#include "ch32f20x_adc.h" +#include "ch32f20x_bkp.h" +#include "ch32f20x_can.h" +#include "ch32f20x_crc.h" +#include "ch32f20x_dac.h" +#include "ch32f20x_dbgmcu.h" +#include "ch32f20x_dma.h" +#include "ch32f20x_exti.h" +#include "ch32f20x_flash.h" +#include "ch32f20x_fsmc.h" +#include "ch32f20x_gpio.h" +#include "ch32f20x_i2c.h" +#include "ch32f20x_iwdg.h" +#include "ch32f20x_pwr.h" +#include "ch32f20x_rcc.h" +#include "ch32f20x_rtc.h" +#include "ch32f20x_sdio.h" +#include "ch32f20x_spi.h" +#include "ch32f20x_tim.h" +#include "ch32f20x_usart.h" +#include "ch32f20x_wwdg.h" +#include "ch32f20x_it.h" +#include "ch32f20x_misc.h" + +#endif /* __CH32F20x_CONF_H */ + diff --git a/hw/bsp/ch32f20x/ch32f20x_it.c b/hw/bsp/ch32f20x/ch32f20x_it.c new file mode 100644 index 0000000000..94e28e380b --- /dev/null +++ b/hw/bsp/ch32f20x/ch32f20x_it.c @@ -0,0 +1,35 @@ +#include "ch32f20x_it.h" + +#include "ch32f20x.h" + +/* -------------------------------------------------------------------------- */ + +void NMI_Handler(void) { + +} + +/* -------------------------------------------------------------------------- */ + +void MemManage_Handler(void) { + +} + +/* -------------------------------------------------------------------------- */ + +void BusFault_Handler(void) { + +} + +/* -------------------------------------------------------------------------- */ + +void UsageFault_Handler(void) { + +} + +/* -------------------------------------------------------------------------- */ + +void DebugMon_Handler(void) { + +} + +/* -------------------------------------------------------------------------- */ diff --git a/hw/bsp/ch32f20x/ch32f20x_it.h b/hw/bsp/ch32f20x/ch32f20x_it.h new file mode 100644 index 0000000000..34f3bbf966 --- /dev/null +++ b/hw/bsp/ch32f20x/ch32f20x_it.h @@ -0,0 +1,25 @@ +/********************************** (C) COPYRIGHT ******************************* +* File Name : ch32f20x_it.h +* Author : WCH +* Version : V1.0.0 +* Date : 2021/08/08 +* 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 __CH32F20xIT_H +#define __CH32F20xIT_H + +#include "ch32f20x.h" + +void NMI_Handler(void); +void HardFault_Handler(void); +void MemManage_Handler(void); +void BusFault_Handler(void); +void UsageFault_Handler(void); +void DebugMon_Handler(void); + + +#endif /* __CH32F20xIT_H */ diff --git a/hw/bsp/ch32f20x/core_cm3.h b/hw/bsp/ch32f20x/core_cm3.h new file mode 100644 index 0000000000..c35a4eec32 --- /dev/null +++ b/hw/bsp/ch32f20x/core_cm3.h @@ -0,0 +1,11 @@ +/* There is core_cm3.h wrapper just to avoid warnings from CMSIS headers */ +/* if you want use original file add to make file: + INC += \ + $(TOP)/$(CH32F20X_SDK_SRC)/CMSIS +*/ +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wstrict-prototypes" + +#include <../../CMSIS/core_cm3.h> + +#pragma GCC diagnostic pop diff --git a/hw/bsp/ch32f20x/debug_uart.c b/hw/bsp/ch32f20x/debug_uart.c new file mode 100644 index 0000000000..a595eb6f78 --- /dev/null +++ b/hw/bsp/ch32f20x/debug_uart.c @@ -0,0 +1,105 @@ +/* + * The MIT License (MIT) + * + * Copyright (c) 2023 Denis Krasutski + * + * 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 + +#include "board.h" +#include "debug_uart.h" + +#define UART_RINGBUFFER_SIZE_TX 64 +#define UART_RINGBUFFER_MASK_TX (UART_RINGBUFFER_SIZE_TX-1) + +static char tx_buf[UART_RINGBUFFER_SIZE_TX]; +static unsigned int tx_produce = 0; +static volatile unsigned int tx_consume = 0; + +void UART_DEV_IRQHandler(void) +{ + if(USART_GetITStatus(UART_DEV, USART_IT_TC) != RESET) { + USART_ClearITPendingBit(UART_DEV, USART_IT_TC); + + if(tx_consume != tx_produce) { + USART_SendData(UART_DEV, tx_buf[tx_consume]); + tx_consume = (tx_consume + 1) & UART_RINGBUFFER_MASK_TX; + } + } +} + +void uart_write(char c) +{ + unsigned int tx_produce_next = (tx_produce + 1) & UART_RINGBUFFER_MASK_TX; + + NVIC_DisableIRQ(UART_DEV_IRQn); + if((tx_consume != tx_produce) || (USART_GetFlagStatus(UART_DEV, USART_FLAG_TXE) == RESET)) { + tx_buf[tx_produce] = c; + tx_produce = tx_produce_next; + } else { + USART_SendData(UART_DEV, c); + } + NVIC_EnableIRQ(UART_DEV_IRQn); +} + +void uart_sync(void) +{ + while(tx_consume != tx_produce) { + //Waiting for transfer complete + } +} + +void usart_printf_init(uint32_t baudrate) +{ + tx_produce = 0; + tx_consume = 0; + + UART_DEV_CLK_EN(); + + GPIO_InitTypeDef gpio_config = { + .GPIO_Pin = UART_DEV_TX_PIN, + .GPIO_Speed = GPIO_Speed_50MHz, + .GPIO_Mode = GPIO_Mode_AF_PP, + }; + GPIO_Init(UART_DEV_GPIO_PORT, &gpio_config); + + USART_InitTypeDef uart_config = { + .USART_BaudRate = baudrate, + .USART_WordLength = USART_WordLength_8b, + .USART_StopBits = USART_StopBits_1, + .USART_Parity = USART_Parity_No, + .USART_HardwareFlowControl = USART_HardwareFlowControl_None, + .USART_Mode = USART_Mode_Tx, + }; + + USART_Init(UART_DEV, &uart_config); + USART_ITConfig(UART_DEV, USART_IT_TC, ENABLE); + USART_Cmd(UART_DEV, ENABLE); + + NVIC_InitTypeDef nvic_config = { + .NVIC_IRQChannel = UART_DEV_IRQn, + .NVIC_IRQChannelPreemptionPriority = 1, + .NVIC_IRQChannelSubPriority = 3, + .NVIC_IRQChannelCmd = ENABLE, + }; + NVIC_Init(&nvic_config); +} diff --git a/hw/bsp/ch32f20x/debug_uart.h b/hw/bsp/ch32f20x/debug_uart.h new file mode 100644 index 0000000000..10284cf6fb --- /dev/null +++ b/hw/bsp/ch32f20x/debug_uart.h @@ -0,0 +1,31 @@ +/* + * The MIT License (MIT) + * + * Copyright (c) 2023 Denis Krasutski + * + * 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 + +void uart_write(char c); +void uart_sync(void); +void usart_printf_init(uint32_t baudrate); diff --git a/hw/bsp/ch32f20x/family.c b/hw/bsp/ch32f20x/family.c new file mode 100644 index 0000000000..9717832d6d --- /dev/null +++ b/hw/bsp/ch32f20x/family.c @@ -0,0 +1,141 @@ +/* + * The MIT License (MIT) + * + * Copyright (c) 2023 Denis Krasutski + * + * 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 "stdio.h" +#include "debug_uart.h" + +#include "ch32f20x.h" + +#include "bsp/board_api.h" +#include "board.h" + +//--------------------------------------------------------------------+ +// Forward USB interrupt events to TinyUSB IRQ Handler +//--------------------------------------------------------------------+ + +void USBHS_IRQHandler(void) +{ + tud_int_handler(0); +} + +void board_init(void) { + + /* Disable interrupts during init */ + __disable_irq(); + +#if CFG_TUSB_OS == OPT_OS_NONE + SysTick_Config(SystemCoreClock / 1000); +#endif + +#if CFG_TUSB_OS == OPT_OS_FREERTOS + // If freeRTOS is used, IRQ priority is limit by max syscall ( smaller is higher ) + NVIC_SetPriority(USBHS_IRQn, configLIBRARY_MAX_SYSCALL_INTERRUPT_PRIORITY); +#endif + + usart_printf_init(115200); + + // USB HS Clock config + RCC_USBCLK48MConfig(RCC_USBCLK48MCLKSource_USBPHY); + RCC_USBHSPLLCLKConfig(RCC_HSBHSPLLCLKSource_HSE); + RCC_USBHSConfig(RCC_USBPLL_Div2); + RCC_USBHSPLLCKREFCLKConfig(RCC_USBHSPLLCKREFCLK_4M); + RCC_USBHSPHYPLLALIVEcmd(ENABLE); + RCC_AHBPeriphClockCmd(RCC_AHBPeriph_USBHS, ENABLE); + + // LED + LED_CLOCK_EN(); + GPIO_InitTypeDef led_pin_config = { + .GPIO_Pin = LED_PIN, + .GPIO_Mode = GPIO_Mode_Out_OD, + .GPIO_Speed = GPIO_Speed_50MHz, + }; + GPIO_Init(LED_PORT, &led_pin_config); + + // Button + BUTTON_CLOCK_EN(); + GPIO_InitTypeDef button_pin_config = { + .GPIO_Pin = BUTTON_PIN, + .GPIO_Mode = GPIO_Mode_IPU, + .GPIO_Speed = GPIO_Speed_50MHz, + }; + GPIO_Init(BUTTON_PORT, &button_pin_config); + + /* Enable interrupts globally */ + __enable_irq(); +} + +#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 #0\n"); +} + +//--------------------------------------------------------------------+ +// Board porting API +//--------------------------------------------------------------------+ + +void board_led_write(bool state) +{ + GPIO_WriteBit(LED_PORT, LED_PIN, state); +} + +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) +{ + int txsize = len; + while ( txsize-- ) + { + uart_write(*(uint8_t const*) buf); + buf++; + } + return len; +} diff --git a/hw/bsp/ch32f20x/family.mk b/hw/bsp/ch32f20x/family.mk new file mode 100644 index 0000000000..c08451b9c8 --- /dev/null +++ b/hw/bsp/ch32f20x/family.mk @@ -0,0 +1,30 @@ +# Submodules +CH32F20X_SDK = hw/mcu/wch/ch32f20x +DEPS_SUBMODULES += $(CH32F20X_SDK) + +# WCH-SDK paths +CH32F20X_SDK_SRC = $(CH32F20X_SDK)/EVT/EXAM/SRC + +include $(TOP)/$(BOARD_PATH)/board.mk + +CPU_CORE ?= cortex-m3 + +CFLAGS += \ + -DCFG_TUSB_MCU=OPT_MCU_CH32F20X \ + -DBOARD_TUD_MAX_SPEED=OPT_MODE_HIGH_SPEED + +SRC_C += \ + src/portable/wch/dcd_ch32_usbhs.c \ + $(CH32F20X_SDK_SRC)/StdPeriphDriver/src/ch32f20x_gpio.c \ + $(CH32F20X_SDK_SRC)/StdPeriphDriver/src/ch32f20x_misc.c \ + $(CH32F20X_SDK_SRC)/StdPeriphDriver/src/ch32f20x_rcc.c \ + $(CH32F20X_SDK_SRC)/StdPeriphDriver/src/ch32f20x_usart.c + +INC += \ + $(TOP)/$(BOARD_PATH) \ + $(TOP)/$(CH32F20X_SDK_SRC)/StdPeriphDriver/inc + +# For freeRTOS port source +FREERTOS_PORTABLE_SRC = $(FREERTOS_PORTABLE_PATH)/ARM_CM3 + +flash: flash-stlink diff --git a/hw/bsp/ch32f20x/startup_gcc_ch32f20x_d8c.s b/hw/bsp/ch32f20x/startup_gcc_ch32f20x_d8c.s new file mode 100644 index 0000000000..2ecac2ac11 --- /dev/null +++ b/hw/bsp/ch32f20x/startup_gcc_ch32f20x_d8c.s @@ -0,0 +1,493 @@ +/** + ****************************************************************************** + * @file startup_gcc_ch32f20x_d8c.s + * @author Denis Krasutski + * @brief CH32F205 Devices vector table + * This module performs: + * - Set the initial SP + * - Set the initial PC == Reset_Handler, + * - Set the vector table entries with the exceptions ISR address + * - Branches to main in the C library (which eventually + * calls main()). + * After Reset the Cortex-M3 processor is in Thread mode, + * priority is Privileged, and the Stack is set to Main. + ****************************************************************************** + */ + +.syntax unified +.cpu cortex-m3 +.thumb +.global g_pfnVectors +.global Default_Handler + +/* start address for the initialization values of the .data section. defined in linker script */ +.word _sidata +/* start address for the .data section. defined in linker script */ +.word _sdata +/* end address for the .data section. defined in linker script */ +.word _edata +/* start address for the .bss section. defined in linker script */ +.word _sbss +/* end address for the .bss section. defined in linker script */ +.word _ebss + +.section .text.Reset_Handler +.weak Reset_Handler +.type Reset_Handler, %function +Reset_Handler: + /* set stack pointer */ + ldr sp, =_estack + /* Call the clock system initialization function.*/ + bl SystemInit + /* Copy the data segment initializers from flash to SRAM */ + ldr r0, =_sdata + ldr r1, =_edata + ldr r2, =_sidata + movs r3, #0 + b LoopCopyDataInit +CopyDataInit: + ldr r4, [r2, r3] + str r4, [r0, r3] + adds r3, r3, #4 +LoopCopyDataInit: + adds r4, r0, r3 + cmp r4, r1 + bcc CopyDataInit + + /* Zero fill the bss segment. */ + ldr r2, =_sbss + ldr r4, =_ebss + movs r3, #0 + b LoopFillZerobss +FillZerobss: + str r3, [r2] + adds r2, r2, #4 +LoopFillZerobss: + cmp r2, r4 + bcc FillZerobss + /* Call static constructors */ + bl __libc_init_array + /* Call the application's entry point.*/ + bl main + bx lr + .size Reset_Handler, .-Reset_Handler + +.section .text.Default_Handler,"ax",%progbits +Default_Handler: +Infinite_Loop: + b Infinite_Loop + .size Default_Handler, .-Default_Handler + +/****************************************************************************** +* +* The minimal vector table for a Cortex M3. Note that the proper constructs +* must be placed on this to ensure that it ends up at physical address +* 0x0000.0000. +* +*******************************************************************************/ + .section .isr_vector,"a",%progbits + .type g_pfnVectors, %object + .size g_pfnVectors, .-g_pfnVectors + +g_pfnVectors: + .word _estack + .word Reset_Handler + .word NMI_Handler + .word HardFault_Handler + .word MemManage_Handler + .word BusFault_Handler + .word UsageFault_Handler + .word 0 + .word 0 + .word 0 + .word 0 + .word SVC_Handler + .word DebugMon_Handler + .word 0 + .word PendSV_Handler + .word SysTick_Handler + +/******************************************************************************* + External Interrupts +*******************************************************************************/ +.word WWDG_IRQHandler +.word PVD_IRQHandler +.word TAMPER_IRQHandler +.word RTC_IRQHandler +.word FLASH_IRQHandler +.word RCC_IRQHandler +.word EXTI0_IRQHandler +.word EXTI1_IRQHandler +.word EXTI2_IRQHandler +.word EXTI3_IRQHandler +.word EXTI4_IRQHandler +.word DMA1_Channel1_IRQHandler +.word DMA1_Channel2_IRQHandler +.word DMA1_Channel3_IRQHandler +.word DMA1_Channel4_IRQHandler +.word DMA1_Channel5_IRQHandler +.word DMA1_Channel6_IRQHandler +.word DMA1_Channel7_IRQHandler +.word ADC1_2_IRQHandler +.word USB_HP_CAN1_TX_IRQHandler +.word USB_LP_CAN1_RX0_IRQHandler +.word CAN1_RX1_IRQHandler +.word CAN1_SCE_IRQHandler +.word EXTI9_5_IRQHandler +.word TIM1_BRK_IRQHandler +.word TIM1_UP_IRQHandler +.word TIM1_TRG_COM_IRQHandler +.word TIM1_CC_IRQHandler +.word TIM2_IRQHandler +.word TIM3_IRQHandler +.word TIM4_IRQHandler +.word I2C1_EV_IRQHandler +.word I2C1_ER_IRQHandler +.word I2C2_EV_IRQHandler +.word I2C2_ER_IRQHandler +.word SPI1_IRQHandler +.word SPI2_IRQHandler +.word USART1_IRQHandler +.word USART2_IRQHandler +.word USART3_IRQHandler +.word EXTI15_10_IRQHandler +.word RTCAlarm_IRQHandler +.word 0 +.word TIM8_BRK_IRQHandler +.word TIM8_UP_IRQHandler +.word TIM8_TRG_COM_IRQHandler +.word TIM8_CC_IRQHandler +.word RNG_IRQHandler +.word FSMC_IRQHandler +.word SDIO_IRQHandler +.word TIM5_IRQHandler +.word SPI3_IRQHandler +.word UART4_IRQHandler +.word UART5_IRQHandler +.word TIM6_IRQHandler +.word TIM7_IRQHandler +.word DMA2_Channel1_IRQHandler +.word DMA2_Channel2_IRQHandler +.word DMA2_Channel3_IRQHandler +.word DMA2_Channel4_IRQHandler +.word DMA2_Channel5_IRQHandler +.word ETH_IRQHandler +.word ETH_WKUP_IRQHandler +.word CAN2_TX_IRQHandler +.word CAN2_RX0_IRQHandler +.word CAN2_RX1_IRQHandler +.word CAN2_SCE_IRQHandler +.word OTG_FS_IRQHandler +.word USBHSWakeup_IRQHandler +.word USBHS_IRQHandler +.word DVP_IRQHandler +.word UART6_IRQHandler +.word UART7_IRQHandler +.word UART8_IRQHandler +.word TIM9_BRK_IRQHandler +.word TIM9_UP_IRQHandler +.word TIM9_TRG_COM_IRQHandler +.word TIM9_CC_IRQHandler +.word TIM10_BRK_IRQHandler +.word TIM10_UP_IRQHandler +.word TIM10_TRG_COM_IRQHandler +.word TIM10_CC_IRQHandler +.word DMA2_Channel6_IRQHandler +.word DMA2_Channel7_IRQHandler +.word DMA2_Channel8_IRQHandler +.word DMA2_Channel9_IRQHandler +.word DMA2_Channel10_IRQHandler +.word DMA2_Channel11_IRQHandler + +/******************************************************************************* +* +* Provide weak aliases +* +*******************************************************************************/ +.weak NMI_Handler +.thumb_set NMI_Handler,Default_Handler + +.weak HardFault_Handler +.thumb_set HardFault_Handler,Default_Handler + +.weak MemManage_Handler +.thumb_set MemManage_Handler,Default_Handler + +.weak BusFault_Handler +.thumb_set BusFault_Handler,Default_Handler + +.weak UsageFault_Handler +.thumb_set UsageFault_Handler,Default_Handler + +.weak SVC_Handler +.thumb_set SVC_Handler,Default_Handler + +.weak DebugMon_Handler +.thumb_set DebugMon_Handler,Default_Handler + +.weak PendSV_Handler +.thumb_set PendSV_Handler,Default_Handler + +.weak SysTick_Handler +.thumb_set SysTick_Handler,Default_Handler + +.weak WWDG_IRQHandler +.thumb_set WWDG_IRQHandler,Default_Handler + +.weak PVD_IRQHandler +.thumb_set PVD_IRQHandler,Default_Handler + +.weak TAMPER_IRQHandler +.thumb_set TAMPER_IRQHandler,Default_Handler + +.weak RTC_IRQHandler +.thumb_set RTC_IRQHandler,Default_Handler + +.weak FLASH_IRQHandler +.thumb_set FLASH_IRQHandler,Default_Handler + +.weak RCC_IRQHandler +.thumb_set RCC_IRQHandler,Default_Handler + +.weak EXTI0_IRQHandler +.thumb_set EXTI0_IRQHandler,Default_Handler + +.weak EXTI1_IRQHandler +.thumb_set EXTI1_IRQHandler,Default_Handler + +.weak EXTI2_IRQHandler +.thumb_set EXTI2_IRQHandler,Default_Handler + +.weak EXTI3_IRQHandler +.thumb_set EXTI3_IRQHandler,Default_Handler + +.weak EXTI4_IRQHandler +.thumb_set EXTI4_IRQHandler,Default_Handler + +.weak DMA1_Channel1_IRQHandler +.thumb_set DMA1_Channel1_IRQHandler,Default_Handler + +.weak DMA1_Channel2_IRQHandler +.thumb_set DMA1_Channel2_IRQHandler,Default_Handler + +.weak DMA1_Channel3_IRQHandler +.thumb_set DMA1_Channel3_IRQHandler,Default_Handler + +.weak DMA1_Channel4_IRQHandler +.thumb_set DMA1_Channel4_IRQHandler,Default_Handler + +.weak DMA1_Channel5_IRQHandler +.thumb_set DMA1_Channel5_IRQHandler,Default_Handler + +.weak DMA1_Channel6_IRQHandler +.thumb_set DMA1_Channel6_IRQHandler,Default_Handler + +.weak DMA1_Channel7_IRQHandler +.thumb_set DMA1_Channel7_IRQHandler,Default_Handler + +.weak ADC1_2_IRQHandler +.thumb_set ADC1_2_IRQHandler,Default_Handler + +.weak USB_HP_CAN1_TX_IRQHandler +.thumb_set USB_HP_CAN1_TX_IRQHandler,Default_Handler + +.weak USB_LP_CAN1_RX0_IRQHandler +.thumb_set USB_LP_CAN1_RX0_IRQHandler,Default_Handler + +.weak CAN1_RX1_IRQHandler +.thumb_set CAN1_RX1_IRQHandler,Default_Handler + +.weak CAN1_SCE_IRQHandler +.thumb_set CAN1_SCE_IRQHandler,Default_Handler + +.weak EXTI9_5_IRQHandler +.thumb_set EXTI9_5_IRQHandler,Default_Handler + +.weak TIM1_BRK_IRQHandler +.thumb_set TIM1_BRK_IRQHandler,Default_Handler + +.weak TIM1_UP_IRQHandler +.thumb_set TIM1_UP_IRQHandler,Default_Handler + +.weak TIM1_TRG_COM_IRQHandler +.thumb_set TIM1_TRG_COM_IRQHandler,Default_Handler + +.weak TIM1_CC_IRQHandler +.thumb_set TIM1_CC_IRQHandler,Default_Handler + +.weak TIM2_IRQHandler +.thumb_set TIM2_IRQHandler,Default_Handler + +.weak TIM3_IRQHandler +.thumb_set TIM3_IRQHandler,Default_Handler + +.weak TIM4_IRQHandler +.thumb_set TIM4_IRQHandler,Default_Handler + +.weak I2C1_EV_IRQHandler +.thumb_set I2C1_EV_IRQHandler,Default_Handler + +.weak I2C1_ER_IRQHandler +.thumb_set I2C1_ER_IRQHandler,Default_Handler + +.weak I2C2_EV_IRQHandler +.thumb_set I2C2_EV_IRQHandler,Default_Handler + +.weak I2C2_ER_IRQHandler +.thumb_set I2C2_ER_IRQHandler,Default_Handler + +.weak SPI1_IRQHandler +.thumb_set SPI1_IRQHandler,Default_Handler + +.weak SPI2_IRQHandler +.thumb_set SPI2_IRQHandler,Default_Handler + +.weak USART1_IRQHandler +.thumb_set USART1_IRQHandler,Default_Handler + +.weak USART2_IRQHandler +.thumb_set USART2_IRQHandler,Default_Handler + +.weak USART3_IRQHandler +.thumb_set USART3_IRQHandler,Default_Handler + +.weak EXTI15_10_IRQHandler +.thumb_set EXTI15_10_IRQHandler,Default_Handler + +.weak RTCAlarm_IRQHandler +.thumb_set RTCAlarm_IRQHandler,Default_Handler + +.weak TIM8_BRK_IRQHandler +.thumb_set TIM8_BRK_IRQHandler,Default_Handler + +.weak TIM8_UP_IRQHandler +.thumb_set TIM8_UP_IRQHandler,Default_Handler + +.weak TIM8_TRG_COM_IRQHandler +.thumb_set TIM8_TRG_COM_IRQHandler,Default_Handler + +.weak TIM8_CC_IRQHandler +.thumb_set TIM8_CC_IRQHandler,Default_Handler + +.weak RNG_IRQHandler +.thumb_set RNG_IRQHandler,Default_Handler + +.weak FSMC_IRQHandler +.thumb_set FSMC_IRQHandler,Default_Handler + +.weak SDIO_IRQHandler +.thumb_set SDIO_IRQHandler,Default_Handler + +.weak TIM5_IRQHandler +.thumb_set TIM5_IRQHandler,Default_Handler + +.weak SPI3_IRQHandler +.thumb_set SPI3_IRQHandler,Default_Handler + +.weak UART4_IRQHandler +.thumb_set UART4_IRQHandler,Default_Handler + +.weak UART5_IRQHandler +.thumb_set UART5_IRQHandler,Default_Handler + +.weak TIM6_IRQHandler +.thumb_set TIM6_IRQHandler,Default_Handler + +.weak TIM7_IRQHandler +.thumb_set TIM7_IRQHandler,Default_Handler + +.weak DMA2_Channel1_IRQHandler +.thumb_set DMA2_Channel1_IRQHandler,Default_Handler + +.weak DMA2_Channel2_IRQHandler +.thumb_set DMA2_Channel2_IRQHandler,Default_Handler + +.weak DMA2_Channel3_IRQHandler +.thumb_set DMA2_Channel3_IRQHandler,Default_Handler + +.weak DMA2_Channel4_IRQHandler +.thumb_set DMA2_Channel4_IRQHandler,Default_Handler + +.weak DMA2_Channel5_IRQHandler +.thumb_set DMA2_Channel5_IRQHandler,Default_Handler + +.weak ETH_IRQHandler +.thumb_set ETH_IRQHandler,Default_Handler + +.weak ETH_WKUP_IRQHandler +.thumb_set ETH_WKUP_IRQHandler,Default_Handler + +.weak CAN2_TX_IRQHandler +.thumb_set CAN2_TX_IRQHandler,Default_Handler + +.weak CAN2_RX0_IRQHandler +.thumb_set CAN2_RX0_IRQHandler,Default_Handler + +.weak CAN2_RX1_IRQHandler +.thumb_set CAN2_RX1_IRQHandler,Default_Handler + +.weak CAN2_SCE_IRQHandler +.thumb_set CAN2_SCE_IRQHandler,Default_Handler + +.weak OTG_FS_IRQHandler +.thumb_set OTG_FS_IRQHandler,Default_Handler + +.weak USBHSWakeup_IRQHandler +.thumb_set USBHSWakeup_IRQHandler,Default_Handler + +.weak USBHS_IRQHandler +.thumb_set USBHS_IRQHandler,Default_Handler + +.weak DVP_IRQHandler +.thumb_set DVP_IRQHandler,Default_Handler + +.weak UART6_IRQHandler +.thumb_set UART6_IRQHandler,Default_Handler + +.weak UART7_IRQHandler +.thumb_set UART7_IRQHandler,Default_Handler + +.weak UART8_IRQHandler +.thumb_set UART8_IRQHandler,Default_Handler + +.weak TIM9_BRK_IRQHandler +.thumb_set TIM9_BRK_IRQHandler,Default_Handler + +.weak TIM9_UP_IRQHandler +.thumb_set TIM9_UP_IRQHandler,Default_Handler + +.weak TIM9_TRG_COM_IRQHandler +.thumb_set TIM9_TRG_COM_IRQHandler,Default_Handler + +.weak TIM9_CC_IRQHandler +.thumb_set TIM9_CC_IRQHandler,Default_Handler + +.weak TIM10_BRK_IRQHandler +.thumb_set TIM10_BRK_IRQHandler,Default_Handler + +.weak TIM10_UP_IRQHandler +.thumb_set TIM10_UP_IRQHandler,Default_Handler + +.weak TIM10_TRG_COM_IRQHandler +.thumb_set TIM10_TRG_COM_IRQHandler,Default_Handler + +.weak TIM10_CC_IRQHandler +.thumb_set TIM10_CC_IRQHandler,Default_Handler + +.weak DMA2_Channel6_IRQHandler +.thumb_set DMA2_Channel6_IRQHandler,Default_Handler + +.weak DMA2_Channel7_IRQHandler +.thumb_set DMA2_Channel7_IRQHandler,Default_Handler + +.weak DMA2_Channel8_IRQHandler +.thumb_set DMA2_Channel8_IRQHandler,Default_Handler + +.weak DMA2_Channel9_IRQHandler +.thumb_set DMA2_Channel9_IRQHandler,Default_Handler + +.weak DMA2_Channel10_IRQHandler +.thumb_set DMA2_Channel10_IRQHandler,Default_Handler + +.weak DMA2_Channel11_IRQHandler +.thumb_set DMA2_Channel11_IRQHandler,Default_Handler diff --git a/hw/bsp/ch32f20x/system_ch32f20x.c b/hw/bsp/ch32f20x/system_ch32f20x.c new file mode 100644 index 0000000000..0a59b92877 --- /dev/null +++ b/hw/bsp/ch32f20x/system_ch32f20x.c @@ -0,0 +1,1122 @@ +/********************************** (C) COPYRIGHT ******************************* +* File Name : system_ch32f20x.c +* Author : WCH +* Version : V1.0.0 +* Date : 2021/08/08 +* Description : CH32F20x Device Peripheral Access Layer System Source File. +* For CH32F208 HSE = 32Mhz +* For others HSE = 8Mhz +********************************************************************************* +* 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 "ch32f20x.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_96MHz_HSE 96000000 +//#define SYSCLK_FREQ_120MHz_HSE 120000000 +//#define SYSCLK_FREQ_144MHz_HSE 144000000 +//#define SYSCLK_FREQ_HSI HSI_VALUE +//#define SYSCLK_FREQ_48MHz_HSI 48000000 +//#define SYSCLK_FREQ_56MHz_HSI 56000000 +//#define SYSCLK_FREQ_72MHz_HSI 72000000 +//#define SYSCLK_FREQ_96MHz_HSI 96000000 +//#define SYSCLK_FREQ_120MHz_HSI 120000000 +//#define SYSCLK_FREQ_144MHz_HSI 144000000 + + +/* Uncomment the following line if you need to relocate your vector Table in Internal SRAM */ +/* #define VECT_TAB_SRAM */ + +/* Vector Table base offset field This value must be a multiple of 0x200 */ +#define VECT_TAB_OFFSET 0x0 + +/* 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_96MHz_HSE +uint32_t SystemCoreClock = SYSCLK_FREQ_96MHz_HSE; /* System Clock Frequency (Core Clock) */ +#elif defined SYSCLK_FREQ_120MHz_HSE +uint32_t SystemCoreClock = SYSCLK_FREQ_120MHz_HSE; /* System Clock Frequency (Core Clock) */ +#elif defined SYSCLK_FREQ_144MHz_HSE +uint32_t SystemCoreClock = SYSCLK_FREQ_144MHz_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) */ +#elif defined SYSCLK_FREQ_96MHz_HSI +uint32_t SystemCoreClock = SYSCLK_FREQ_96MHz_HSI; /* System Clock Frequency (Core Clock) */ +#elif defined SYSCLK_FREQ_120MHz_HSI +uint32_t SystemCoreClock = SYSCLK_FREQ_120MHz_HSI; /* System Clock Frequency (Core Clock) */ +#elif defined SYSCLK_FREQ_144MHz_HSI +uint32_t SystemCoreClock = SYSCLK_FREQ_144MHz_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}; + +/* 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_96MHz_HSE +static void SetSysClockTo96_HSE( void ); +#elif defined SYSCLK_FREQ_120MHz_HSE +static void SetSysClockTo120_HSE( void ); +#elif defined SYSCLK_FREQ_144MHz_HSE +static void SetSysClockTo144_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 ); +#elif defined SYSCLK_FREQ_96MHz_HSI +static void SetSysClockTo96_HSI( void ); +#elif defined SYSCLK_FREQ_120MHz_HSI +static void SetSysClockTo120_HSI( void ); +#elif defined SYSCLK_FREQ_144MHz_HSI +static void SetSysClockTo144_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; + +#ifdef CH32F20x_D8C + RCC->CFGR0 &= ( uint32_t )0xF8FF0000; +#else + RCC->CFGR0 &= ( uint32_t )0xF0FF0000; +#endif + + RCC->CTLR &= ( uint32_t )0xFEF6FFFF; + RCC->CTLR &= ( uint32_t )0xFFFBFFFF; + RCC->CFGR0 &= ( uint32_t )0xFF80FFFF; +#ifdef CH32F20x_D8C + RCC->CTLR &= ( uint32_t )0xEBFFFFFF; + RCC->INTR = 0x00FF0000; + RCC->CFGR2 = 0x00000000; +#else + RCC->INTR = 0x009F0000; +#endif + + SetSysClock(); + +#ifdef VECT_TAB_SRAM + SCB->VTOR = SRAM_BASE | VECT_TAB_OFFSET; /* Vector Table Relocation in Internal SRAM. */ +#else + SCB->VTOR = FLASH_BASE | VECT_TAB_OFFSET; /* Vector Table Relocation in Internal FLASH. */ +#endif +} + +/********************************************************************* + * @fn SystemCoreClockUpdate + * + * @brief Update SystemCoreClock variable according to Clock Register Values. + * + * @return none + */ +void SystemCoreClockUpdate( void ) +{ + uint32_t tmp = 0, pllmull = 0, pllsource = 0; + uint8_t Pll_6_5 = 0; + +#if defined (CH32F20x_D8C) + uint8_t Pll2mull = 0; + +#endif + + 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 defined (CH32F20x_D6) || defined (CH32F20x_D8) || defined (CH32F20x_D8W) + if( pllmull == 17 ) + { + pllmull = 18; + } +#else + if( pllmull == 2 ) + { + pllmull = 18; + } + if( pllmull == 15 ) + { + pllmull = 13; /* *6.5 */ + Pll_6_5 = 1; + } + if( pllmull == 16 ) + { + pllmull = 15; + } + if( pllmull == 17 ) + { + pllmull = 16; + } +#endif + + if( pllsource == 0x00 ) + { + if(EXTEN->EXTEN_CTR & EXTEN_PLL_HSI_PRE) SystemCoreClock = HSI_VALUE * pllmull; + else SystemCoreClock = (HSI_VALUE >> 1) * pllmull; + } + else + { +#if defined (CH32F20x_D8C) + if(RCC->CFGR2 & (1<<16)){ /* PLL2 */ + SystemCoreClock = HSE_VALUE/(((RCC->CFGR2 & 0xF0)>>4) + 1); /* PREDIV2 */ + + Pll2mull = (uint8_t)((RCC->CFGR2 & 0xF00)>>8); + + if(Pll2mull == 0) SystemCoreClock = (SystemCoreClock * 5)>>1; + else if(Pll2mull == 1) SystemCoreClock = (SystemCoreClock * 25)>>1; + else if(Pll2mull == 15) SystemCoreClock = SystemCoreClock * 20; + else SystemCoreClock = SystemCoreClock * (Pll2mull + 2); + + SystemCoreClock = SystemCoreClock/((RCC->CFGR2 & 0xF) + 1); /* PREDIV1 */ + } + else{/* HSE */ + SystemCoreClock = HSE_VALUE/((RCC->CFGR2 & 0xF) + 1); /* PREDIV1 */ + } + + SystemCoreClock = SystemCoreClock * pllmull; +#else + +#if defined (CH32F20x_D8W) + if((RCC->CFGR0 & (3<<22)) == (3<<22)) + { + SystemCoreClock = ((HSE_VALUE>>1)) * pllmull; + } + else +#endif + if( ( RCC->CFGR0 & RCC_PLLXTPRE ) != ( uint32_t )RESET ) + { +#ifdef CH32F20x_D8W + SystemCoreClock = ( ( HSE_VALUE >> 2 ) >> 1 ) * pllmull; +#else + SystemCoreClock = ( HSE_VALUE >> 1 ) * pllmull; +#endif + } + else + { +#ifdef CH32F20x_D8W + SystemCoreClock = ( HSE_VALUE >> 2 ) * pllmull; +#else + SystemCoreClock = HSE_VALUE * pllmull; +#endif + + } +#endif + } + + if( Pll_6_5 == 1 ) SystemCoreClock = ( SystemCoreClock / 2 ); + + 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 ) +{ +#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_96MHz_HSE + SetSysClockTo96_HSE(); +#elif defined SYSCLK_FREQ_120MHz_HSE + SetSysClockTo120_HSE(); +#elif defined SYSCLK_FREQ_144MHz_HSE + SetSysClockTo144_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(); +#elif defined SYSCLK_FREQ_96MHz_HSI + SetSysClockTo96_HSI(); +#elif defined SYSCLK_FREQ_120MHz_HSI + SetSysClockTo120_HSI(); +#elif defined SYSCLK_FREQ_144MHz_HSI + SetSysClockTo144_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 ) + { + /* 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 + * CH32F20x_D6 (HSE=8Mhz) + * CH32F20x_D8 (HSE=8Mhz) + * CH32F20x_D8W (HSE=32Mhz) + */ + 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 ) + { + /* 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; + + /* CH32F20x_D6-PLL configuration: PLLCLK = HSE * 6 = 48 MHz (HSE=8Mhz) + * CH32F20x_D8-PLL configuration: PLLCLK = HSE * 6 = 48 MHz (HSE=8Mhz) + * CH32F20x_D8W-PLL configuration: PLLCLK = HSE/4 * 6 = 48 MHz(HSE=32Mhz) + */ + RCC->CFGR0 &= ( uint32_t )( ( uint32_t )~( RCC_PLLSRC | RCC_PLLXTPRE | RCC_PLLMULL ) ); + +#if defined (CH32F20x_D6) || defined (CH32F20x_D8) || defined (CH32F20x_D8W) + RCC->CFGR0 |= ( uint32_t )( RCC_PLLSRC_HSE | RCC_PLLXTPRE_HSE | RCC_PLLMULL6 ); +#else + RCC->CFGR0 |= ( uint32_t )( RCC_PLLSRC_HSE | RCC_PLLXTPRE_HSE | RCC_PLLMULL6_EXTEN ); +#endif + + /* 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 ) + { + /* 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; + + /* CH32F20x_D6-PLL configuration: PLLCLK = HSE * 7 = 56 MHz (HSE=8Mhz) + * CH32F20x_D8-PLL configuration: PLLCLK = HSE * 7 = 56 MHz (HSE=8Mhz) + * CH32F20x_D8W-PLL configuration: PLLCLK = HSE/4 * 7 = 56 MHz(HSE=32Mhz) + */ + RCC->CFGR0 &= ( uint32_t )( ( uint32_t )~( RCC_PLLSRC | RCC_PLLXTPRE | RCC_PLLMULL ) ); + +#if defined (CH32F20x_D6) || defined (CH32F20x_D8) || defined (CH32F20x_D8W) + RCC->CFGR0 |= ( uint32_t )( RCC_PLLSRC_HSE | RCC_PLLXTPRE_HSE | RCC_PLLMULL7 ); +#else + RCC->CFGR0 |= ( uint32_t )( RCC_PLLSRC_HSE | RCC_PLLXTPRE_HSE | RCC_PLLMULL7_EXTEN ); +#endif + + /* 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 ) + { + /* 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; + + /* CH32F20x_D6-PLL configuration: PLLCLK = HSE * 9 = 72 MHz (HSE=8Mhz) + * CH32F20x_D8-PLL configuration: PLLCLK = HSE * 9 = 72 MHz (HSE=8Mhz) + * CH32F20x_D8W-PLL configuration: PLLCLK = HSE/4 * 9 = 72 MHz(HSE=32Mhz) + */ + RCC->CFGR0 &= ( uint32_t )( ( uint32_t )~( RCC_PLLSRC | RCC_PLLXTPRE | + RCC_PLLMULL ) ); + +#if defined (CH32F20x_D6) || defined (CH32F20x_D8) || defined (CH32F20x_D8W) + RCC->CFGR0 |= ( uint32_t )( RCC_PLLSRC_HSE | RCC_PLLXTPRE_HSE | RCC_PLLMULL9 ); +#else + RCC->CFGR0 |= ( uint32_t )( RCC_PLLSRC_HSE | RCC_PLLXTPRE_HSE | RCC_PLLMULL9_EXTEN ); +#endif + + /* 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_96MHz_HSE + +/********************************************************************* + * @fn SetSysClockTo96_HSE + * + * @brief Sets System clock frequency to 96MHz and configure HCLK, PCLK2 and PCLK1 prescalers. + * + * @return none + */ +static void SetSysClockTo96_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 ) + { + /* 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; + + /* CH32F20x_D6-PLL configuration: PLLCLK = HSE * 12 = 96 MHz (HSE=8Mhz) + * CH32F20x_D8-PLL configuration: PLLCLK = HSE * 12 = 96 MHz (HSE=8Mhz) + * CH32F20x_D8W-PLL configuration: PLLCLK = HSE/4 * 12 = 96 MHz(HSE=32Mhz) + */ + RCC->CFGR0 &= ( uint32_t )( ( uint32_t )~( RCC_PLLSRC | RCC_PLLXTPRE | + RCC_PLLMULL ) ); + +#if defined (CH32F20x_D6) || defined (CH32F20x_D8) || defined (CH32F20x_D8W) + RCC->CFGR0 |= ( uint32_t )( RCC_PLLSRC_HSE | RCC_PLLXTPRE_HSE | RCC_PLLMULL12 ); +#else + RCC->CFGR0 |= ( uint32_t )( RCC_PLLSRC_HSE | RCC_PLLXTPRE_HSE | RCC_PLLMULL12_EXTEN ); +#endif + + /* 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_120MHz_HSE + +/********************************************************************* + * @fn SetSysClockTo120_HSE + * + * @brief Sets System clock frequency to 120MHz and configure HCLK, PCLK2 and PCLK1 prescalers. + * + * @return none + */ +static void SetSysClockTo120_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) + { +#if defined (CH32F20x_D8W) + RCC->CFGR0 |= (uint32_t)(3<<22); + /* HCLK = SYSCLK */ + RCC->CFGR0 |= (uint32_t)RCC_HPRE_DIV2; +#else + /* HCLK = SYSCLK */ + RCC->CFGR0 |= (uint32_t)RCC_HPRE_DIV1; +#endif + + /* PCLK2 = HCLK */ + RCC->CFGR0 |= (uint32_t)RCC_PPRE2_DIV1; + /* PCLK1 = HCLK */ + RCC->CFGR0 |= (uint32_t)RCC_PPRE1_DIV2; + + /* CH32F20x_D6-PLL configuration: PLLCLK = HSE * 15 = 120 MHz (HSE=8Mhz) + * CH32F20x_D8-PLL configuration: PLLCLK = HSE * 15 = 120 MHz (HSE=8Mhz) + * CH32F20x_D8W-PLL configuration: PLLCLK = HSE/2 * 15 = 240 MHz(HSE=32Mhz) + */ + RCC->CFGR0 &= (uint32_t)((uint32_t)~(RCC_PLLSRC | RCC_PLLXTPRE | + RCC_PLLMULL)); + +#if defined (CH32F20x_D6) || defined (CH32F20x_D8) || defined (CH32F20x_D8W) + RCC->CFGR0 |= (uint32_t)(RCC_PLLSRC_HSE | RCC_PLLXTPRE_HSE | RCC_PLLMULL15); +#else + RCC->CFGR0 |= (uint32_t)(RCC_PLLSRC_HSE | RCC_PLLXTPRE_HSE | RCC_PLLMULL15_EXTEN); +#endif + + /* 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_144MHz_HSE + +/********************************************************************* + * @fn SetSysClockTo144_HSE + * + * @brief Sets System clock frequency to 144MHz and configure HCLK, PCLK2 and PCLK1 prescalers. + * + * @return none + */ +static void SetSysClockTo144_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 ) + { + /* 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; + + /* CH32F20x_D6-PLL configuration: PLLCLK = HSE * 18 = 144 MHz (HSE=8Mhz) + * CH32F20x_D8-PLL configuration: PLLCLK = HSE * 18 = 144 MHz (HSE=8Mhz) + * CH32F20x_D8W-PLL configuration: PLLCLK = HSE/4 * 18 = 144 MHz(HSE=32Mhz) + */ + RCC->CFGR0 &= ( uint32_t )( ( uint32_t )~( RCC_PLLSRC | RCC_PLLXTPRE | + RCC_PLLMULL ) ); + +#if defined (CH32F20x_D6) || defined (CH32F20x_D8) || defined (CH32F20x_D8W) + RCC->CFGR0 |= ( uint32_t )( RCC_PLLSRC_HSE | RCC_PLLXTPRE_HSE | RCC_PLLMULL18 ); +#else + RCC->CFGR0 |= ( uint32_t )( RCC_PLLSRC_HSE | RCC_PLLXTPRE_HSE | RCC_PLLMULL18_EXTEN ); +#endif + + /* 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; + + /* 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 ) ); + +#if defined (CH32F20x_D6) || defined (CH32F20x_D8) || defined (CH32F20x_D8W) + RCC->CFGR0 |= ( uint32_t )( RCC_PLLSRC_HSI_Div2 | RCC_PLLMULL6 ); +#else + RCC->CFGR0 |= ( uint32_t )( RCC_PLLSRC_HSI_Div2 | RCC_PLLMULL6_EXTEN ); +#endif + + /* 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; + + /* 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 ) ); + +#if defined (CH32F20x_D6) || defined (CH32F20x_D8) || defined (CH32F20x_D8W) + RCC->CFGR0 |= ( uint32_t )( RCC_PLLSRC_HSI_Div2 | RCC_PLLMULL7 ); +#else + RCC->CFGR0 |= ( uint32_t )( RCC_PLLSRC_HSI_Div2 | RCC_PLLMULL7_EXTEN ); +#endif + + /* 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; + + /* 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 ) ); + +#if defined (CH32F20x_D6) || defined (CH32F20x_D8) || defined (CH32F20x_D8W) + RCC->CFGR0 |= ( uint32_t )( RCC_PLLSRC_HSI_Div2 | RCC_PLLMULL9 ); +#else + RCC->CFGR0 |= ( uint32_t )( RCC_PLLSRC_HSI_Div2 | RCC_PLLMULL9_EXTEN ); +#endif + + /* 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_96MHz_HSI + +/********************************************************************* + * @fn SetSysClockTo96_HSI + * + * @brief Sets System clock frequency to 96MHz and configure HCLK, PCLK2 and PCLK1 prescalers. + * + * @return none + */ +static void SetSysClockTo96_HSI( void ) +{ + EXTEN->EXTEN_CTR |= EXTEN_PLL_HSI_PRE; + + /* 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 * 12 = 96 MHz */ + RCC->CFGR0 &= ( uint32_t )( ( uint32_t )~( RCC_PLLSRC | RCC_PLLXTPRE | RCC_PLLMULL ) ); + +#if defined (CH32F20x_D6) || defined (CH32F20x_D8) || defined (CH32F20x_D8W) + RCC->CFGR0 |= ( uint32_t )( RCC_PLLSRC_HSI_Div2 | RCC_PLLMULL12 ); +#else + RCC->CFGR0 |= ( uint32_t )( RCC_PLLSRC_HSI_Div2 | RCC_PLLMULL12_EXTEN ); +#endif + + /* 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_120MHz_HSI + +/********************************************************************* + * @fn SetSysClockTo120_HSI + * + * @brief Sets System clock frequency to 120MHz and configure HCLK, PCLK2 and PCLK1 prescalers. + * + * @return none + */ +static void SetSysClockTo120_HSI(void) +{ + EXTEN->EXTEN_CTR |= EXTEN_PLL_HSI_PRE; + + /* 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 * 15 = 120 MHz */ + RCC->CFGR0 &= (uint32_t)((uint32_t)~(RCC_PLLSRC | RCC_PLLXTPRE | + RCC_PLLMULL)); + +#if defined (CH32F20x_D6) || defined (CH32F20x_D8) || defined (CH32F20x_D8W) + RCC->CFGR0 |= ( uint32_t )( RCC_PLLSRC_HSI_Div2 | RCC_PLLMULL15 ); +#else + RCC->CFGR0 |= ( uint32_t )( RCC_PLLSRC_HSI_Div2 | RCC_PLLMULL15_EXTEN ); +#endif + + /* 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_144MHz_HSI + +/********************************************************************* + * @fn SetSysClockTo144_HSI + * + * @brief Sets System clock frequency to 144MHz and configure HCLK, PCLK2 and PCLK1 prescalers. + * + * @return none + */ +static void SetSysClockTo144_HSI( void ) +{ + EXTEN->EXTEN_CTR |= EXTEN_PLL_HSI_PRE; + + /* 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 * 18 = 144 MHz */ + RCC->CFGR0 &= ( uint32_t )( ( uint32_t )~( RCC_PLLSRC | RCC_PLLXTPRE | RCC_PLLMULL ) ); + +#if defined (CH32F20x_D6) || defined (CH32F20x_D8) || defined (CH32F20x_D8W) + RCC->CFGR0 |= ( uint32_t )( RCC_PLLSRC_HSI_Div2 | RCC_PLLMULL18 ); +#else + RCC->CFGR0 |= ( uint32_t )( RCC_PLLSRC_HSI_Div2 | RCC_PLLMULL18_EXTEN ); +#endif + + /* 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 diff --git a/hw/bsp/ch32f20x/system_ch32f20x.h b/hw/bsp/ch32f20x/system_ch32f20x.h new file mode 100644 index 0000000000..734c80a5a5 --- /dev/null +++ b/hw/bsp/ch32f20x/system_ch32f20x.h @@ -0,0 +1,28 @@ +/********************************** (C) COPYRIGHT ******************************* +* File Name : system_ch32f20x.h +* Author : WCH +* Version : V1.0.0 +* Date : 2021/08/08 +* Description : CH32F20x Device Peripheral Access Layer System Header File. +*******************************************************************************/ +#ifndef __SYSTEM_CH32F20x_H +#define __SYSTEM_CH32F20x_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 /*__CH32F20x_SYSTEM_H */ + + + diff --git a/hw/bsp/ch32v307/family.mk b/hw/bsp/ch32v307/family.mk index 4b06cf429e..45f0317ee2 100644 --- a/hw/bsp/ch32v307/family.mk +++ b/hw/bsp/ch32v307/family.mk @@ -29,7 +29,7 @@ CFLAGS += \ -DBOARD_TUD_MAX_SPEED=OPT_MODE_HIGH_SPEED SRC_C += \ - src/portable/wch/ch32v307/dcd_usbhs.c \ + src/portable/wch/dcd_ch32_usbhs.c \ $(CH32V307_SDK_SRC)/Core/core_riscv.c \ $(CH32V307_SDK_SRC)/Peripheral/src/ch32v30x_gpio.c \ $(CH32V307_SDK_SRC)/Peripheral/src/ch32v30x_misc.c \ diff --git a/src/common/tusb_mcu.h b/src/common/tusb_mcu.h index 8807ff8aa0..a72976ae92 100644 --- a/src/common/tusb_mcu.h +++ b/src/common/tusb_mcu.h @@ -383,6 +383,10 @@ #elif TU_CHECK_MCU(OPT_MCU_CH32V307) #define TUP_DCD_ENDPOINT_MAX 16 #define TUP_RHPORT_HIGHSPEED 1 + +#elif TU_CHECK_MCU(OPT_MCU_CH32F20X) + #define TUP_DCD_ENDPOINT_MAX 16 + #define TUP_RHPORT_HIGHSPEED 1 #endif diff --git a/src/portable/wch/ch32v307/ch32_usbhs_reg.h b/src/portable/wch/ch32_usbhs_reg.h similarity index 98% rename from src/portable/wch/ch32v307/ch32_usbhs_reg.h rename to src/portable/wch/ch32_usbhs_reg.h index 5a2c1fbc9a..9b956231fb 100644 --- a/src/portable/wch/ch32v307/ch32_usbhs_reg.h +++ b/src/portable/wch/ch32_usbhs_reg.h @@ -1,7 +1,11 @@ #ifndef _USB_CH32_USBHS_REG_H #define _USB_CH32_USBHS_REG_H +#if (CFG_TUSB_MCU == OPT_MCU_CH32V307) #include +#elif (CFG_TUSB_MCU == OPT_MCU_CH32F20X) +#include +#endif /******************* GLOBAL ******************/ diff --git a/src/portable/wch/ch32v307/dcd_usbhs.c b/src/portable/wch/dcd_ch32_usbhs.c similarity index 98% rename from src/portable/wch/ch32v307/dcd_usbhs.c rename to src/portable/wch/dcd_ch32_usbhs.c index 3ad011cffd..1f1c0b8764 100644 --- a/src/portable/wch/ch32v307/dcd_usbhs.c +++ b/src/portable/wch/dcd_ch32_usbhs.c @@ -26,11 +26,11 @@ #include "tusb_option.h" -#if CFG_TUD_ENABLED && (CFG_TUSB_MCU == OPT_MCU_CH32V307) +#if CFG_TUD_ENABLED && ((CFG_TUSB_MCU == OPT_MCU_CH32V307) || (CFG_TUSB_MCU == OPT_MCU_CH32F20X)) #include "device/dcd.h" #include "ch32_usbhs_reg.h" -#include "core_riscv.h" + // Max number of bi-directional endpoints including EP0 #define EP_MAX 16 @@ -73,7 +73,7 @@ void dcd_init(uint8_t rhport) { #if TUD_OPT_HIGH_SPEED USBHSD->CONTROL = USBHS_DMA_EN | USBHS_INT_BUSY_EN | USBHS_HIGH_SPEED; #else - #error OPT_MODE_FULL_SPEED not currently supported on CH32V307 + #error OPT_MODE_FULL_SPEED not currently supported on CH32 USBHSD->CONTROL = USBHS_DMA_EN | USBHS_INT_BUSY_EN | USBHS_FULL_SPEED; #endif diff --git a/src/tusb_option.h b/src/tusb_option.h index a41f5a07ea..f4b1a1dd42 100644 --- a/src/tusb_option.h +++ b/src/tusb_option.h @@ -169,6 +169,7 @@ // WCH #define OPT_MCU_CH32V307 2200 ///< WCH CH32V307 +#define OPT_MCU_CH32F20X 2210 ///< WCH CH32F20x // NXP LPC MCX diff --git a/tools/get_deps.py b/tools/get_deps.py index 1fac291a3a..af3043e4ec 100644 --- a/tools/get_deps.py +++ b/tools/get_deps.py @@ -164,6 +164,9 @@ 'hw/mcu/wch/ch32v307': ['https://github.com/openwch/ch32v307.git', '17761f5cf9dbbf2dcf665b7c04934188add20082', 'ch32v307'], + 'hw/mcu/wch/ch32f20x': ['https://github.com/openwch/ch32f20x.git', + '77c4095087e5ed2c548ec9058e655d0b8757663b', + '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' diff --git a/tools/iar_template.ipcf b/tools/iar_template.ipcf index 4919fe7b46..c3683c3d7c 100644 --- a/tools/iar_template.ipcf +++ b/tools/iar_template.ipcf @@ -164,8 +164,8 @@ $TUSB_DIR$/src/portable/valentyusb/eptri/dcd_eptri.c - - $TUSB_DIR$/src/portable/wch/ch32v307/dcd_usbhs.c + + $TUSB_DIR$/src/portable/wch/dcd_ch32_usbhs.c $TUSB_DIR$/src/typec/usbc.c From b6059fa942897d3037e6dce2a6f4082b9f2ebb57 Mon Sep 17 00:00:00 2001 From: hathach Date: Fri, 24 Nov 2023 12:04:03 +0700 Subject: [PATCH 2/2] fix pre-commit end of file --- hw/bsp/ch32f20x/ch32f20x_conf.h | 1 - hw/bsp/ch32f20x/system_ch32f20x.h | 3 --- 2 files changed, 4 deletions(-) diff --git a/hw/bsp/ch32f20x/ch32f20x_conf.h b/hw/bsp/ch32f20x/ch32f20x_conf.h index f94da5dec4..05199ff95b 100644 --- a/hw/bsp/ch32f20x/ch32f20x_conf.h +++ b/hw/bsp/ch32f20x/ch32f20x_conf.h @@ -37,4 +37,3 @@ #include "ch32f20x_misc.h" #endif /* __CH32F20x_CONF_H */ - diff --git a/hw/bsp/ch32f20x/system_ch32f20x.h b/hw/bsp/ch32f20x/system_ch32f20x.h index 734c80a5a5..cf2f5328bf 100644 --- a/hw/bsp/ch32f20x/system_ch32f20x.h +++ b/hw/bsp/ch32f20x/system_ch32f20x.h @@ -23,6 +23,3 @@ extern void SystemCoreClockUpdate(void); #endif #endif /*__CH32F20x_SYSTEM_H */ - - -