mirror of
https://github.com/hathach/tinyusb.git
synced 2025-01-17 05:32:55 +08:00
Merge pull request #959 from KarlK90/gd32vf103-support-tiny-usb
[PORT] Add GD32VF103 support and Sipeed Longan Nano Board support
This commit is contained in:
commit
2bb63406e9
1
.github/workflows/build_riscv.yml
vendored
1
.github/workflows/build_riscv.yml
vendored
@ -16,6 +16,7 @@ jobs:
|
|||||||
family:
|
family:
|
||||||
# Alphabetical order
|
# Alphabetical order
|
||||||
- 'fomu'
|
- 'fomu'
|
||||||
|
- 'gd32vf103'
|
||||||
steps:
|
steps:
|
||||||
- name: Setup Python
|
- name: Setup Python
|
||||||
uses: actions/setup-python@v2
|
uses: actions/setup-python@v2
|
||||||
|
3
.gitmodules
vendored
3
.gitmodules
vendored
@ -124,3 +124,6 @@
|
|||||||
[submodule "hw/mcu/mindmotion/mm32sdk"]
|
[submodule "hw/mcu/mindmotion/mm32sdk"]
|
||||||
path = hw/mcu/mindmotion/mm32sdk
|
path = hw/mcu/mindmotion/mm32sdk
|
||||||
url = https://github.com/zhangslice/mm32sdk.git
|
url = https://github.com/zhangslice/mm32sdk.git
|
||||||
|
[submodule "hw/mcu/gd/nuclei-sdk"]
|
||||||
|
path = hw/mcu/gd/nuclei-sdk
|
||||||
|
url = https://github.com/Nuclei-Software/nuclei-sdk.git
|
||||||
|
@ -150,11 +150,14 @@ extern uint32_t SystemCoreClock;
|
|||||||
//--------------------------------------------------------------------+
|
//--------------------------------------------------------------------+
|
||||||
// Interrupt nesting behavior configuration.
|
// Interrupt nesting behavior configuration.
|
||||||
//--------------------------------------------------------------------+
|
//--------------------------------------------------------------------+
|
||||||
/* Cortex-M specific definitions. __NVIC_PRIO_BITS is defined in core_cmx.h */
|
#if defined(__NVIC_PRIO_BITS)
|
||||||
#ifdef __NVIC_PRIO_BITS
|
// For Cortex-M specific: __NVIC_PRIO_BITS is defined in core_cmx.h
|
||||||
#define configPRIO_BITS __NVIC_PRIO_BITS
|
#define configPRIO_BITS __NVIC_PRIO_BITS
|
||||||
|
#elif defined(__ECLIC_INTCTLBITS)
|
||||||
|
// RISC-V Bumblebee core from nuclei
|
||||||
|
#define configPRIO_BITS __ECLIC_INTCTLBITS
|
||||||
#else
|
#else
|
||||||
#error "This port requires __NVIC_PRIO_BITS to be defined"
|
#error "FreeRTOS configPRIO_BITS to be defined"
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
/* The lowest interrupt priority that can be used in a call to a "set priority" function. */
|
/* The lowest interrupt priority that can be used in a call to a "set priority" function. */
|
||||||
|
@ -150,11 +150,14 @@ extern uint32_t SystemCoreClock;
|
|||||||
//--------------------------------------------------------------------+
|
//--------------------------------------------------------------------+
|
||||||
// Interrupt nesting behavior configuration.
|
// Interrupt nesting behavior configuration.
|
||||||
//--------------------------------------------------------------------+
|
//--------------------------------------------------------------------+
|
||||||
/* Cortex-M specific definitions. __NVIC_PRIO_BITS is defined in core_cmx.h */
|
#if defined(__NVIC_PRIO_BITS)
|
||||||
#ifdef __NVIC_PRIO_BITS
|
// For Cortex-M specific: __NVIC_PRIO_BITS is defined in core_cmx.h
|
||||||
#define configPRIO_BITS __NVIC_PRIO_BITS
|
#define configPRIO_BITS __NVIC_PRIO_BITS
|
||||||
|
#elif defined(__ECLIC_INTCTLBITS)
|
||||||
|
// RISC-V Bumblebee core from nuclei
|
||||||
|
#define configPRIO_BITS __ECLIC_INTCTLBITS
|
||||||
#else
|
#else
|
||||||
#error "This port requires __NVIC_PRIO_BITS to be defined"
|
#error "FreeRTOS configPRIO_BITS to be defined"
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
/* The lowest interrupt priority that can be used in a call to a "set priority" function. */
|
/* The lowest interrupt priority that can be used in a call to a "set priority" function. */
|
||||||
|
@ -130,6 +130,9 @@
|
|||||||
#elif CFG_TUSB_MCU == OPT_MCU_RX63X || CFG_TUSB_MCU == OPT_MCU_RX65X
|
#elif CFG_TUSB_MCU == OPT_MCU_RX63X || CFG_TUSB_MCU == OPT_MCU_RX65X
|
||||||
// no header needed
|
// no header needed
|
||||||
|
|
||||||
|
#elif CFG_TUSB_MCU == OPT_MCU_GD32VF103
|
||||||
|
#include "gd32vf103.h"
|
||||||
|
|
||||||
#else
|
#else
|
||||||
#error "Missing MCU header"
|
#error "Missing MCU header"
|
||||||
#endif
|
#endif
|
||||||
|
@ -5,7 +5,7 @@ CFLAGS += \
|
|||||||
-nostdlib \
|
-nostdlib \
|
||||||
-DCFG_TUSB_MCU=OPT_MCU_VALENTYUSB_EPTRI
|
-DCFG_TUSB_MCU=OPT_MCU_VALENTYUSB_EPTRI
|
||||||
|
|
||||||
# Cross Compiler for RISC-V
|
# Toolchain from https://github.com/xpack-dev-tools/riscv-none-embed-gcc-xpack
|
||||||
CROSS_COMPILE = riscv-none-embed-
|
CROSS_COMPILE = riscv-none-embed-
|
||||||
|
|
||||||
# All source paths should be relative to the top level.
|
# All source paths should be relative to the top level.
|
||||||
|
20
hw/bsp/gd32vf103/boards/sipeed_longan_nano/board.h
Normal file
20
hw/bsp/gd32vf103/boards/sipeed_longan_nano/board.h
Normal file
@ -0,0 +1,20 @@
|
|||||||
|
#ifndef _NUCLEI_SDK_HAL_H
|
||||||
|
#define _NUCLEI_SDK_HAL_H
|
||||||
|
|
||||||
|
#include "gd32vf103c_longan_nano.h"
|
||||||
|
|
||||||
|
// 4 bits for interrupt level, 0 for priority.
|
||||||
|
// level 0 = lowest priority, level 15 = highest priority.
|
||||||
|
#define __ECLIC_INTCTLBITS 4
|
||||||
|
|
||||||
|
#define __SYSTEM_CLOCK 72000000
|
||||||
|
#define HXTAL_VALUE ((uint32_t)8000000)
|
||||||
|
|
||||||
|
#define SOC_DEBUG_UART GD32_COM0
|
||||||
|
|
||||||
|
#define DBG_KEY_UNLOCK 0x4B5A6978
|
||||||
|
#define DBG_CMD_RESET 0x1
|
||||||
|
#define DBG_KEY REG32(DBG + 0x0C)
|
||||||
|
#define DBG_CMD REG32(DBG + 0x08)
|
||||||
|
|
||||||
|
#endif
|
13
hw/bsp/gd32vf103/boards/sipeed_longan_nano/board.mk
Normal file
13
hw/bsp/gd32vf103/boards/sipeed_longan_nano/board.mk
Normal file
@ -0,0 +1,13 @@
|
|||||||
|
LONGAN_NANO_SDK_BSP = $(GD32VF103_SDK_SOC)/Board/gd32vf103c_longan_nano
|
||||||
|
LINKER_SCRIPTS = $(LONGAN_NANO_SDK_BSP)/Source/GCC
|
||||||
|
|
||||||
|
# All source paths should be relative to the top level.
|
||||||
|
LD_FILE = $(LINKER_SCRIPTS)/gcc_gd32vf103xb_flashxip.ld # Longan Nano 128k ROM 32k RAM
|
||||||
|
#LD_FILE = $(LINKER_SCRIPTS)/gcc_gd32vf103x8_flashxip.ld # Longan Nano Lite 64k ROM 20k RAM
|
||||||
|
|
||||||
|
SRC_C += $(LONGAN_NANO_SDK_BSP)/Source/gd32vf103c_longan_nano.c
|
||||||
|
INC += $(TOP)/$(LONGAN_NANO_SDK_BSP)/Include
|
||||||
|
|
||||||
|
# Longan Nano 128k ROM 32k RAM
|
||||||
|
JLINK_DEVICE = gd32vf103cbt6
|
||||||
|
#JLINK_DEVICE = gd32vf103c8t6 # Longan Nano Lite 64k ROM 20k RAM
|
197
hw/bsp/gd32vf103/family.c
Normal file
197
hw/bsp/gd32vf103/family.c
Normal file
@ -0,0 +1,197 @@
|
|||||||
|
/*
|
||||||
|
* The MIT License (MIT)
|
||||||
|
*
|
||||||
|
* Copyright (c) 2019 Ha Thach (tinyusb.org)
|
||||||
|
*
|
||||||
|
* Permission is hereby granted, free of charge, to any person obtaining a copy
|
||||||
|
* of this software and associated documentation files (the "Software"), to deal
|
||||||
|
* in the Software without restriction, including without limitation the rights
|
||||||
|
* to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
|
||||||
|
* copies of the Software, and to permit persons to whom the Software is
|
||||||
|
* furnished to do so, subject to the following conditions:
|
||||||
|
*
|
||||||
|
* The above copyright notice and this permission notice shall be included in
|
||||||
|
* all copies or substantial portions of the Software.
|
||||||
|
*
|
||||||
|
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
|
||||||
|
* IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
|
||||||
|
* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
|
||||||
|
* AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
|
||||||
|
* LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
|
||||||
|
* OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
|
||||||
|
* THE SOFTWARE.
|
||||||
|
*
|
||||||
|
* This file is part of the TinyUSB stack.
|
||||||
|
*/
|
||||||
|
|
||||||
|
#include "board.h"
|
||||||
|
#include "drv_usb_hw.h"
|
||||||
|
#include "drv_usb_dev.h"
|
||||||
|
|
||||||
|
#include "../board.h"
|
||||||
|
|
||||||
|
//--------------------------------------------------------------------+
|
||||||
|
// Forward USB interrupt events to TinyUSB IRQ Handler
|
||||||
|
//--------------------------------------------------------------------+
|
||||||
|
|
||||||
|
void USBFS_IRQHandler(void) { tud_int_handler(0); }
|
||||||
|
|
||||||
|
//--------------------------------------------------------------------+
|
||||||
|
// MACRO TYPEDEF CONSTANT ENUM
|
||||||
|
//--------------------------------------------------------------------+
|
||||||
|
|
||||||
|
#define USB_NO_VBUS_PIN
|
||||||
|
|
||||||
|
// According to GD32VF103 user manual clock tree:
|
||||||
|
// Systick clock = AHB clock / 4.
|
||||||
|
#define TIMER_TICKS ((SystemCoreClock / 4) / 1000)
|
||||||
|
|
||||||
|
#define BUTTON_PORT GPIOA
|
||||||
|
#define BUTTON_PIN GPIO_PIN_0
|
||||||
|
#define BUTTON_STATE_ACTIVE 1
|
||||||
|
|
||||||
|
#define UART_DEV SOC_DEBUG_UART
|
||||||
|
|
||||||
|
#define LED_PIN LED_R
|
||||||
|
|
||||||
|
void board_init(void) {
|
||||||
|
/* Disable interrupts during init */
|
||||||
|
__disable_irq();
|
||||||
|
|
||||||
|
#if CFG_TUSB_OS == OPT_OS_NONE
|
||||||
|
SysTick_Config(TIMER_TICKS);
|
||||||
|
#endif
|
||||||
|
|
||||||
|
rcu_periph_clock_enable(RCU_GPIOA);
|
||||||
|
rcu_periph_clock_enable(RCU_GPIOB);
|
||||||
|
rcu_periph_clock_enable(RCU_GPIOC);
|
||||||
|
rcu_periph_clock_enable(RCU_GPIOD);
|
||||||
|
rcu_periph_clock_enable(RCU_AF);
|
||||||
|
|
||||||
|
#ifdef BUTTON_PIN
|
||||||
|
gpio_init(BUTTON_PORT, GPIO_MODE_IN_FLOATING, GPIO_OSPEED_50MHZ, BUTTON_PIN);
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifdef LED_PIN
|
||||||
|
gd_led_init(LED_PIN);
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#if defined(UART_DEV)
|
||||||
|
gd_com_init(UART_DEV);
|
||||||
|
#endif
|
||||||
|
|
||||||
|
/* USB D+ and D- pins don't need to be configured. */
|
||||||
|
/* Configure VBUS Pin */
|
||||||
|
#ifndef USB_NO_VBUS_PIN
|
||||||
|
gpio_init(GPIOA, GPIO_MODE_IN_FLOATING, GPIO_OSPEED_50MHZ, GPIO_PIN_9);
|
||||||
|
#endif
|
||||||
|
|
||||||
|
/* This for ID line debug */
|
||||||
|
// gpio_init(GPIOA, GPIO_MODE_AF_OD, GPIO_OSPEED_50MHZ, GPIO_PIN_10);
|
||||||
|
|
||||||
|
/* Enable USB OTG clock */
|
||||||
|
usb_rcu_config();
|
||||||
|
|
||||||
|
/* Reset USB OTG peripheral */
|
||||||
|
rcu_periph_reset_enable(RCU_USBFSRST);
|
||||||
|
rcu_periph_reset_disable(RCU_USBFSRST);
|
||||||
|
|
||||||
|
/* Configure USBFS IRQ */
|
||||||
|
ECLIC_Register_IRQ(USBFS_IRQn, ECLIC_NON_VECTOR_INTERRUPT,
|
||||||
|
ECLIC_POSTIVE_EDGE_TRIGGER, 3, 0, NULL);
|
||||||
|
|
||||||
|
/* Retrieve otg core registers */
|
||||||
|
usb_gr* otg_core_regs = (usb_gr*)(USBFS_REG_BASE + USB_REG_OFFSET_CORE);
|
||||||
|
|
||||||
|
#ifdef USB_NO_VBUS_PIN
|
||||||
|
/* Disable VBUS sense*/
|
||||||
|
otg_core_regs->GCCFG |= GCCFG_VBUSIG | GCCFG_PWRON | GCCFG_VBUSBCEN;
|
||||||
|
#else
|
||||||
|
/* Enable VBUS sense via pin PA9 */
|
||||||
|
otg_core_regs->GCCFG |= GCCFG_VBUSIG | GCCFG_PWRON | GCCFG_VBUSBCEN;
|
||||||
|
otg_core_regs->GCCFG &= ~GCCFG_VBUSIG;
|
||||||
|
#endif
|
||||||
|
|
||||||
|
/* Enable interrupts globaly */
|
||||||
|
__enable_irq();
|
||||||
|
}
|
||||||
|
|
||||||
|
void gd32vf103_reset(void) {
|
||||||
|
/* The MTIMER unit of the GD32VF103 doesn't have the MSFRST
|
||||||
|
* register to generate a software reset request.
|
||||||
|
* BUT instead two undocumented registers in the debug peripheral
|
||||||
|
* that allow issueing a software reset.
|
||||||
|
* https://github.com/esmil/gd32vf103inator/blob/master/include/gd32vf103/dbg.h
|
||||||
|
*/
|
||||||
|
DBG_KEY = DBG_KEY_UNLOCK;
|
||||||
|
DBG_CMD = DBG_CMD_RESET;
|
||||||
|
}
|
||||||
|
|
||||||
|
//--------------------------------------------------------------------+
|
||||||
|
// Board porting API
|
||||||
|
//--------------------------------------------------------------------+
|
||||||
|
|
||||||
|
void board_led_write(bool state) {
|
||||||
|
state ? gd_led_on(LED_PIN) : gd_led_off(LED_PIN);
|
||||||
|
}
|
||||||
|
|
||||||
|
uint32_t board_button_read(void) {
|
||||||
|
return BUTTON_STATE_ACTIVE == gpio_input_bit_get(BUTTON_PORT, BUTTON_PIN);
|
||||||
|
}
|
||||||
|
|
||||||
|
int board_uart_read(uint8_t* buf, int len) {
|
||||||
|
#if defined(UART_DEV)
|
||||||
|
int rxsize = len;
|
||||||
|
while (rxsize--) {
|
||||||
|
*(uint8_t*)buf = usart_read(UART_DEV);
|
||||||
|
buf++;
|
||||||
|
}
|
||||||
|
return len;
|
||||||
|
#else
|
||||||
|
(void)buf;
|
||||||
|
(void)len;
|
||||||
|
return 0;
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
|
||||||
|
int board_uart_write(void const* buf, int len) {
|
||||||
|
#if defined(UART_DEV)
|
||||||
|
int txsize = len;
|
||||||
|
while (txsize--) {
|
||||||
|
usart_write(UART_DEV, *(uint8_t*)buf);
|
||||||
|
buf++;
|
||||||
|
}
|
||||||
|
return len;
|
||||||
|
#else
|
||||||
|
(void)buf;
|
||||||
|
(void)len;
|
||||||
|
return 0;
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
|
||||||
|
#if CFG_TUSB_OS == OPT_OS_NONE
|
||||||
|
volatile uint32_t system_ticks = 0;
|
||||||
|
void eclic_mtip_handler(void) {
|
||||||
|
system_ticks++;
|
||||||
|
SysTick_Reload(TIMER_TICKS);
|
||||||
|
}
|
||||||
|
uint32_t board_millis(void) { return system_ticks; }
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifdef USE_FULL_ASSERT
|
||||||
|
/**
|
||||||
|
* @brief Reports the name of the source file and the source line number
|
||||||
|
* where the assert_param error has occurred.
|
||||||
|
* @param file: pointer to the source file name
|
||||||
|
* @param line: assert_param error line source number
|
||||||
|
* @retval None
|
||||||
|
*/
|
||||||
|
void assert_failed(char* file, uint32_t line) {
|
||||||
|
/* USER CODE BEGIN 6 */
|
||||||
|
/* User can add his own implementation to report the file name and line
|
||||||
|
number,
|
||||||
|
tex: printf("Wrong parameters value: file %s on line %d\r\n", file, line)
|
||||||
|
*/
|
||||||
|
/* USER CODE END 6 */
|
||||||
|
}
|
||||||
|
#endif /* USE_FULL_ASSERT */
|
68
hw/bsp/gd32vf103/family.mk
Normal file
68
hw/bsp/gd32vf103/family.mk
Normal file
@ -0,0 +1,68 @@
|
|||||||
|
# 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-embed-gcc-xpack
|
||||||
|
CROSS_COMPILE ?= riscv-none-embed-
|
||||||
|
|
||||||
|
# Submodules
|
||||||
|
NUCLEI_SDK = hw/mcu/gd/nuclei-sdk
|
||||||
|
DEPS_SUBMODULES += $(NUCLEI_SDK)
|
||||||
|
|
||||||
|
# Nuclei-SDK paths
|
||||||
|
GD32VF103_SDK_SOC = $(NUCLEI_SDK)/SoC/gd32vf103
|
||||||
|
GD32VF103_SDK_DRIVER = $(GD32VF103_SDK_SOC)/Common/Source/Drivers
|
||||||
|
LIBC_STUBS = $(GD32VF103_SDK_SOC)/Common/Source/Stubs
|
||||||
|
STARTUP_ASM = $(GD32VF103_SDK_SOC)/Common/Source/GCC
|
||||||
|
|
||||||
|
include $(TOP)/$(BOARD_PATH)/board.mk
|
||||||
|
|
||||||
|
SKIP_NANOLIB = 1
|
||||||
|
|
||||||
|
CFLAGS += \
|
||||||
|
-march=rv32imac \
|
||||||
|
-mabi=ilp32 \
|
||||||
|
-mcmodel=medlow \
|
||||||
|
-mstrict-align \
|
||||||
|
-nostdlib -nostartfiles \
|
||||||
|
-DCFG_TUSB_MCU=OPT_MCU_GD32VF103 \
|
||||||
|
-DDOWNLOAD_MODE=DOWNLOAD_MODE_FLASHXIP \
|
||||||
|
-DGD32VF103
|
||||||
|
|
||||||
|
# mcu driver cause following warnings
|
||||||
|
CFLAGS += -Wno-error=unused-parameter
|
||||||
|
|
||||||
|
SRC_C += \
|
||||||
|
src/portable/st/synopsys/dcd_synopsys.c \
|
||||||
|
$(GD32VF103_SDK_DRIVER)/gd32vf103_rcu.c \
|
||||||
|
$(GD32VF103_SDK_DRIVER)/gd32vf103_gpio.c \
|
||||||
|
$(GD32VF103_SDK_DRIVER)/Usb/gd32vf103_usb_hw.c \
|
||||||
|
$(GD32VF103_SDK_DRIVER)/gd32vf103_usart.c \
|
||||||
|
$(LIBC_STUBS)/sbrk.c \
|
||||||
|
$(LIBC_STUBS)/close.c \
|
||||||
|
$(LIBC_STUBS)/isatty.c \
|
||||||
|
$(LIBC_STUBS)/fstat.c \
|
||||||
|
$(LIBC_STUBS)/lseek.c \
|
||||||
|
$(LIBC_STUBS)/read.c
|
||||||
|
|
||||||
|
SRC_S += \
|
||||||
|
$(STARTUP_ASM)/startup_gd32vf103.S \
|
||||||
|
$(STARTUP_ASM)/intexc_gd32vf103.S
|
||||||
|
|
||||||
|
INC += \
|
||||||
|
$(TOP)/$(BOARD_PATH) \
|
||||||
|
$(TOP)/$(NUCLEI_SDK)/NMSIS/Core/Include \
|
||||||
|
$(TOP)/$(GD32VF103_SDK_SOC)/Common/Include \
|
||||||
|
$(TOP)/$(GD32VF103_SDK_SOC)/Common/Include/Usb
|
||||||
|
|
||||||
|
# For freeRTOS port source
|
||||||
|
FREERTOS_PORT = RISC-V
|
||||||
|
|
||||||
|
# For flash-jlink target
|
||||||
|
JLINK_IF = jtag
|
||||||
|
|
||||||
|
# flash target ROM bootloader
|
||||||
|
flash: $(BUILD)/$(PROJECT).bin
|
||||||
|
dfu-util -R -a 0 --dfuse-address 0x08000000 -D $<
|
668
hw/bsp/gd32vf103/system_gd32vf103.c
Normal file
668
hw/bsp/gd32vf103/system_gd32vf103.c
Normal file
@ -0,0 +1,668 @@
|
|||||||
|
/*!
|
||||||
|
\file system_gd32vf103.h
|
||||||
|
\brief RISC-V Device Peripheral Access Layer Source File for
|
||||||
|
GD32VF103 Device Series
|
||||||
|
|
||||||
|
*/
|
||||||
|
|
||||||
|
/*
|
||||||
|
Copyright (c) 2020, GigaDevice Semiconductor Inc.
|
||||||
|
|
||||||
|
Redistribution and use in source and binary forms, with or without modification,
|
||||||
|
are permitted provided that the following conditions are met:
|
||||||
|
|
||||||
|
1. Redistributions of source code must retain the above copyright notice, this
|
||||||
|
list of conditions and the following disclaimer.
|
||||||
|
2. Redistributions in binary form must reproduce the above copyright notice,
|
||||||
|
this list of conditions and the following disclaimer in the documentation
|
||||||
|
and/or other materials provided with the distribution.
|
||||||
|
3. Neither the name of the copyright holder nor the names of its contributors
|
||||||
|
may be used to endorse or promote products derived from this software without
|
||||||
|
specific prior written permission.
|
||||||
|
|
||||||
|
THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
|
||||||
|
AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
|
||||||
|
WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED.
|
||||||
|
IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT,
|
||||||
|
INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT
|
||||||
|
NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR
|
||||||
|
PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY,
|
||||||
|
WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
|
||||||
|
ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY
|
||||||
|
OF SUCH DAMAGE.
|
||||||
|
*/
|
||||||
|
|
||||||
|
/* This file refers the RISC-V standard, some adjustments are made according to GigaDevice chips */
|
||||||
|
#include "board.h"
|
||||||
|
|
||||||
|
/* system frequency define */
|
||||||
|
#define __IRC8M (IRC8M_VALUE) /* internal 8 MHz RC oscillator frequency */
|
||||||
|
#define __HXTAL (HXTAL_VALUE) /* high speed crystal oscillator frequency */
|
||||||
|
#define __SYS_OSC_CLK (__IRC8M) /* main oscillator frequency */
|
||||||
|
#define __SYSTEM_CLOCK_HXTAL (HXTAL_VALUE)
|
||||||
|
|
||||||
|
#if !defined(__SYSTEM_CLOCK)
|
||||||
|
#define __SYSTEM_CLOCK 72000000
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#if __SYSTEM_CLOCK == 48000000
|
||||||
|
#define __SYSTEM_CLOCK_48M_PLL_HXTAL (uint32_t)(48000000)
|
||||||
|
uint32_t SystemCoreClock = __SYSTEM_CLOCK_48M_PLL_HXTAL;
|
||||||
|
static void system_clock_48m_hxtal(void);
|
||||||
|
|
||||||
|
#elif __SYSTEM_CLOCK == 72000000
|
||||||
|
#define __SYSTEM_CLOCK_72M_PLL_HXTAL (uint32_t)(72000000)
|
||||||
|
uint32_t SystemCoreClock = __SYSTEM_CLOCK_72M_PLL_HXTAL;
|
||||||
|
static void system_clock_72m_hxtal(void);
|
||||||
|
|
||||||
|
#elif __SYSTEM_CLOCK == 96000000
|
||||||
|
#define __SYSTEM_CLOCK_96M_PLL_HXTAL (uint32_t)(96000000)
|
||||||
|
uint32_t SystemCoreClock = __SYSTEM_CLOCK_96M_PLL_HXTAL;
|
||||||
|
static void system_clock_96m_hxtal(void);
|
||||||
|
|
||||||
|
#else
|
||||||
|
#error No valid system clock configuration set!
|
||||||
|
#endif
|
||||||
|
|
||||||
|
/* configure the system clock */
|
||||||
|
static void system_clock_config(void);
|
||||||
|
|
||||||
|
/*!
|
||||||
|
\brief configure the system clock
|
||||||
|
\param[in] none
|
||||||
|
\param[out] none
|
||||||
|
\retval none
|
||||||
|
*/
|
||||||
|
static void system_clock_config(void)
|
||||||
|
{
|
||||||
|
#if defined (__SYSTEM_CLOCK_48M_PLL_HXTAL)
|
||||||
|
system_clock_48m_hxtal();
|
||||||
|
#elif defined (__SYSTEM_CLOCK_72M_PLL_HXTAL)
|
||||||
|
system_clock_72m_hxtal();
|
||||||
|
#elif defined (__SYSTEM_CLOCK_96M_PLL_HXTAL)
|
||||||
|
system_clock_96m_hxtal();
|
||||||
|
#endif /* __SYSTEM_CLOCK_HXTAL */
|
||||||
|
}
|
||||||
|
|
||||||
|
/*!
|
||||||
|
\brief setup the microcontroller system, initialize the system
|
||||||
|
\param[in] none
|
||||||
|
\param[out] none
|
||||||
|
\retval none
|
||||||
|
*/
|
||||||
|
void SystemInit(void)
|
||||||
|
{
|
||||||
|
/* reset the RCC clock configuration to the default reset state */
|
||||||
|
/* enable IRC8M */
|
||||||
|
RCU_CTL |= RCU_CTL_IRC8MEN;
|
||||||
|
|
||||||
|
/* reset SCS, AHBPSC, APB1PSC, APB2PSC, ADCPSC, CKOUT0SEL bits */
|
||||||
|
RCU_CFG0 &= ~(RCU_CFG0_SCS | RCU_CFG0_AHBPSC | RCU_CFG0_APB1PSC | RCU_CFG0_APB2PSC |
|
||||||
|
RCU_CFG0_ADCPSC | RCU_CFG0_ADCPSC_2 | RCU_CFG0_CKOUT0SEL);
|
||||||
|
|
||||||
|
/* reset HXTALEN, CKMEN, PLLEN bits */
|
||||||
|
RCU_CTL &= ~(RCU_CTL_HXTALEN | RCU_CTL_CKMEN | RCU_CTL_PLLEN);
|
||||||
|
|
||||||
|
/* Reset HXTALBPS bit */
|
||||||
|
RCU_CTL &= ~(RCU_CTL_HXTALBPS);
|
||||||
|
|
||||||
|
/* reset PLLSEL, PREDV0_LSB, PLLMF, USBFSPSC bits */
|
||||||
|
|
||||||
|
RCU_CFG0 &= ~(RCU_CFG0_PLLSEL | RCU_CFG0_PREDV0_LSB | RCU_CFG0_PLLMF |
|
||||||
|
RCU_CFG0_USBFSPSC | RCU_CFG0_PLLMF_4);
|
||||||
|
RCU_CFG1 = 0x00000000U;
|
||||||
|
|
||||||
|
/* Reset HXTALEN, CKMEN, PLLEN, PLL1EN and PLL2EN bits */
|
||||||
|
RCU_CTL &= ~(RCU_CTL_PLLEN | RCU_CTL_PLL1EN | RCU_CTL_PLL2EN | RCU_CTL_CKMEN | RCU_CTL_HXTALEN);
|
||||||
|
/* disable all interrupts */
|
||||||
|
RCU_INT = 0x00FF0000U;
|
||||||
|
|
||||||
|
/* Configure the System clock source, PLL Multiplier, AHB/APBx prescalers and Flash settings */
|
||||||
|
system_clock_config();
|
||||||
|
}
|
||||||
|
|
||||||
|
/*!
|
||||||
|
\brief update the SystemCoreClock with current core clock retrieved from cpu registers
|
||||||
|
\param[in] none
|
||||||
|
\param[out] none
|
||||||
|
\retval none
|
||||||
|
*/
|
||||||
|
void SystemCoreClockUpdate(void)
|
||||||
|
{
|
||||||
|
uint32_t scss;
|
||||||
|
uint32_t pllsel, predv0sel, pllmf, ck_src;
|
||||||
|
uint32_t predv0, predv1, pll1mf;
|
||||||
|
|
||||||
|
scss = GET_BITS(RCU_CFG0, 2, 3);
|
||||||
|
|
||||||
|
switch (scss)
|
||||||
|
{
|
||||||
|
/* IRC8M is selected as CK_SYS */
|
||||||
|
case SEL_IRC8M:
|
||||||
|
SystemCoreClock = IRC8M_VALUE;
|
||||||
|
break;
|
||||||
|
|
||||||
|
/* HXTAL is selected as CK_SYS */
|
||||||
|
case SEL_HXTAL:
|
||||||
|
SystemCoreClock = HXTAL_VALUE;
|
||||||
|
break;
|
||||||
|
|
||||||
|
/* PLL is selected as CK_SYS */
|
||||||
|
case SEL_PLL:
|
||||||
|
/* PLL clock source selection, HXTAL or IRC8M/2 */
|
||||||
|
pllsel = (RCU_CFG0 & RCU_CFG0_PLLSEL);
|
||||||
|
|
||||||
|
|
||||||
|
if(RCU_PLLSRC_IRC8M_DIV2 == pllsel){
|
||||||
|
/* PLL clock source is IRC8M/2 */
|
||||||
|
ck_src = IRC8M_VALUE / 2U;
|
||||||
|
}else{
|
||||||
|
/* PLL clock source is HXTAL */
|
||||||
|
ck_src = HXTAL_VALUE;
|
||||||
|
|
||||||
|
predv0sel = (RCU_CFG1 & RCU_CFG1_PREDV0SEL);
|
||||||
|
|
||||||
|
/* source clock use PLL1 */
|
||||||
|
if(RCU_PREDV0SRC_CKPLL1 == predv0sel){
|
||||||
|
predv1 = ((RCU_CFG1 & RCU_CFG1_PREDV1) >> 4) + 1U;
|
||||||
|
pll1mf = ((RCU_CFG1 & RCU_CFG1_PLL1MF) >> 8) + 2U;
|
||||||
|
if(17U == pll1mf){
|
||||||
|
pll1mf = 20U;
|
||||||
|
}
|
||||||
|
ck_src = (ck_src / predv1) * pll1mf;
|
||||||
|
}
|
||||||
|
predv0 = (RCU_CFG1 & RCU_CFG1_PREDV0) + 1U;
|
||||||
|
ck_src /= predv0;
|
||||||
|
}
|
||||||
|
|
||||||
|
/* PLL multiplication factor */
|
||||||
|
pllmf = GET_BITS(RCU_CFG0, 18, 21);
|
||||||
|
|
||||||
|
if((RCU_CFG0 & RCU_CFG0_PLLMF_4)){
|
||||||
|
pllmf |= 0x10U;
|
||||||
|
}
|
||||||
|
|
||||||
|
if(pllmf >= 15U){
|
||||||
|
pllmf += 1U;
|
||||||
|
}else{
|
||||||
|
pllmf += 2U;
|
||||||
|
}
|
||||||
|
|
||||||
|
SystemCoreClock = ck_src * pllmf;
|
||||||
|
|
||||||
|
if(15U == pllmf){
|
||||||
|
/* PLL source clock multiply by 6.5 */
|
||||||
|
SystemCoreClock = ck_src * 6U + ck_src / 2U;
|
||||||
|
}
|
||||||
|
|
||||||
|
break;
|
||||||
|
|
||||||
|
/* IRC8M is selected as CK_SYS */
|
||||||
|
default:
|
||||||
|
SystemCoreClock = IRC8M_VALUE;
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
#if defined (__SYSTEM_CLOCK_48M_PLL_HXTAL)
|
||||||
|
/*!
|
||||||
|
\brief configure the system clock to 48M by PLL which selects HXTAL(MD/HD/XD:8M; CL:25M) as its clock source
|
||||||
|
\param[in] none
|
||||||
|
\param[out] none
|
||||||
|
\retval none
|
||||||
|
*/
|
||||||
|
static void system_clock_48m_hxtal(void)
|
||||||
|
{
|
||||||
|
uint32_t timeout = 0U;
|
||||||
|
uint32_t stab_flag = 0U;
|
||||||
|
|
||||||
|
/* enable HXTAL */
|
||||||
|
RCU_CTL |= RCU_CTL_HXTALEN;
|
||||||
|
|
||||||
|
/* wait until HXTAL is stable or the startup time is longer than HXTAL_STARTUP_TIMEOUT */
|
||||||
|
do{
|
||||||
|
timeout++;
|
||||||
|
stab_flag = (RCU_CTL & RCU_CTL_HXTALSTB);
|
||||||
|
}while((0U == stab_flag) && (HXTAL_STARTUP_TIMEOUT != timeout));
|
||||||
|
|
||||||
|
/* if fail */
|
||||||
|
if(0U == (RCU_CTL & RCU_CTL_HXTALSTB)){
|
||||||
|
while(1){
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
/* HXTAL is stable */
|
||||||
|
/* AHB = SYSCLK */
|
||||||
|
RCU_CFG0 |= RCU_AHB_CKSYS_DIV1;
|
||||||
|
/* APB2 = AHB/1 */
|
||||||
|
RCU_CFG0 |= RCU_APB2_CKAHB_DIV1;
|
||||||
|
/* APB1 = AHB/2 */
|
||||||
|
RCU_CFG0 |= RCU_APB1_CKAHB_DIV2;
|
||||||
|
|
||||||
|
/* CK_PLL = (CK_PREDIV0) * 12 = 48 MHz */
|
||||||
|
RCU_CFG0 &= ~(RCU_CFG0_PLLMF | RCU_CFG0_PLLMF_4);
|
||||||
|
RCU_CFG0 |= (RCU_PLLSRC_HXTAL | RCU_PLL_MUL12);
|
||||||
|
|
||||||
|
if(HXTAL_VALUE==25000000){
|
||||||
|
|
||||||
|
/* CK_PREDIV0 = (CK_HXTAL)/5 *8 /10 = 4 MHz */
|
||||||
|
RCU_CFG1 &= ~(RCU_CFG1_PREDV0SEL | RCU_CFG1_PLL1MF | RCU_CFG1_PREDV1 | RCU_CFG1_PREDV0);
|
||||||
|
RCU_CFG1 |= (RCU_PREDV0SRC_CKPLL1 | RCU_PLL1_MUL8 | RCU_PREDV1_DIV5 | RCU_PREDV0_DIV10);
|
||||||
|
|
||||||
|
/* enable PLL1 */
|
||||||
|
RCU_CTL |= RCU_CTL_PLL1EN;
|
||||||
|
/* wait till PLL1 is ready */
|
||||||
|
while((RCU_CTL & RCU_CTL_PLL1STB) == 0){
|
||||||
|
}
|
||||||
|
|
||||||
|
}else if(HXTAL_VALUE==8000000){
|
||||||
|
RCU_CFG1 &= ~(RCU_CFG1_PREDV0SEL | RCU_CFG1_PREDV1 | RCU_CFG1_PLL1MF | RCU_CFG1_PREDV0);
|
||||||
|
RCU_CFG1 |= (RCU_PREDV0SRC_HXTAL | RCU_PREDV0_DIV2 );
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
/* enable PLL */
|
||||||
|
RCU_CTL |= RCU_CTL_PLLEN;
|
||||||
|
|
||||||
|
/* wait until PLL is stable */
|
||||||
|
while(0U == (RCU_CTL & RCU_CTL_PLLSTB)){
|
||||||
|
}
|
||||||
|
|
||||||
|
/* select PLL as system clock */
|
||||||
|
RCU_CFG0 &= ~RCU_CFG0_SCS;
|
||||||
|
RCU_CFG0 |= RCU_CKSYSSRC_PLL;
|
||||||
|
|
||||||
|
/* wait until PLL is selected as system clock */
|
||||||
|
while(0U == (RCU_CFG0 & RCU_SCSS_PLL)){
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
#elif defined (__SYSTEM_CLOCK_72M_PLL_HXTAL)
|
||||||
|
/*!
|
||||||
|
\brief configure the system clock to 72M by PLL which selects HXTAL(MD/HD/XD:8M; CL:25M) as its clock source
|
||||||
|
\param[in] none
|
||||||
|
\param[out] none
|
||||||
|
\retval none
|
||||||
|
*/
|
||||||
|
static void system_clock_72m_hxtal(void)
|
||||||
|
{
|
||||||
|
uint32_t timeout = 0U;
|
||||||
|
uint32_t stab_flag = 0U;
|
||||||
|
|
||||||
|
/* enable HXTAL */
|
||||||
|
RCU_CTL |= RCU_CTL_HXTALEN;
|
||||||
|
|
||||||
|
/* wait until HXTAL is stable or the startup time is longer than HXTAL_STARTUP_TIMEOUT */
|
||||||
|
do{
|
||||||
|
timeout++;
|
||||||
|
stab_flag = (RCU_CTL & RCU_CTL_HXTALSTB);
|
||||||
|
}while((0U == stab_flag) && (HXTAL_STARTUP_TIMEOUT != timeout));
|
||||||
|
|
||||||
|
/* if fail */
|
||||||
|
if(0U == (RCU_CTL & RCU_CTL_HXTALSTB)){
|
||||||
|
while(1){
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
/* HXTAL is stable */
|
||||||
|
/* AHB = SYSCLK */
|
||||||
|
RCU_CFG0 |= RCU_AHB_CKSYS_DIV1;
|
||||||
|
/* APB2 = AHB/1 */
|
||||||
|
RCU_CFG0 |= RCU_APB2_CKAHB_DIV1;
|
||||||
|
/* APB1 = AHB/2 */
|
||||||
|
RCU_CFG0 |= RCU_APB1_CKAHB_DIV2;
|
||||||
|
|
||||||
|
/* CK_PLL = (CK_PREDIV0) * 18 = 72 MHz */
|
||||||
|
RCU_CFG0 &= ~(RCU_CFG0_PLLMF | RCU_CFG0_PLLMF_4);
|
||||||
|
RCU_CFG0 |= (RCU_PLLSRC_HXTAL | RCU_PLL_MUL18);
|
||||||
|
|
||||||
|
|
||||||
|
if(HXTAL_VALUE==25000000){
|
||||||
|
|
||||||
|
/* CK_PREDIV0 = (CK_HXTAL)/5 *8 /10 = 4 MHz */
|
||||||
|
RCU_CFG1 &= ~(RCU_CFG1_PREDV0SEL | RCU_CFG1_PLL1MF | RCU_CFG1_PREDV1 | RCU_CFG1_PREDV0);
|
||||||
|
RCU_CFG1 |= (RCU_PREDV0SRC_CKPLL1 | RCU_PLL1_MUL8 | RCU_PREDV1_DIV5 | RCU_PREDV0_DIV10);
|
||||||
|
|
||||||
|
/* enable PLL1 */
|
||||||
|
RCU_CTL |= RCU_CTL_PLL1EN;
|
||||||
|
/* wait till PLL1 is ready */
|
||||||
|
while((RCU_CTL & RCU_CTL_PLL1STB) == 0){
|
||||||
|
}
|
||||||
|
|
||||||
|
}else if(HXTAL_VALUE==8000000){
|
||||||
|
RCU_CFG1 &= ~(RCU_CFG1_PREDV0SEL | RCU_CFG1_PREDV1 | RCU_CFG1_PLL1MF | RCU_CFG1_PREDV0);
|
||||||
|
RCU_CFG1 |= (RCU_PREDV0SRC_HXTAL | RCU_PREDV0_DIV2 );
|
||||||
|
}
|
||||||
|
|
||||||
|
/* enable PLL */
|
||||||
|
RCU_CTL |= RCU_CTL_PLLEN;
|
||||||
|
|
||||||
|
/* wait until PLL is stable */
|
||||||
|
while(0U == (RCU_CTL & RCU_CTL_PLLSTB)){
|
||||||
|
}
|
||||||
|
|
||||||
|
/* select PLL as system clock */
|
||||||
|
RCU_CFG0 &= ~RCU_CFG0_SCS;
|
||||||
|
RCU_CFG0 |= RCU_CKSYSSRC_PLL;
|
||||||
|
|
||||||
|
/* wait until PLL is selected as system clock */
|
||||||
|
while(0U == (RCU_CFG0 & RCU_SCSS_PLL)){
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
#elif defined (__SYSTEM_CLOCK_96M_PLL_HXTAL)
|
||||||
|
/*!
|
||||||
|
\brief configure the system clock to 96M by PLL which selects HXTAL(MD/HD/XD:8M; CL:25M) as its clock source
|
||||||
|
\param[in] none
|
||||||
|
\param[out] none
|
||||||
|
\retval none
|
||||||
|
*/
|
||||||
|
static void system_clock_96m_hxtal(void)
|
||||||
|
{
|
||||||
|
uint32_t timeout = 0U;
|
||||||
|
uint32_t stab_flag = 0U;
|
||||||
|
|
||||||
|
/* enable HXTAL */
|
||||||
|
RCU_CTL |= RCU_CTL_HXTALEN;
|
||||||
|
|
||||||
|
/* wait until HXTAL is stable or the startup time is longer than HXTAL_STARTUP_TIMEOUT */
|
||||||
|
do{
|
||||||
|
timeout++;
|
||||||
|
stab_flag = (RCU_CTL & RCU_CTL_HXTALSTB);
|
||||||
|
}while((0U == stab_flag) && (HXTAL_STARTUP_TIMEOUT != timeout));
|
||||||
|
|
||||||
|
/* if fail */
|
||||||
|
if(0U == (RCU_CTL & RCU_CTL_HXTALSTB)){
|
||||||
|
while(1){
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
/* HXTAL is stable */
|
||||||
|
/* AHB = SYSCLK */
|
||||||
|
RCU_CFG0 |= RCU_AHB_CKSYS_DIV1;
|
||||||
|
/* APB2 = AHB/1 */
|
||||||
|
RCU_CFG0 |= RCU_APB2_CKAHB_DIV1;
|
||||||
|
/* APB1 = AHB/2 */
|
||||||
|
RCU_CFG0 |= RCU_APB1_CKAHB_DIV2;
|
||||||
|
|
||||||
|
if(HXTAL_VALUE==25000000){
|
||||||
|
|
||||||
|
/* CK_PLL = (CK_PREDIV0) * 24 = 96 MHz */
|
||||||
|
RCU_CFG0 &= ~(RCU_CFG0_PLLMF | RCU_CFG0_PLLMF_4);
|
||||||
|
RCU_CFG0 |= (RCU_PLLSRC_HXTAL | RCU_PLL_MUL24);
|
||||||
|
|
||||||
|
/* CK_PREDIV0 = (CK_HXTAL)/5 *8 /10 = 4 MHz */
|
||||||
|
RCU_CFG1 &= ~(RCU_CFG1_PREDV0SEL | RCU_CFG1_PLL1MF | RCU_CFG1_PREDV1 | RCU_CFG1_PREDV0);
|
||||||
|
RCU_CFG1 |= (RCU_PREDV0SRC_CKPLL1 | RCU_PLL1_MUL8 | RCU_PREDV1_DIV5 | RCU_PREDV0_DIV10);
|
||||||
|
/* enable PLL1 */
|
||||||
|
RCU_CTL |= RCU_CTL_PLL1EN;
|
||||||
|
/* wait till PLL1 is ready */
|
||||||
|
while((RCU_CTL & RCU_CTL_PLL1STB) == 0){
|
||||||
|
}
|
||||||
|
|
||||||
|
}else if(HXTAL_VALUE==8000000){
|
||||||
|
/* CK_PLL = (CK_PREDIV0) * 24 = 96 MHz */
|
||||||
|
RCU_CFG0 &= ~(RCU_CFG0_PLLMF | RCU_CFG0_PLLMF_4);
|
||||||
|
RCU_CFG0 |= (RCU_PLLSRC_HXTAL | RCU_PLL_MUL24);
|
||||||
|
|
||||||
|
RCU_CFG1 &= ~(RCU_CFG1_PREDV0SEL | RCU_CFG1_PREDV1 | RCU_CFG1_PLL1MF | RCU_CFG1_PREDV0);
|
||||||
|
RCU_CFG1 |= (RCU_PREDV0SRC_HXTAL | RCU_PREDV0_DIV2 );
|
||||||
|
}
|
||||||
|
|
||||||
|
/* enable PLL */
|
||||||
|
RCU_CTL |= RCU_CTL_PLLEN;
|
||||||
|
|
||||||
|
/* wait until PLL is stable */
|
||||||
|
while(0U == (RCU_CTL & RCU_CTL_PLLSTB)){
|
||||||
|
}
|
||||||
|
|
||||||
|
/* select PLL as system clock */
|
||||||
|
RCU_CFG0 &= ~RCU_CFG0_SCS;
|
||||||
|
RCU_CFG0 |= RCU_CKSYSSRC_PLL;
|
||||||
|
|
||||||
|
/* wait until PLL is selected as system clock */
|
||||||
|
while(0U == (RCU_CFG0 & RCU_SCSS_PLL)){
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
#endif
|
||||||
|
|
||||||
|
/**
|
||||||
|
* \defgroup NMSIS_Core_IntExcNMI_Handling Interrupt and Exception and NMI Handling
|
||||||
|
* \brief Functions for interrupt, exception and nmi handle available in system_<device>.c.
|
||||||
|
* \details
|
||||||
|
* Nuclei provide a template for interrupt, exception and NMI handling. Silicon Vendor could adapat according
|
||||||
|
* to their requirement. Silicon vendor could implement interface for different exception code and
|
||||||
|
* replace current implementation.
|
||||||
|
*
|
||||||
|
* @{
|
||||||
|
*/
|
||||||
|
/** \brief Max exception handler number, don't include the NMI(0xFFF) one */
|
||||||
|
#define MAX_SYSTEM_EXCEPTION_NUM 12
|
||||||
|
/**
|
||||||
|
* \brief Store the exception handlers for each exception ID
|
||||||
|
* \note
|
||||||
|
* - This SystemExceptionHandlers are used to store all the handlers for all
|
||||||
|
* the exception codes Nuclei N/NX core provided.
|
||||||
|
* - Exception code 0 - 11, totally 12 exceptions are mapped to SystemExceptionHandlers[0:11]
|
||||||
|
* - Exception for NMI is also re-routed to exception handling(exception code 0xFFF) in startup code configuration, the handler itself is mapped to SystemExceptionHandlers[MAX_SYSTEM_EXCEPTION_NUM]
|
||||||
|
*/
|
||||||
|
static unsigned long SystemExceptionHandlers[MAX_SYSTEM_EXCEPTION_NUM + 1];
|
||||||
|
|
||||||
|
/**
|
||||||
|
* \brief Exception Handler Function Typedef
|
||||||
|
* \note
|
||||||
|
* This typedef is only used internal in this system_gd32vf103.c file.
|
||||||
|
* It is used to do type conversion for registered exception handler before calling it.
|
||||||
|
*/
|
||||||
|
typedef void (*EXC_HANDLER)(unsigned long mcause, unsigned long sp);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* \brief System Default Exception Handler
|
||||||
|
* \details
|
||||||
|
* This function provided a default exception and NMI handling code for all exception ids.
|
||||||
|
* By default, It will just print some information for debug, Vendor can customize it according to its requirements.
|
||||||
|
*/
|
||||||
|
static void system_default_exception_handler(unsigned long mcause, unsigned long sp)
|
||||||
|
{
|
||||||
|
/* TODO: Uncomment this if you have implement printf function */
|
||||||
|
/*printf("MCAUSE: 0x%lx\r\n", mcause);
|
||||||
|
printf("MEPC : 0x%lx\r\n", __RV_CSR_READ(CSR_MEPC));
|
||||||
|
printf("MTVAL : 0x%lx\r\n", __RV_CSR_READ(CSR_MBADADDR));*/
|
||||||
|
while (1);
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* \brief Initialize all the default core exception handlers
|
||||||
|
* \details
|
||||||
|
* The core exception handler for each exception id will be initialized to \ref system_default_exception_handler.
|
||||||
|
* \note
|
||||||
|
* Called in \ref _init function, used to initialize default exception handlers for all exception IDs
|
||||||
|
*/
|
||||||
|
static void Exception_Init(void)
|
||||||
|
{
|
||||||
|
for (int i = 0; i < MAX_SYSTEM_EXCEPTION_NUM + 1; i++) {
|
||||||
|
SystemExceptionHandlers[i] = (unsigned long)system_default_exception_handler;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* \brief Register an exception handler for exception code EXCn
|
||||||
|
* \details
|
||||||
|
* * For EXCn < \ref MAX_SYSTEM_EXCEPTION_NUM, it will be registered into SystemExceptionHandlers[EXCn-1].
|
||||||
|
* * For EXCn == NMI_EXCn, it will be registered into SystemExceptionHandlers[MAX_SYSTEM_EXCEPTION_NUM].
|
||||||
|
* \param EXCn See \ref EXCn_Type
|
||||||
|
* \param exc_handler The exception handler for this exception code EXCn
|
||||||
|
*/
|
||||||
|
void Exception_Register_EXC(uint32_t EXCn, unsigned long exc_handler)
|
||||||
|
{
|
||||||
|
if ((EXCn < MAX_SYSTEM_EXCEPTION_NUM) && (EXCn != 0)) {
|
||||||
|
SystemExceptionHandlers[EXCn] = exc_handler;
|
||||||
|
} else if (EXCn == NMI_EXCn) {
|
||||||
|
SystemExceptionHandlers[MAX_SYSTEM_EXCEPTION_NUM] = exc_handler;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* \brief Get current exception handler for exception code EXCn
|
||||||
|
* \details
|
||||||
|
* * For EXCn < \ref MAX_SYSTEM_EXCEPTION_NUM, it will return SystemExceptionHandlers[EXCn-1].
|
||||||
|
* * For EXCn == NMI_EXCn, it will return SystemExceptionHandlers[MAX_SYSTEM_EXCEPTION_NUM].
|
||||||
|
* \param EXCn See \ref EXCn_Type
|
||||||
|
* \return Current exception handler for exception code EXCn, if not found, return 0.
|
||||||
|
*/
|
||||||
|
unsigned long Exception_Get_EXC(uint32_t EXCn)
|
||||||
|
{
|
||||||
|
if ((EXCn < MAX_SYSTEM_EXCEPTION_NUM) && (EXCn != 0)) {
|
||||||
|
return SystemExceptionHandlers[EXCn];
|
||||||
|
} else if (EXCn == NMI_EXCn) {
|
||||||
|
return SystemExceptionHandlers[MAX_SYSTEM_EXCEPTION_NUM];
|
||||||
|
} else {
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* \brief Common NMI and Exception handler entry
|
||||||
|
* \details
|
||||||
|
* This function provided a command entry for NMI and exception. Silicon Vendor could modify
|
||||||
|
* this template implementation according to requirement.
|
||||||
|
* \remarks
|
||||||
|
* - RISCV provided common entry for all types of exception. This is proposed code template
|
||||||
|
* for exception entry function, Silicon Vendor could modify the implementation.
|
||||||
|
* - For the core_exception_handler template, we provided exception register function \ref Exception_Register_EXC
|
||||||
|
* which can help developer to register your exception handler for specific exception number.
|
||||||
|
*/
|
||||||
|
uint32_t core_exception_handler(unsigned long mcause, unsigned long sp)
|
||||||
|
{
|
||||||
|
uint32_t EXCn = (uint32_t)(mcause & 0X00000fff);
|
||||||
|
EXC_HANDLER exc_handler;
|
||||||
|
|
||||||
|
if ((EXCn < MAX_SYSTEM_EXCEPTION_NUM) && (EXCn > 0)) {
|
||||||
|
exc_handler = (EXC_HANDLER)SystemExceptionHandlers[EXCn];
|
||||||
|
} else if (EXCn == NMI_EXCn) {
|
||||||
|
exc_handler = (EXC_HANDLER)SystemExceptionHandlers[MAX_SYSTEM_EXCEPTION_NUM];
|
||||||
|
} else {
|
||||||
|
exc_handler = (EXC_HANDLER)system_default_exception_handler;
|
||||||
|
}
|
||||||
|
if (exc_handler != NULL) {
|
||||||
|
exc_handler(mcause, sp);
|
||||||
|
}
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
/** @} */ /* End of Doxygen Group NMSIS_Core_ExceptionAndNMI */
|
||||||
|
|
||||||
|
/**
|
||||||
|
* \brief initialize eclic config
|
||||||
|
* \details
|
||||||
|
* Eclic need initialize after boot up, Vendor could also change the initialization
|
||||||
|
* configuration.
|
||||||
|
*/
|
||||||
|
void ECLIC_Init(void)
|
||||||
|
{
|
||||||
|
/* TODO: Add your own initialization code here. This function will be called by main */
|
||||||
|
ECLIC_SetMth(0);
|
||||||
|
ECLIC_SetCfgNlbits(__ECLIC_INTCTLBITS);
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* \brief Initialize a specific IRQ and register the handler
|
||||||
|
* \details
|
||||||
|
* This function set vector mode, trigger mode and polarity, interrupt level and priority,
|
||||||
|
* assign handler for specific IRQn.
|
||||||
|
* \param [in] IRQn NMI interrupt handler address
|
||||||
|
* \param [in] shv \ref ECLIC_NON_VECTOR_INTERRUPT means non-vector mode, and \ref ECLIC_VECTOR_INTERRUPT is vector mode
|
||||||
|
* \param [in] trig_mode see \ref ECLIC_TRIGGER_Type
|
||||||
|
* \param [in] lvl interupt level
|
||||||
|
* \param [in] priority interrupt priority
|
||||||
|
* \param [in] handler interrupt handler, if NULL, handler will not be installed
|
||||||
|
* \return -1 means invalid input parameter. 0 means successful.
|
||||||
|
* \remarks
|
||||||
|
* - This function use to configure specific eclic interrupt and register its interrupt handler and enable its interrupt.
|
||||||
|
* - If the vector table is placed in read-only section(FLASHXIP mode), handler could not be installed
|
||||||
|
*/
|
||||||
|
int32_t ECLIC_Register_IRQ(IRQn_Type IRQn, uint8_t shv, ECLIC_TRIGGER_Type trig_mode, uint8_t lvl, uint8_t priority, void* handler)
|
||||||
|
{
|
||||||
|
if ((IRQn > SOC_INT_MAX) || (shv > ECLIC_VECTOR_INTERRUPT) \
|
||||||
|
|| (trig_mode > ECLIC_NEGTIVE_EDGE_TRIGGER)) {
|
||||||
|
return -1;
|
||||||
|
}
|
||||||
|
|
||||||
|
/* set interrupt vector mode */
|
||||||
|
ECLIC_SetShvIRQ(IRQn, shv);
|
||||||
|
/* set interrupt trigger mode and polarity */
|
||||||
|
ECLIC_SetTrigIRQ(IRQn, trig_mode);
|
||||||
|
/* set interrupt level */
|
||||||
|
ECLIC_SetLevelIRQ(IRQn, lvl);
|
||||||
|
/* set interrupt priority */
|
||||||
|
ECLIC_SetPriorityIRQ(IRQn, priority);
|
||||||
|
if (handler != NULL) {
|
||||||
|
/* set interrupt handler entry to vector table */
|
||||||
|
ECLIC_SetVector(IRQn, (rv_csr_t)handler);
|
||||||
|
}
|
||||||
|
/* enable interrupt */
|
||||||
|
ECLIC_EnableIRQ(IRQn);
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
/** @} */ /* End of Doxygen Group NMSIS_Core_ExceptionAndNMI */
|
||||||
|
|
||||||
|
/**
|
||||||
|
* \brief early init function before main
|
||||||
|
* \details
|
||||||
|
* This function is executed right before main function.
|
||||||
|
* For RISC-V gnu toolchain, _init function might not be called
|
||||||
|
* by __libc_init_array function, so we defined a new function
|
||||||
|
* to do initialization
|
||||||
|
*/
|
||||||
|
void _premain_init(void)
|
||||||
|
{
|
||||||
|
/* Initialize exception default handlers */
|
||||||
|
Exception_Init();
|
||||||
|
/* ECLIC initialization, mainly MTH and NLBIT */
|
||||||
|
ECLIC_Init();
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* \brief finish function after main
|
||||||
|
* \param [in] status status code return from main
|
||||||
|
* \details
|
||||||
|
* This function is executed right after main function.
|
||||||
|
* For RISC-V gnu toolchain, _fini function might not be called
|
||||||
|
* by __libc_fini_array function, so we defined a new function
|
||||||
|
* to do initialization
|
||||||
|
*/
|
||||||
|
void _postmain_fini(int status)
|
||||||
|
{
|
||||||
|
/* TODO: Add your own finishing code here, called after main */
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* \brief _init function called in __libc_init_array()
|
||||||
|
* \details
|
||||||
|
* This `__libc_init_array()` function is called during startup code,
|
||||||
|
* user need to implement this function, otherwise when link it will
|
||||||
|
* error init.c:(.text.__libc_init_array+0x26): undefined reference to `_init'
|
||||||
|
* \note
|
||||||
|
* Please use \ref _premain_init function now
|
||||||
|
*/
|
||||||
|
void _init(void)
|
||||||
|
{
|
||||||
|
/* Don't put any code here, please use _premain_init now */
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* \brief _fini function called in __libc_fini_array()
|
||||||
|
* \details
|
||||||
|
* This `__libc_fini_array()` function is called when exit main.
|
||||||
|
* user need to implement this function, otherwise when link it will
|
||||||
|
* error fini.c:(.text.__libc_fini_array+0x28): undefined reference to `_fini'
|
||||||
|
* \note
|
||||||
|
* Please use \ref _postmain_fini function now
|
||||||
|
*/
|
||||||
|
void _fini(void)
|
||||||
|
{
|
||||||
|
/* Don't put any code here, please use _postmain_fini now */
|
||||||
|
}
|
||||||
|
|
||||||
|
/** @} */ /* End of Doxygen Group NMSIS_Core_SystemAndClock */
|
1
hw/mcu/gd/nuclei-sdk
Submodule
1
hw/mcu/gd/nuclei-sdk
Submodule
@ -0,0 +1 @@
|
|||||||
|
Subproject commit 7eb7bfa9ea4fbeacfafe1d5f77d5a0e6ed3922e7
|
@ -89,7 +89,8 @@
|
|||||||
(CFG_TUSB_MCU == OPT_MCU_STM32L4 && defined(STM32L4_SYNOPSYS)) || \
|
(CFG_TUSB_MCU == OPT_MCU_STM32L4 && defined(STM32L4_SYNOPSYS)) || \
|
||||||
CFG_TUSB_MCU == OPT_MCU_RX63X || \
|
CFG_TUSB_MCU == OPT_MCU_RX63X || \
|
||||||
CFG_TUSB_MCU == OPT_MCU_RX65X || \
|
CFG_TUSB_MCU == OPT_MCU_RX65X || \
|
||||||
CFG_TUSB_MCU == OPT_MCU_RX72N
|
CFG_TUSB_MCU == OPT_MCU_RX72N || \
|
||||||
|
CFG_TUSB_MCU == OPT_MCU_GD32VF103
|
||||||
#define USE_LINEAR_BUFFER 0
|
#define USE_LINEAR_BUFFER 0
|
||||||
#else
|
#else
|
||||||
#define USE_LINEAR_BUFFER 1
|
#define USE_LINEAR_BUFFER 1
|
||||||
|
@ -147,6 +147,10 @@
|
|||||||
//#elif TU_CHECK_MCU(MM32F327X)
|
//#elif TU_CHECK_MCU(MM32F327X)
|
||||||
// #define DCD_ATTR_ENDPOINT_MAX not known yet
|
// #define DCD_ATTR_ENDPOINT_MAX not known yet
|
||||||
|
|
||||||
|
//------------- GigaDevice -------------//
|
||||||
|
#elif TU_CHECK_MCU(GD32VF103)
|
||||||
|
#define DCD_ATTR_ENDPOINT_MAX 4
|
||||||
|
|
||||||
#else
|
#else
|
||||||
#warning "DCD_ATTR_ENDPOINT_MAX is not defined for this MCU, default to 8"
|
#warning "DCD_ATTR_ENDPOINT_MAX is not defined for this MCU, default to 8"
|
||||||
#define DCD_ATTR_ENDPOINT_MAX 8
|
#define DCD_ATTR_ENDPOINT_MAX 8
|
||||||
|
@ -51,7 +51,8 @@
|
|||||||
CFG_TUSB_MCU == OPT_MCU_STM32F4 || \
|
CFG_TUSB_MCU == OPT_MCU_STM32F4 || \
|
||||||
CFG_TUSB_MCU == OPT_MCU_STM32F7 || \
|
CFG_TUSB_MCU == OPT_MCU_STM32F7 || \
|
||||||
CFG_TUSB_MCU == OPT_MCU_STM32H7 || \
|
CFG_TUSB_MCU == OPT_MCU_STM32H7 || \
|
||||||
(CFG_TUSB_MCU == OPT_MCU_STM32L4 && defined(STM32L4_SYNOPSYS)) \
|
(CFG_TUSB_MCU == OPT_MCU_STM32L4 && defined(STM32L4_SYNOPSYS) || \
|
||||||
|
CFG_TUSB_MCU == OPT_MCU_GD32VF103 ) \
|
||||||
)
|
)
|
||||||
|
|
||||||
// EP_MAX : Max number of bi-directional endpoints including EP0
|
// EP_MAX : Max number of bi-directional endpoints including EP0
|
||||||
@ -92,6 +93,30 @@
|
|||||||
#define EP_MAX_FS 6
|
#define EP_MAX_FS 6
|
||||||
#define EP_FIFO_SIZE_FS 1280
|
#define EP_FIFO_SIZE_FS 1280
|
||||||
|
|
||||||
|
#elif CFG_TUSB_MCU == OPT_MCU_GD32VF103
|
||||||
|
#include "synopsys_common.h"
|
||||||
|
|
||||||
|
// These numbers are the same for the whole GD32VF103 family.
|
||||||
|
#define OTG_FS_IRQn 86
|
||||||
|
#define EP_MAX_FS 4
|
||||||
|
#define EP_FIFO_SIZE_FS 1280
|
||||||
|
|
||||||
|
// The GD32VF103 is a RISC-V MCU, which implements the ECLIC Core-Local
|
||||||
|
// Interrupt Controller by Nuclei. It is nearly API compatible to the
|
||||||
|
// NVIC used by ARM MCUs.
|
||||||
|
#define ECLIC_INTERRUPT_ENABLE_BASE 0xD2001001UL
|
||||||
|
|
||||||
|
#define NVIC_EnableIRQ __eclic_enable_interrupt
|
||||||
|
#define NVIC_DisableIRQ __eclic_disable_interrupt
|
||||||
|
|
||||||
|
static inline void __eclic_enable_interrupt (uint32_t irq) {
|
||||||
|
*(volatile uint8_t*)(ECLIC_INTERRUPT_ENABLE_BASE + (irq * 4)) = 1;
|
||||||
|
}
|
||||||
|
|
||||||
|
static inline void __eclic_disable_interrupt (uint32_t irq){
|
||||||
|
*(volatile uint8_t*)(ECLIC_INTERRUPT_ENABLE_BASE + (irq * 4)) = 0;
|
||||||
|
}
|
||||||
|
|
||||||
#else
|
#else
|
||||||
#error "Unsupported MCUs"
|
#error "Unsupported MCUs"
|
||||||
#endif
|
#endif
|
||||||
@ -282,6 +307,8 @@ static void set_turnaround(USB_OTG_GlobalTypeDef * usb_otg, tusb_speed_t speed)
|
|||||||
// Turnaround timeout depends on the MCU clock
|
// Turnaround timeout depends on the MCU clock
|
||||||
uint32_t turnaround;
|
uint32_t turnaround;
|
||||||
|
|
||||||
|
TU_LOG_INT(2, SystemCoreClock);
|
||||||
|
|
||||||
if ( SystemCoreClock >= 32000000U )
|
if ( SystemCoreClock >= 32000000U )
|
||||||
turnaround = 0x6U;
|
turnaround = 0x6U;
|
||||||
else if ( SystemCoreClock >= 27500000U )
|
else if ( SystemCoreClock >= 27500000U )
|
||||||
@ -625,6 +652,8 @@ bool dcd_edpt_open (uint8_t rhport, tusb_desc_endpoint_t const * desc_edpt)
|
|||||||
|
|
||||||
_allocated_fifo_words_tx += fifo_size;
|
_allocated_fifo_words_tx += fifo_size;
|
||||||
|
|
||||||
|
TU_LOG(2, " Allocated %u bytes at offset %u", fifo_size*4, EP_FIFO_SIZE-_allocated_fifo_words_tx*4);
|
||||||
|
|
||||||
// DIEPTXF starts at FIFO #1.
|
// DIEPTXF starts at FIFO #1.
|
||||||
// Both TXFD and TXSA are in unit of 32-bit words.
|
// Both TXFD and TXSA are in unit of 32-bit words.
|
||||||
usb_otg->DIEPTXF[epnum - 1] = (fifo_size << USB_OTG_DIEPTXF_INEPTXFD_Pos) | (EP_FIFO_SIZE/4 - _allocated_fifo_words_tx);
|
usb_otg->DIEPTXF[epnum - 1] = (fifo_size << USB_OTG_DIEPTXF_INEPTXFD_Pos) | (EP_FIFO_SIZE/4 - _allocated_fifo_words_tx);
|
||||||
|
1465
src/portable/st/synopsys/synopsys_common.h
Normal file
1465
src/portable/st/synopsys/synopsys_common.h
Normal file
File diff suppressed because it is too large
Load Diff
@ -122,6 +122,9 @@
|
|||||||
// Mind Motion
|
// Mind Motion
|
||||||
#define OPT_MCU_MM32F327X 1500 ///< Mind Motion MM32F327
|
#define OPT_MCU_MM32F327X 1500 ///< Mind Motion MM32F327
|
||||||
|
|
||||||
|
// GigaDevice
|
||||||
|
#define OPT_MCU_GD32VF103 1600 ///< GigaDevice GD32VF103
|
||||||
|
|
||||||
//--------------------------------------------------------------------+
|
//--------------------------------------------------------------------+
|
||||||
// Supported OS
|
// Supported OS
|
||||||
//--------------------------------------------------------------------+
|
//--------------------------------------------------------------------+
|
||||||
|
Loading…
x
Reference in New Issue
Block a user