Skip to content

Commit

Permalink
Merge pull request #959 from KarlK90/gd32vf103-support-tiny-usb
Browse files Browse the repository at this point in the history
[PORT] Add GD32VF103 support and Sipeed Longan Nano Board support
  • Loading branch information
hathach authored Aug 15, 2021
2 parents 48f17ef + c4a6a5c commit 2bb6340
Show file tree
Hide file tree
Showing 19 changed files with 2,491 additions and 9 deletions.
1 change: 1 addition & 0 deletions .github/workflows/build_riscv.yml
Original file line number Diff line number Diff line change
Expand Up @@ -16,6 +16,7 @@ jobs:
family:
# Alphabetical order
- 'fomu'
- 'gd32vf103'
steps:
- name: Setup Python
uses: actions/setup-python@v2
Expand Down
3 changes: 3 additions & 0 deletions .gitmodules
Original file line number Diff line number Diff line change
Expand Up @@ -124,3 +124,6 @@
[submodule "hw/mcu/mindmotion/mm32sdk"]
path = hw/mcu/mindmotion/mm32sdk
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
Empty file.
9 changes: 6 additions & 3 deletions examples/device/cdc_msc_freertos/src/FreeRTOSConfig.h
Original file line number Diff line number Diff line change
Expand Up @@ -150,11 +150,14 @@ extern uint32_t SystemCoreClock;
//--------------------------------------------------------------------+
// Interrupt nesting behavior configuration.
//--------------------------------------------------------------------+
/* Cortex-M specific definitions. __NVIC_PRIO_BITS is defined in core_cmx.h */
#ifdef __NVIC_PRIO_BITS
#if defined(__NVIC_PRIO_BITS)
// For Cortex-M specific: __NVIC_PRIO_BITS is defined in core_cmx.h
#define configPRIO_BITS __NVIC_PRIO_BITS
#elif defined(__ECLIC_INTCTLBITS)
// RISC-V Bumblebee core from nuclei
#define configPRIO_BITS __ECLIC_INTCTLBITS
#else
#error "This port requires __NVIC_PRIO_BITS to be defined"
#error "FreeRTOS configPRIO_BITS to be defined"
#endif

/* The lowest interrupt priority that can be used in a call to a "set priority" function. */
Expand Down
Empty file.
9 changes: 6 additions & 3 deletions examples/device/hid_composite_freertos/src/FreeRTOSConfig.h
Original file line number Diff line number Diff line change
Expand Up @@ -150,11 +150,14 @@ extern uint32_t SystemCoreClock;
//--------------------------------------------------------------------+
// Interrupt nesting behavior configuration.
//--------------------------------------------------------------------+
/* Cortex-M specific definitions. __NVIC_PRIO_BITS is defined in core_cmx.h */
#ifdef __NVIC_PRIO_BITS
#if defined(__NVIC_PRIO_BITS)
// For Cortex-M specific: __NVIC_PRIO_BITS is defined in core_cmx.h
#define configPRIO_BITS __NVIC_PRIO_BITS
#elif defined(__ECLIC_INTCTLBITS)
// RISC-V Bumblebee core from nuclei
#define configPRIO_BITS __ECLIC_INTCTLBITS
#else
#error "This port requires __NVIC_PRIO_BITS to be defined"
#error "FreeRTOS configPRIO_BITS to be defined"
#endif

/* The lowest interrupt priority that can be used in a call to a "set priority" function. */
Expand Down
3 changes: 3 additions & 0 deletions hw/bsp/board_mcu.h
Original file line number Diff line number Diff line change
Expand Up @@ -130,6 +130,9 @@
#elif CFG_TUSB_MCU == OPT_MCU_RX63X || CFG_TUSB_MCU == OPT_MCU_RX65X
// no header needed

#elif CFG_TUSB_MCU == OPT_MCU_GD32VF103
#include "gd32vf103.h"

#else
#error "Missing MCU header"
#endif
Expand Down
2 changes: 1 addition & 1 deletion hw/bsp/fomu/family.mk
Original file line number Diff line number Diff line change
Expand Up @@ -5,7 +5,7 @@ CFLAGS += \
-nostdlib \
-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-

# All source paths should be relative to the top level.
Expand Down
20 changes: 20 additions & 0 deletions hw/bsp/gd32vf103/boards/sipeed_longan_nano/board.h
Original file line number Diff line number Diff line change
@@ -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 changes: 13 additions & 0 deletions hw/bsp/gd32vf103/boards/sipeed_longan_nano/board.mk
Original file line number Diff line number Diff line change
@@ -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 changes: 197 additions & 0 deletions hw/bsp/gd32vf103/family.c
Original file line number Diff line number Diff line change
@@ -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 changes: 68 additions & 0 deletions hw/bsp/gd32vf103/family.mk
Original file line number Diff line number Diff line change
@@ -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 $<
Loading

0 comments on commit 2bb6340

Please sign in to comment.