[BSP] 添加GD32E230开发板适配 (#10557)

This commit is contained in:
Huang YunKun
2025-07-31 17:27:18 +08:00
committed by GitHub
parent 9f66b35874
commit c55cbc5cf2
36 changed files with 3686 additions and 209 deletions

View File

@@ -303,6 +303,7 @@
"gd32/arm/gd32h759i-start",
"gd32/arm/gd32e503v-eval",
"gd32/arm/gd32527I-eval",
"gd32/arm/gd32e230-lckfb",
"n32/n32g43xcl-stb",
"n32/n32g45xcl-stb",
"n32/n32g45xml-stb",

3
.gitignore vendored
View File

@@ -65,3 +65,6 @@ vdso.lds
# stm32cubemx
**/CubeMX_Config/Drivers/
**/CubeMX_Config/MDK-ARM/
# mac
.DS_Store

View File

@@ -24,6 +24,8 @@ GD32 ARM 系列 BSP 目前支持情况如下表所示:
| [gd32470z-lckfb](gd32470z-lckfb) | 立创梁山派 GD32F470ZGT6 开发板 |
| **E5 系列** | |
| [gd32e503v-eval](gd32e503v-eval) | 兆易创新 官方 GD32E503V-EVAL 开发板 |
| **E23 系列** | |
| [gd32e230-lckfb](gd32e230-lckfb) | 立创·GD32E230C8T6开发板 |
可以通过阅读相应 BSP 下的 README 来快速上手,如果想要使用 BSP 更多功能可参考 docs 文件夹下提供的说明文档,如下表所示:

View File

@@ -0,0 +1,25 @@
kernel.tick:
kconfig:
- CONFIG_RT_TICK_PER_SECOND=100
kernel.console_name:
kconfig:
- CONFIG_RT_CONSOLE_DEVICE_NAME="uart0"
component.dev_drv.ipc.sys_workqueue:
kconfig:
- CONFIG_RT_USING_SYSTEM_WORKQUEUE=y
hw_drv_onchip.uart0:
kconfig:
- CONFIG_BSP_USING_UART0=y
hw_drv_onchip.adc0:
kconfig:
- CONFIG_BSP_USING_ADC=y
- CONFIG_BSP_USING_ADC0=y
hw_drv_onchip.spi0:
kconfig:
- CONFIG_BSP_USING_SPI=y
- CONFIG_BSP_USING_SPI0=y
hw_drv_onchip.i2c0:
kconfig:
- CONFIG_BSP_USING_I2C0=y
- CONFIG_BSP_I2C0_SCL_PIN=22
- CONFIG_BSP_I2C0_SDA_PIN=23

File diff suppressed because it is too large Load Diff

View File

@@ -0,0 +1,12 @@
mainmenu "RT-Thread Configuration"
BSP_DIR := .
RTT_DIR := ../../../..
PKGS_DIR := packages
source "$(RTT_DIR)/Kconfig"
osource "$PKGS_DIR/Kconfig"
rsource "../libraries/Kconfig"
rsource "board/Kconfig"

View File

@@ -0,0 +1,105 @@
# GD32E230立创开发板说明
## 简介
本文档是为 GD32E230立创开发板提供的板级支持包 (BSP) 说明。
该核心板以 GD32E230C8T6 作为主控制器,可通过板载的 USB 接口或 5V 引脚供电。核心板引出了所有 I/O 口,方便连接各种外设模块。
该开发板常用 **板载资源** 如下:
- **主控芯片**GD32E230C8T6
- **内核**ARM® Cortex®-M23
- **主频**72MHz
- **FLASH**64KB
- **RAM**8KB
- **常用外设**
- **LED**1 个,用户 LED (PC13)
- **按键**1 个,复位按键
- **定时器**
- 1 x 高级定时器 (TIMER0)
- 5 x 通用定时器 (TIMER2, TIMER14, TIMER15, TIMER16)
- 1 x 基本定时器 (TIMER5)
- **通信接口**
- 2 x USART (USART0, USART1)
- 2 x SPI (SPI0, SPI1)
- 2 x I2C (I2C0, I2C1)
- **ADC**1 x 12位 ADC (最多10个外部通道)
- **常用接口** USB 接口
- **调试接口**SWD (SWDIO / SWCLK)
## 外设支持
本 BSP 目前对外设的支持情况如下:
| **片上外设** | **支持情况** | **备注** |
| :--- | :---: | :--- |
| GPIO | 支持 | PAx, PBx... |
| UART | 支持 | USART0, USART1 |
| **扩展模块** | **支持情况** | **备注** |
| 暂无 | 暂不支持 | 暂不支持 |
## 使用说明
使用说明分为如下两个章节:
- **快速上手**
本章节是为刚接触 RT-Thread 的新手准备的使用说明,遵循简单的步骤即可将 RT-Thread 操作系统运行在该开发板上,看到实验效果。
- **进阶使用**
本章节是为需要在 RT-Thread 操作系统上使用更多开发板资源的开发者准备的。通过使用 ENV 工具对 BSP 进行配置,可以开启更多板载资源,实现更多高级功能。
### 快速上手
本 BSP 支持 GCC 开发环境下面介绍如何在GCC环境下编译下载。
#### 硬件连接
使用DAP-Link连接开发板与 PC。
#### 编译下载
``` shell
scons -j12
```
``` shell
pyocd flash -t gd32e230c8t6 rtthread.bin
```
开发板板载USB转串口没有调试器也可以直接连接USB进行下载。
#### 运行结果
下载程序成功之后,系统会自动运行,板载的蓝色 LED (PC13) 将会闪烁。
连接开发板对应的串口到 PC在终端工具里打开相应的串口波特率115200数据位8停止位1无校验复位设备后可以看到 RT-Thread 的输出信息:
``` shell
\ | /
- RT - Thread Operating System
/ | \ 4.1.0 build Jul 23 2025
2006 - 2024 Copyright by rt-thread team
hello rt-thread
```
### 进阶使用
此 BSP 默认只开启了 GPIO 和 USART0 的功能,如果需使用更多外设功能,需要利用 ENV 工具对 BSP 进行配置,步骤如下:
1. 在 bsp 目录下打开 env 工具。
2. 输入 `menuconfig` 命令配置工程,配置好之后保存退出。
3. 输入 `pkgs --update` 命令更新软件包。
4. 输入 `scons -j12` 编译。
## 注意事项
1. GD32E230资源受限虽然通过调整参数极限运行msh但是意义不大建议关闭。
2. **GPIOA-13****GPIOA-14** 默认用于 SWD 调试下载功能,建议不要配置为其它功能,否则将可能导致无法正常下载和调试。
## 联系人信息
维护人:
- [htynkn](https://github.com/htynkn), 邮箱:<htynkn@gmail.com>

View File

@@ -0,0 +1,15 @@
# for module compiling
import os
Import('RTT_ROOT')
from building import *
cwd = GetCurrentDir()
objs = []
list = os.listdir(cwd)
for d in list:
path = os.path.join(cwd, d)
if os.path.isfile(os.path.join(path, 'SConscript')):
objs = objs + SConscript(os.path.join(d, 'SConscript'))
Return('objs')

View File

@@ -0,0 +1,74 @@
import os
import sys
import rtconfig
if os.getenv('RTT_ROOT'):
RTT_ROOT = os.getenv('RTT_ROOT')
else:
RTT_ROOT = os.path.normpath(os.getcwd() + '/../../../..')
sys.path = sys.path + [os.path.join(RTT_ROOT, 'tools')]
try:
from building import *
except:
print('Cannot found RT-Thread root directory, please check RTT_ROOT')
print(RTT_ROOT)
exit(-1)
def bsp_pkg_check():
import subprocess
check_paths = [
os.path.join("packages", "gd32-arm-cmsis-latest"),
os.path.join("packages", "gd32-arm-series-latest")
]
need_update = not all(os.path.exists(p) for p in check_paths)
if need_update:
print("\n===============================================================================")
print("Dependency packages missing, please running 'pkgs --update'...")
print("If no packages are fetched, run 'pkgs --upgrade' first, then 'pkgs --update'...")
print("===============================================================================")
exit(1)
RegisterPreBuildingAction(bsp_pkg_check)
TARGET = 'rtthread.' + rtconfig.TARGET_EXT
DefaultEnvironment(tools=[])
env = Environment(tools = ['mingw'],
AS = rtconfig.AS, ASFLAGS = rtconfig.AFLAGS,
CC = rtconfig.CC, CFLAGS = rtconfig.CFLAGS,
AR = rtconfig.AR, ARFLAGS = '-rc',
CXX = rtconfig.CXX, CXXFLAGS = rtconfig.CXXFLAGS,
LINK = rtconfig.LINK, LINKFLAGS = rtconfig.LFLAGS)
env.PrependENVPath('PATH', rtconfig.EXEC_PATH)
if rtconfig.PLATFORM in ['iccarm']:
env.Replace(CCCOM = ['$CC $CCFLAGS $CPPFLAGS $_CPPDEFFLAGS $_CPPINCFLAGS -o $TARGET $SOURCES'])
env.Replace(ARFLAGS = [''])
env.Replace(LINKCOM = env["LINKCOM"] + ' --map rtthread.map')
Export('env')
Export('RTT_ROOT')
Export('rtconfig')
SDK_ROOT = os.path.abspath('./')
if os.path.exists(SDK_ROOT + '/libraries'):
libraries_path_prefix = SDK_ROOT + '/libraries'
else:
libraries_path_prefix = os.path.dirname(SDK_ROOT) + '/libraries'
SDK_LIB = libraries_path_prefix
Export('SDK_LIB')
# prepare building environment
objs = PrepareBuilding(env, RTT_ROOT, has_libcpu=False)
# include drivers
objs.extend(SConscript(os.path.join(libraries_path_prefix, 'gd32_drivers', 'SConscript')))
# make a building
DoBuilding(TARGET, objs)

View File

@@ -0,0 +1,15 @@
from building import *
import os
cwd = GetCurrentDir()
src = Glob('*.c')
CPPPATH = [cwd]
group = DefineGroup('Applications', src, depend = [''], CPPPATH = CPPPATH)
list = os.listdir(cwd)
for item in list:
if os.path.isfile(os.path.join(cwd, item, 'SConscript')):
group = group + SConscript(os.path.join(item, 'SConscript'))
Return('group')

View File

@@ -0,0 +1,100 @@
/*
* Copyright (c) 2006-2025, RT-Thread Development Team
*
* SPDX-License-Identifier: Apache-2.0
*
* Change Logs:
* Date Author Notes
* 2025-07-28 Yunkun Huang Init Project
*/
#include <rtthread.h>
#include <rtdevice.h>
#include <board.h>
#define LED_PIN BSP_LED_PIN
static void led_blink_thread_entry(void *parameter)
{
rt_pin_mode(LED_PIN, PIN_MODE_OUTPUT);
rt_kprintf("LED blink thread started.\n");
while (1)
{
rt_pin_write(LED_PIN, PIN_HIGH);
rt_thread_mdelay(500);
rt_pin_write(LED_PIN, PIN_LOW);
rt_thread_mdelay(500);
}
}
#define UART_DEVICE_NAME "uart0"
static void uart_send_thread_entry(void *parameter)
{
rt_device_t console_dev;
char msg[] = "hello rt-thread\r\n";
console_dev = rt_console_get_device();
if (!console_dev)
{
rt_kprintf("Failed to get console device.\n");
return;
}
rt_kprintf("UART send thread started. Will send message every 2 seconds.\n");
while (1)
{
rt_device_write(console_dev, 0, msg, (sizeof(msg) - 1));
rt_thread_mdelay(2000);
}
}
int main(void)
{
rt_thread_t led_tid = RT_NULL;
rt_thread_t uart_tid = RT_NULL;
led_tid = rt_thread_create("led_blink",
led_blink_thread_entry,
RT_NULL,
256,
20,
10);
if (led_tid != RT_NULL)
{
rt_thread_startup(led_tid);
}
else
{
rt_kprintf("Failed to create led_blink thread.\n");
}
uart_tid = rt_thread_create("uart_send",
uart_send_thread_entry,
RT_NULL,
512,
21,
10);
if (uart_tid != RT_NULL)
{
rt_kprintf("uart_send thread created successfully. Starting it up...\n");
rt_thread_startup(uart_tid);
}
else
{
rt_kprintf("!!! FAILED to create uart_send thread. Not enough memory?\n");
}
return 0;
}

View File

@@ -0,0 +1,246 @@
# SPDX-License-Identifier: Apache-2.0
menu "Hardware Drivers Config"
config SOC_SERIES_GD32E23x
bool
default y
config SOC_GD32E230C8T6
bool
select SOC_SERIES_GD32E23x
select RT_USING_COMPONENTS_INIT
select RT_USING_USER_MAIN
default y
menu "Onboard Peripheral Drivers"
menuconfig BSP_USING_LED
bool "Enable Onboard LED"
default y
if BSP_USING_LED
config BSP_LED_PIN
int "The pin number of the onboard LED"
default 45 # GET_PIN(C, 13)
endif
endmenu
menu "On-chip Peripheral Drivers"
config BSP_USING_GPIO
bool "Enable GPIO"
select RT_USING_PIN
default y
menuconfig BSP_USING_UART
bool "Enable UART"
select RT_USING_SERIAL
default y
if BSP_USING_UART
config BSP_USING_UART0
bool "Enable UART0 for Console"
default y
config BSP_UART0_RX_USING_DMA
bool "Enable UART0 RX DMA"
depends on BSP_USING_UART0
select RT_SERIAL_USING_DMA
default n
config BSP_UART0_TX_USING_DMA
bool "Enable UART0 TX DMA"
depends on BSP_USING_UART0
select RT_SERIAL_USING_DMA
default n
config BSP_UART0_RX_BUFSIZE
int "Set UART0 RX buffer size"
range 64 65535
depends on BSP_USING_UART0 && RT_USING_SERIAL_V2
default 64
config BSP_UART0_TX_BUFSIZE
int "Set UART0 TX buffer size"
range 0 65535
depends on BSP_USING_UART0 && RT_USING_SERIAL_V2
default 64
config BSP_UART0_DMA_PING_BUFSIZE
int "Set UART0 RX DMA ping-pong buffer size"
range 32 65535
depends on RT_USING_SERIAL_V2 && BSP_UART0_RX_USING_DMA
default 32
config BSP_USING_UART1
bool "Enable UART1"
default n
config BSP_UART1_RX_USING_DMA
bool "Enable UART1 RX DMA"
depends on BSP_USING_UART1
select RT_SERIAL_USING_DMA
default n
config BSP_UART1_TX_USING_DMA
bool "Enable UART1 TX DMA"
depends on BSP_USING_UART1
select RT_SERIAL_USING_DMA
default n
config BSP_UART1_RX_BUFSIZE
int "Set UART1 RX buffer size"
range 64 65535
depends on BSP_USING_UART1 && RT_USING_SERIAL_V2
default 64
config BSP_UART1_TX_BUFSIZE
int "Set UART1 TX buffer size"
range 0 65535
depends on BSP_USING_UART1 && RT_USING_SERIAL_V2
default 0
config BSP_UART1_DMA_PING_BUFSIZE
int "Set UART1 RX DMA ping-pong buffer size"
range 32 65535
depends on RT_USING_SERIAL_V2 && BSP_UART1_RX_USING_DMA
default 32
endif
menuconfig BSP_USING_SPI
bool "Enable SPI"
select RT_USING_SPI
default n
if BSP_USING_SPI
config BSP_USING_SPI0
bool "Enable SPI0"
default n
config BSP_SPI0_TX_USING_DMA
bool "Enable SPI0 TX DMA"
depends on BSP_USING_SPI0
default n
config BSP_SPI0_RX_USING_DMA
bool "Enable SPI0 RX DMA"
depends on BSP_USING_SPI0
default n
config BSP_USING_SPI1
bool "Enable SPI1"
default n
config BSP_SPI1_TX_USING_DMA
bool "Enable SPI1 TX DMA"
depends on BSP_USING_SPI1
default n
config BSP_SPI1_RX_USING_DMA
bool "Enable SPI1 RX DMA"
depends on BSP_USING_SPI1
default n
endif
menu "I2C Configuration"
menuconfig BSP_USING_HW_I2C
bool "Enable Hardware I2C"
select RT_USING_I2C
default n
if BSP_USING_HW_I2C
config BSP_USING_I2C0
bool "Enable I2C0"
default y
config BSP_USING_I2C1
bool "Enable I2C1"
default n
endif
menuconfig BSP_USING_I2C0
bool "Enable I2C0 BUS (software simulation)"
default n
select RT_USING_I2C
select RT_USING_I2C_BITOPS
select RT_USING_PIN
if BSP_USING_I2C0
config BSP_I2C0_SCL_PIN
int "i2c0 scl pin number"
range 1 216
default 22
config BSP_I2C0_SDA_PIN
int "I2C0 sda pin number"
range 1 216
default 23
endif
menuconfig BSP_USING_I2C1
bool "Enable I2C1 BUS (software simulation)"
default n
select RT_USING_I2C
select RT_USING_I2C_BITOPS
select RT_USING_PIN
if BSP_USING_I2C1
config BSP_I2C1_SCL_PIN
int "i2c1 scl pin number"
range 1 216
default 24
config BSP_I2C1_SDA_PIN
int "I2C1 sda pin number"
range 1 216
default 25
endif
endmenu
menuconfig BSP_USING_ADC
bool "Enable ADC"
select RT_USING_ADC
default n
if BSP_USING_ADC
config BSP_USING_ADC0
bool "Enable ADC"
default y
endif
menuconfig BSP_USING_TIM
bool "Enable Hardware Timer"
select RT_USING_HWTIMER
default n
if BSP_USING_TIM
config BSP_USING_TIM2
bool "Enable TIM2"
default n
config BSP_USING_TIM3
bool "Enable TIM3"
default n
endif
menuconfig BSP_USING_ONCHIP_RTC
bool "Enable RTC"
select RT_USING_RTC
default n
if BSP_USING_ONCHIP_RTC
choice
prompt "Select RTC clock source"
default BSP_RTC_USING_LSE
config BSP_RTC_USING_LSE
bool "RTC using LSE (External Crystal)"
config BSP_RTC_USING_LSI
bool "RTC using LSI (Internal RC)"
endchoice
endif
config BSP_USING_WDT
bool "Enable Watchdog Timer"
select RT_USING_WDT
default n
# Source the upstream GD32 drivers Kconfig
source "$(BSP_DIR)/../libraries/gd32_drivers/Kconfig"
endmenu
menu "Board extended module Drivers"
# Configuration for external modules connected to the board
endmenu
endmenu

View File

@@ -0,0 +1,17 @@
import os
import rtconfig
from building import *
cwd = GetCurrentDir()
# add general drivers
src = Split('''
board.c
''')
path = [cwd]
CPPDEFINES = ['GD32E23X', 'GD32E23X_HD']
group = DefineGroup('Drivers', src, depend = [''], CPPPATH = path, CPPDEFINES = CPPDEFINES)
Return('group')

View File

@@ -0,0 +1,80 @@
/*
* Copyright (c) 2006-2025, RT-Thread Development Team
*
* SPDX-License-Identifier: Apache-2.0
*
*/
#include <rthw.h>
#include <rtthread.h>
#include "board.h"
#include "gd32e23x.h"
#ifdef RT_USING_SERIAL
#if defined(RT_USING_SERIAL_V2)
#include "drv_usart_v2.h"
#else
#include "drv_usart.h"
#endif
#endif
/**
* @brief This function is executed in case of error occurrence.
* @param None
* @retval None
*/
void Error_Handler(void)
{
rt_kprintf("\nError_Handler triggered! System halted.\n");
while (1)
{
}
}
/**
* @brief This is the timer interrupt service routine.
*
*/
void SysTick_Handler(void)
{
/* enter interrupt */
rt_interrupt_enter();
rt_tick_increase();
/* leave interrupt */
rt_interrupt_leave();
}
/**
* @brief This function will initial GD32 board.
* @note This function is called from the RT-Thread startup code.
*/
void rt_hw_board_init(void)
{
#ifdef VECT_TAB_RAM
SCB->VTOR = 0x20000000;
#else /* VECT_TAB_FLASH is the default */
SCB->VTOR = 0x08000000;
#endif
SysTick_Config(SystemCoreClock / RT_TICK_PER_SECOND);
NVIC_SetPriority(SysTick_IRQn, (1 << __NVIC_PRIO_BITS) - 1);
#ifdef RT_USING_HEAP
rt_system_heap_init((void *)HEAP_BEGIN, (void *)HEAP_END);
#endif
#ifdef RT_USING_SERIAL
rt_hw_usart_init();
#endif
#ifdef RT_USING_CONSOLE
rt_console_set_device(RT_CONSOLE_DEVICE_NAME);
#endif
#ifdef RT_USING_COMPONENTS_INIT
rt_components_board_init();
#endif
}

View File

@@ -0,0 +1,35 @@
/*
* Copyright (c) 2006-2025, RT-Thread Development Team
*
* SPDX-License-Identifier: Apache-2.0
*
*/
#ifndef __BOARD_H__
#define __BOARD_H__
#include "gd32e23x.h"
#include "drv_gpio.h"
#include "gd32e23x_exti.h"
#define GD32_SRAM_SIZE 8
#define GD32_SRAM_BEGIN (0x20000000)
#define GD32_SRAM_END (GD32_SRAM_BEGIN + GD32_SRAM_SIZE * 1024)
#ifdef __ARMCC_VERSION
extern int Image$$RW_IRAM1$$ZI$$Limit;
#define HEAP_BEGIN (&Image$$RW_IRAM1$$ZI$$Limit)
#elif __ICCARM__
#pragma section="CSTACK"
#define HEAP_BEGIN (__segment_end("CSTACK"))
#else /* GCC */
extern int __bss_end;
#define HEAP_BEGIN (&__bss_end)
#endif
#define HEAP_END GD32_SRAM_END
#endif

View File

@@ -0,0 +1,59 @@
/*!
\file gd32e23x_libopt.h
\brief library optional for gd32e23x
\version 2025-02-10, V2.3.0, firmware for GD32E23x
*/
/*
Copyright (c) 2025, 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.
*/
#ifndef GD32E23X_LIBOPT_H
#define GD32E23X_LIBOPT_H
#include "gd32e23x_adc.h"
#include "gd32e23x_crc.h"
#include "gd32e23x_dbg.h"
#include "gd32e23x_dma.h"
#include "gd32e23x_exti.h"
#include "gd32e23x_fmc.h"
#include "gd32e23x_gpio.h"
#include "gd32e23x_syscfg.h"
#include "gd32e23x_i2c.h"
#include "gd32e23x_fwdgt.h"
#include "gd32e23x_pmu.h"
#include "gd32e23x_rcu.h"
#include "gd32e23x_rtc.h"
#include "gd32e23x_spi.h"
#include "gd32e23x_timer.h"
#include "gd32e23x_usart.h"
#include "gd32e23x_wwdgt.h"
#include "gd32e23x_misc.h"
#include "gd32e23x_cmp.h"
#endif /* GD32E23X_LIBOPT_H */

View File

@@ -0,0 +1,51 @@
/*###ICF### Section handled by ICF editor, don't touch! ****/
/*-Editor annotation file-*/
/* IcfEditorFile="$TOOLKIT_DIR$\config\ide\IcfEditor\cortex_v1_0.xml" */
/*-Specials-*/
define symbol __ICFEDIT_intvec_start__ = 0x08000000;
/*-Memory Regions-*/
/*
* IMPORTANT: Please check your specific chip's datasheet for correct memory sizes.
* The following values are for a GD32E230 with 64KB Flash and 8KB SRAM.
*/
define symbol __ICFEDIT_region_ROM_start__ = 0x08000000;
define symbol __ICFEDIT_region_ROM_end__ = 0x0800FFFF; /* 64KB Flash */
define symbol __ICFEDIT_region_RAM_start__ = 0x20000000;
define symbol __ICFEDIT_region_RAM_end__ = 0x20001FFF; /* 8KB SRAM */
/*-Sizes-*/
/*
* The CSTACK is used for main function before scheduler start and for interrupt handlers.
* The HEAP is the C library heap, which is rarely used in RT-Thread.
* RT-Thread uses the remaining RAM for its own dynamic memory heap.
*/
define symbol __ICFEDIT_size_cstack__ = 0x400; /* 1024 bytes, a safer size */
define symbol __ICFEDIT_size_heap__ = 0x100; /* 256 bytes, can be smaller */
/**** End of ICF editor section. ###ICF###*/
define memory mem with size = 4G;
define region ROM_region = mem:[from __ICFEDIT_region_ROM_start__ to __ICFEDIT_region_ROM_end__];
define region RAM_region = mem:[from __ICFEDIT_region_RAM_start__ to __ICFEDIT_region_RAM_end__];
/* Remove the non-existent RAM1 region */
/* define region RAM1_region = mem:[from __region_RAM1_start__ to __region_RAM1_end__]; */
define block CSTACK with alignment = 8, size = __ICFEDIT_size_cstack__ { };
define block HEAP with alignment = 8, size = __ICFEDIT_size_heap__ { };
initialize by copy { readwrite };
do not initialize { section .noinit };
/* Keep RT-Thread FinSH command symbols */
keep { section FSymTab };
keep { section VSymTab };
keep { section .rti_fn* };
place at address mem:__ICFEDIT_intvec_start__ { readonly section .intvec };
place in ROM_region { readonly };
place in RAM_region { readwrite,
block CSTACK, block HEAP };
/* Remove placement in the non-existent RAM1 region */
/* place in RAM1_region { section .sram }; */

View File

@@ -0,0 +1,139 @@
/*
* linker script for GD32E230x with GNU ld
* Adapted from GD32E50x version.
* Corrected by Gemini to fix oversized .bin file and subsequent linker errors.
*/
MEMORY
{
/*
* IMPORTANT: Please check your specific chip's datasheet for correct memory sizes.
* The following values are for a GD32E230 with 64KB Flash and 8KB SRAM.
*/
CODE (rx) : ORIGIN = 0x08000000, LENGTH = 64k /* MODIFIED: 64KB flash */
DATA (rw) : ORIGIN = 0x20000000, LENGTH = 8k /* MODIFIED: 8KB sram */
}
/* Program Entry, set to mark it as "used" and avoid gc */
ENTRY(Reset_Handler)
/*
* Define the size of the stack used by the system.
* This is for the main stack pointer (MSP), used before RT-Thread scheduler starts and in interrupts.
* Increased to 1KB for safety.
*/
_system_stack_size = 0x400; /* MODIFIED: 1024 bytes */
SECTIONS
{
.text :
{
. = ALIGN(4);
_stext = .;
KEEP(*(.isr_vector)) /* Startup code */
. = ALIGN(4);
*(.text) /* remaining code */
*(.text.*) /* remaining code */
*(.rodata) /* read-only data (constants) */
*(.rodata*)
*(.glue_7)
*(.glue_7t)
*(.gnu.linkonce.t*)
/* section information for finsh shell */
. = ALIGN(4);
__fsymtab_start = .;
KEEP(*(FSymTab))
__fsymtab_end = .;
. = ALIGN(4);
__vsymtab_start = .;
KEEP(*(VSymTab))
__vsymtab_end = .;
. = ALIGN(4);
/* section information for initial. */
. = ALIGN(4);
__rt_init_start = .;
KEEP(*(SORT(.rti_fn*)))
__rt_init_end = .;
. = ALIGN(4);
. = ALIGN(4);
_etext = .;
} > CODE
/*
* The .ARM.exidx section is needed for exception handling and stack unwinding.
* It should be placed in a loadable region like CODE.
*/
.ARM.exidx :
{
__exidx_start = .;
*(.ARM.exidx* .gnu.linkonce.armexidx.*)
__exidx_end = .;
} > CODE
/*
* Define the load address for the .data section.
* It should immediately follow the .ARM.exidx section in Flash.
*/
_sidata = __exidx_end;
/* .data section which is used for initialized data */
.data : AT (_sidata)
{
. = ALIGN(4);
_sdata = . ;
*(.data)
*(.data.*)
*(.gnu.linkonce.d*)
. = ALIGN(4);
_edata = . ;
} > DATA
/* Main stack, located at the top of the RAM region */
.stack (NOLOAD):
{
. = ALIGN(8);
_sstack = .;
. = . + _system_stack_size;
. = ALIGN(8);
_estack = .;
} > DATA
/* .bss section which is used for uninitialized data */
.bss :
{
. = ALIGN(4);
_sbss = .;
*(.bss)
*(.bss.*)
*(COMMON)
. = ALIGN(4);
_ebss = . ;
} > DATA
/* Define __bss_end for C code to find the heap start. */
__bss_end = _ebss;
_end = .;
/******************************************************************************
* Corrected section to discard unwanted information from the final binary. *
******************************************************************************/
/DISCARD/ :
{
libc.a ( * )
libm.a ( * )
libgcc.a ( * )
/* Discard all debugging and comment sections using the correct wildcard syntax */
*(.comment)
*(.debug*)
*(.line)
*(.stab)
*(.stabstr)
*(.note.gnu.build-id)
*(.ARM.attributes)
}
}

View File

@@ -0,0 +1,39 @@
; *************************************************************
; *** Scatter-Loading Description File for GD32E230 + RT-Thread
; *** Target: GD32E230C8T6 (64KB Flash, 8KB SRAM)
; *** This version is more structured and recommended.
; *************************************************************
#!armclang --cpu=cortex-m23
; Define stack and heap sizes
define symbol Stack_Size = 0x00000400; ; 1KB for Main Stack
define symbol Heap_Size = 0x00000100; ; 256B for C-library Heap
; Max size of load region LR_IROM1
LR_IROM1 0x08000000 0x00010000 { ; Load region: Flash, 64KB
; First execution region for exception vectors and startup code
ER_IROM1 0x08000000 0x00010000 {
*.o (RESET, +First)
*(InRoot$$Sections)
.ANY (+RO)
; --- Special sections for RT-Thread ---
* (FSymTab)
* (VSymTab)
* (rti_fn*)
; --------------------------------------
}
; RAM region for RW, ZI, Stack, and Heap
RW_IRAM1 0x20000000 0x00002000 { ; RW region: SRAM, 8KB
; C-library Stack, placed at the top of RAM, growing downwards
ARM_LIB_STACK STACK_TOP(0x20002000) EMPTY -Stack_Size { }
.ANY (+RW +ZI)
; C-library Heap, placed after RW/ZI data
ARM_LIB_HEAP +0 EMPTY Heap_Size { }
}
}

Binary file not shown.

After

Width:  |  Height:  |  Size: 120 KiB

View File

@@ -0,0 +1,413 @@
#ifndef RT_CONFIG_H__
#define RT_CONFIG_H__
/* RT-Thread Kernel */
/* klibc options */
/* rt_vsnprintf options */
/* end of rt_vsnprintf options */
/* rt_vsscanf options */
/* end of rt_vsscanf options */
/* rt_memset options */
/* end of rt_memset options */
/* rt_memcpy options */
/* end of rt_memcpy options */
/* rt_memmove options */
/* end of rt_memmove options */
/* rt_memcmp options */
/* end of rt_memcmp options */
/* rt_strstr options */
/* end of rt_strstr options */
/* rt_strcasecmp options */
/* end of rt_strcasecmp options */
/* rt_strncpy options */
/* end of rt_strncpy options */
/* rt_strcpy options */
/* end of rt_strcpy options */
/* rt_strncmp options */
/* end of rt_strncmp options */
/* rt_strcmp options */
/* end of rt_strcmp options */
/* rt_strlen options */
/* end of rt_strlen options */
/* rt_strnlen options */
/* end of rt_strnlen options */
/* end of klibc options */
#define RT_NAME_MAX 8
#define RT_CPUS_NR 1
#define RT_ALIGN_SIZE 8
#define RT_THREAD_PRIORITY_32
#define RT_THREAD_PRIORITY_MAX 32
#define RT_TICK_PER_SECOND 100
#define RT_USING_OVERFLOW_CHECK
#define RT_USING_HOOK
#define RT_HOOK_USING_FUNC_PTR
#define RT_USING_IDLE_HOOK
#define RT_IDLE_HOOK_LIST_SIZE 4
#define IDLE_THREAD_STACK_SIZE 256
/* kservice options */
/* end of kservice options */
#define RT_USING_DEBUG
#define RT_DEBUGING_ASSERT
#define RT_DEBUGING_COLOR
#define RT_DEBUGING_CONTEXT
/* Inter-Thread communication */
#define RT_USING_SEMAPHORE
#define RT_USING_MUTEX
#define RT_USING_EVENT
#define RT_USING_MAILBOX
#define RT_USING_MESSAGEQUEUE
/* end of Inter-Thread communication */
/* Memory Management */
#define RT_USING_MEMPOOL
#define RT_USING_SMALL_MEM
#define RT_USING_SMALL_MEM_AS_HEAP
#define RT_USING_HEAP
/* end of Memory Management */
#define RT_USING_DEVICE
#define RT_USING_CONSOLE
#define RT_CONSOLEBUF_SIZE 128
#define RT_CONSOLE_DEVICE_NAME "uart0"
#define RT_VER_NUM 0x50201
#define RT_BACKTRACE_LEVEL_MAX_NR 32
/* end of RT-Thread Kernel */
#define RT_USING_HW_ATOMIC
#define ARCH_ARM
#define ARCH_ARM_CORTEX_M
#define ARCH_ARM_CORTEX_M23
/* RT-Thread Components */
#define RT_USING_COMPONENTS_INIT
#define RT_USING_USER_MAIN
#define RT_MAIN_THREAD_STACK_SIZE 1024
#define RT_MAIN_THREAD_PRIORITY 10
/* DFS: device virtual file system */
/* end of DFS: device virtual file system */
/* Device Drivers */
#define RT_USING_DEVICE_IPC
#define RT_UNAMED_PIPE_NUMBER 64
#define RT_USING_SERIAL
#define RT_USING_SERIAL_V1
#define RT_SERIAL_RB_BUFSZ 64
#define RT_USING_PIN
/* end of Device Drivers */
/* C/C++ and POSIX layer */
/* ISO-ANSI C layer */
/* Timezone and Daylight Saving Time */
#define RT_LIBC_USING_LIGHT_TZ_DST
#define RT_LIBC_TZ_DEFAULT_HOUR 8
#define RT_LIBC_TZ_DEFAULT_MIN 0
#define RT_LIBC_TZ_DEFAULT_SEC 0
/* end of Timezone and Daylight Saving Time */
/* end of ISO-ANSI C layer */
/* POSIX (Portable Operating System Interface) layer */
/* Interprocess Communication (IPC) */
/* Socket is in the 'Network' category */
/* end of Interprocess Communication (IPC) */
/* end of POSIX (Portable Operating System Interface) layer */
/* end of C/C++ and POSIX layer */
/* Network */
/* end of Network */
/* Memory protection */
/* end of Memory protection */
/* Utilities */
/* end of Utilities */
/* Using USB legacy version */
/* end of Using USB legacy version */
/* end of RT-Thread Components */
/* RT-Thread Utestcases */
/* end of RT-Thread Utestcases */
/* RT-Thread online packages */
/* IoT - internet of things */
/* Wi-Fi */
/* Marvell WiFi */
/* end of Marvell WiFi */
/* Wiced WiFi */
/* end of Wiced WiFi */
/* CYW43012 WiFi */
/* end of CYW43012 WiFi */
/* BL808 WiFi */
/* end of BL808 WiFi */
/* CYW43439 WiFi */
/* end of CYW43439 WiFi */
/* end of Wi-Fi */
/* IoT Cloud */
/* end of IoT Cloud */
/* end of IoT - internet of things */
/* security packages */
/* end of security packages */
/* language packages */
/* JSON: JavaScript Object Notation, a lightweight data-interchange format */
/* end of JSON: JavaScript Object Notation, a lightweight data-interchange format */
/* XML: Extensible Markup Language */
/* end of XML: Extensible Markup Language */
/* end of language packages */
/* multimedia packages */
/* LVGL: powerful and easy-to-use embedded GUI library */
/* end of LVGL: powerful and easy-to-use embedded GUI library */
/* u8g2: a monochrome graphic library */
/* end of u8g2: a monochrome graphic library */
/* end of multimedia packages */
/* tools packages */
/* end of tools packages */
/* system packages */
/* enhanced kernel services */
/* end of enhanced kernel services */
/* acceleration: Assembly language or algorithmic acceleration packages */
/* end of acceleration: Assembly language or algorithmic acceleration packages */
/* CMSIS: ARM Cortex-M Microcontroller Software Interface Standard */
/* end of CMSIS: ARM Cortex-M Microcontroller Software Interface Standard */
/* Micrium: Micrium software products porting for RT-Thread */
/* end of Micrium: Micrium software products porting for RT-Thread */
/* end of system packages */
/* peripheral libraries and drivers */
/* HAL & SDK Drivers */
/* STM32 HAL & SDK Drivers */
/* end of STM32 HAL & SDK Drivers */
/* Infineon HAL Packages */
/* end of Infineon HAL Packages */
/* Kendryte SDK */
/* end of Kendryte SDK */
/* WCH HAL & SDK Drivers */
/* end of WCH HAL & SDK Drivers */
/* AT32 HAL & SDK Drivers */
/* end of AT32 HAL & SDK Drivers */
/* HC32 DDL Drivers */
/* end of HC32 DDL Drivers */
/* NXP HAL & SDK Drivers */
/* end of NXP HAL & SDK Drivers */
/* NUVOTON Drivers */
/* end of NUVOTON Drivers */
/* GD32 Drivers */
#define PKG_USING_GD32_ARM_CMSIS_DRIVER
#define PKG_USING_GD32_ARM_CMSIS_DRIVER_LATEST_VERSION
#define PKG_USING_GD32_ARM_SERIES_DRIVER
#define PKG_USING_GD32_ARM_SERIES_DRIVER_LATEST_VERSION
/* end of GD32 Drivers */
/* end of HAL & SDK Drivers */
/* sensors drivers */
/* end of sensors drivers */
/* touch drivers */
/* end of touch drivers */
/* end of peripheral libraries and drivers */
/* AI packages */
/* end of AI packages */
/* Signal Processing and Control Algorithm Packages */
/* end of Signal Processing and Control Algorithm Packages */
/* miscellaneous packages */
/* project laboratory */
/* end of project laboratory */
/* samples: kernel and components samples */
/* end of samples: kernel and components samples */
/* entertainment: terminal games and other interesting software packages */
/* end of entertainment: terminal games and other interesting software packages */
/* end of miscellaneous packages */
/* Arduino libraries */
/* Projects and Demos */
/* end of Projects and Demos */
/* Sensors */
/* end of Sensors */
/* Display */
/* end of Display */
/* Timing */
/* end of Timing */
/* Data Processing */
/* end of Data Processing */
/* Data Storage */
/* Communication */
/* end of Communication */
/* Device Control */
/* end of Device Control */
/* Other */
/* end of Other */
/* Signal IO */
/* end of Signal IO */
/* Uncategorized */
/* end of Arduino libraries */
/* end of RT-Thread online packages */
#define SOC_FAMILY_GD32
#define SOC_SERIES_GD32E23x
/* Hardware Drivers Config */
#define SOC_GD32E230C8T6
/* Onboard Peripheral Drivers */
#define BSP_USING_LED
#define BSP_LED_PIN 45
/* end of Onboard Peripheral Drivers */
/* On-chip Peripheral Drivers */
#define BSP_USING_GPIO
#define BSP_USING_UART
#define BSP_USING_UART0
/* I2C Configuration */
/* end of I2C Configuration */
/* end of On-chip Peripheral Drivers */
/* Board extended module Drivers */
/* end of Hardware Drivers Config */
#endif

View File

@@ -0,0 +1,148 @@
import os
# toolchains options
ARCH='arm'
CPU='cortex-m23'
CROSS_TOOL='gcc'
# bsp lib config
BSP_LIBRARY_TYPE = None
if os.getenv('RTT_CC'):
CROSS_TOOL = os.getenv('RTT_CC')
if os.getenv('RTT_ROOT'):
RTT_ROOT = os.getenv('RTT_ROOT')
# cross_tool provides the cross compiler
# EXEC_PATH is the compiler execute path, for example, CodeSourcery, Keil MDK, IAR
if CROSS_TOOL == 'gcc':
PLATFORM = 'gcc'
EXEC_PATH = r'/usr/bin'
elif CROSS_TOOL == 'keil':
PLATFORM = 'armcc'
EXEC_PATH = r'C:/Keil_v5'
elif CROSS_TOOL == 'iar':
PLATFORM = 'iccarm'
EXEC_PATH = r'C:/Program Files (x86)/IAR Systems/Embedded Workbench 8.3'
if os.getenv('RTT_EXEC_PATH'):
EXEC_PATH = os.getenv('RTT_EXEC_PATH')
BUILD = 'release'
if PLATFORM == 'gcc':
# toolchains
PREFIX = 'arm-none-eabi-'
CC = PREFIX + 'gcc'
AS = PREFIX + 'gcc'
AR = PREFIX + 'ar'
CXX = PREFIX + 'g++'
LINK = PREFIX + 'gcc'
TARGET_EXT = 'elf'
SIZE = PREFIX + 'size'
OBJDUMP = PREFIX + 'objdump'
OBJCPY = PREFIX + 'objcopy'
DEVICE = ' -mcpu=cortex-m23 -mthumb -ffunction-sections -fdata-sections'
CFLAGS = DEVICE + ' -Dgcc'
AFLAGS = ' -c' + DEVICE + ' -x assembler-with-cpp -Wa,-mimplicit-it=thumb'
LFLAGS = DEVICE + ' -Wl,--gc-sections,-Map=rtthread.map,-cref,-u,Reset_Handler -T board/linker_scripts/link.ld'
CPATH = ''
LPATH = ''
if BUILD == 'debug':
CFLAGS += ' -O0 -gdwarf-2 -g'
AFLAGS += ' -gdwarf-2'
else:
CFLAGS += ' -O2'
CXXFLAGS = CFLAGS
POST_ACTION = OBJCPY + ' -O binary $TARGET rtthread.bin\n' + SIZE + ' $TARGET \n'
elif PLATFORM == 'armcc':
# toolchains
CC = 'armcc'
CXX = 'armcc'
AS = 'armasm'
AR = 'armar'
LINK = 'armlink'
TARGET_EXT = 'axf'
DEVICE = ' --cpu Cortex-M23 '
CFLAGS = '-c ' + DEVICE + ' --apcs=interwork --c99'
AFLAGS = DEVICE + ' --apcs=interwork '
LFLAGS = DEVICE + ' --scatter "board/linker_scripts/link.sct" --info sizes --info totals --info unused --info veneers --list rtthread.map --strict'
CFLAGS += ' -I' + EXEC_PATH + '/ARM/ARMCC/include'
LFLAGS += ' --libpath=' + EXEC_PATH + '/ARM/ARMCC/lib'
CFLAGS += ' -D__MICROLIB '
AFLAGS += ' --pd "__MICROLIB SETA 1" '
LFLAGS += ' --library_type=microlib '
EXEC_PATH += '/ARM/ARMCC/bin/'
if BUILD == 'debug':
CFLAGS += ' -g -O0'
AFLAGS += ' -g'
else:
CFLAGS += ' -O2'
CXXFLAGS = CFLAGS
CFLAGS += ' -std=c99'
POST_ACTION = 'fromelf --bin $TARGET --output rtthread.bin \nfromelf -z $TARGET'
elif PLATFORM == 'iccarm':
# toolchains
CC = 'iccarm'
CXX = 'iccarm'
AS = 'iasmarm'
AR = 'iarchive'
LINK = 'ilinkarm'
TARGET_EXT = 'out'
DEVICE = '-Dewarm'
CFLAGS = DEVICE
CFLAGS += ' --diag_suppress Pa050'
CFLAGS += ' --no_cse'
CFLAGS += ' --no_unroll'
CFLAGS += ' --no_inline'
CFLAGS += ' --no_code_motion'
CFLAGS += ' --no_tbaa'
CFLAGS += ' --no_clustering'
CFLAGS += ' --no_scheduling'
CFLAGS += ' --endian=little'
CFLAGS += ' --cpu=Cortex-M23'
CFLAGS += ' -e'
CFLAGS += ' --dlib_config "' + EXEC_PATH + '/arm/INC/c/DLib_Config_Normal.h"'
CFLAGS += ' --silent'
AFLAGS = DEVICE
AFLAGS += ' -s+'
AFLAGS += ' -w+'
AFLAGS += ' -r'
AFLAGS += ' --cpu Cortex-M23'
AFLAGS += ' -S'
if BUILD == 'debug':
CFLAGS += ' --debug'
CFLAGS += ' -On'
else:
CFLAGS += ' -Oh'
LFLAGS = ' --config "board/linker_scripts/link.icf"'
LFLAGS += ' --entry __iar_program_start'
CXXFLAGS = CFLAGS
EXEC_PATH = EXEC_PATH + '/arm/bin/'
POST_ACTION = 'ielftool --bin $TARGET rtthread.bin'
def dist_handle(BSP_ROOT, dist_dir):
import sys
cwd_path = os.getcwd()
sys.path.append(os.path.join(os.path.dirname(BSP_ROOT), 'tools'))
from sdk_dist import dist_do_building
dist_do_building(BSP_ROOT, dist_dir)

View File

@@ -34,4 +34,9 @@ config SOC_SERIES_GD32H7xx
config SOC_SERIES_GD32F5xx
bool
select ARCH_ARM_CORTEX_M33
select SOC_FAMILY_GD32
config SOC_SERIES_GD32E23x
bool
select ARCH_ARM_CORTEX_M23
select SOC_FAMILY_GD32

View File

@@ -1,5 +1,5 @@
/*
* Copyright (c) 2006-2022, RT-Thread Development Team
* Copyright (c) 2006-2025, RT-Thread Development Team
*
* SPDX-License-Identifier: Apache-2.0
*
@@ -35,6 +35,16 @@ struct rt_adc_device adc2;
static const struct gd32_adc adc_obj[] = {
#ifdef BSP_USING_ADC0
{
#if defined SOC_SERIES_GD32E23x
ADC,
RCU_ADC,
{
GET_PIN(A, 0), GET_PIN(A, 1), GET_PIN(A, 2), GET_PIN(A, 3),
GET_PIN(A, 4), GET_PIN(A, 5), GET_PIN(A, 6), GET_PIN(A, 7),
GET_PIN(B, 0), GET_PIN(B, 1), -1, -1,
-1, -1, -1, -1,
},
#else
ADC0,
RCU_ADC0,
{
@@ -43,6 +53,7 @@ static const struct gd32_adc adc_obj[] = {
GET_PIN(B, 0), GET_PIN(B, 1), GET_PIN(C, 0), GET_PIN(C, 1),
GET_PIN(C, 2), GET_PIN(C, 3), GET_PIN(C, 4), GET_PIN(C, 5),
},
#endif
&adc0,
"adc0",
},
@@ -89,7 +100,7 @@ static void gd32_adc_gpio_init(rcu_periph_enum adc_clk, rt_base_t pin)
/* enable ADC clock */
rcu_periph_clock_enable(adc_clk);
#if defined SOC_SERIES_GD32F4xx
#if defined SOC_SERIES_GD32F4xx || defined SOC_SERIES_GD32E23x
/* configure adc pin */
gpio_mode_set(PIN_GDPORT(pin), GPIO_MODE_ANALOG, GPIO_PUPD_NONE, PIN_GDPIN(pin));
#else
@@ -122,27 +133,47 @@ static rt_err_t gd32_adc_enabled(struct rt_adc_device *device, rt_int8_t channel
{
gd32_adc_gpio_init(adc->adc_clk, adc->adc_pins[channel]);
#if defined SOC_SERIES_GD32E23x
adc_data_alignment_config(ADC_DATAALIGN_RIGHT);
#else
adc_data_alignment_config(adc_periph, ADC_DATAALIGN_RIGHT);
#endif
#if defined SOC_SERIES_GD32F4xx
adc_channel_length_config(adc_periph, ADC_ROUTINE_CHANNEL, 1);
adc_external_trigger_source_config(adc_periph, ADC_ROUTINE_CHANNEL, ADC_EXTTRIG_ROUTINE_EXTI_11);
adc_external_trigger_config(adc_periph, ADC_ROUTINE_CHANNEL, ENABLE);
#elif defined SOC_SERIES_GD32E23x
adc_channel_length_config(ADC_REGULAR_CHANNEL, 1);
adc_external_trigger_source_config(ADC_REGULAR_CHANNEL, ADC_EXTTRIG_REGULAR_NONE);
adc_external_trigger_config(ADC_REGULAR_CHANNEL, ENABLE);
#else
adc_channel_length_config(adc_periph, ADC_REGULAR_CHANNEL, 1);
adc_external_trigger_source_config(adc_periph, ADC_REGULAR_CHANNEL, ADC0_1_2_EXTTRIG_REGULAR_NONE);
adc_external_trigger_config(adc_periph, ADC_REGULAR_CHANNEL, ENABLE);
#endif
#if defined SOC_SERIES_GD32E23x
adc_enable();
#else
adc_enable(adc_periph);
#endif
rt_hw_us_delay(1);
/* ADC calibration and reset calibration */
#if defined SOC_SERIES_GD32E23x
adc_calibration_enable();
#else
adc_calibration_enable(adc_periph);
#endif
}
else
{
#if defined SOC_SERIES_GD32E23x
adc_disable();
#else
adc_disable(adc_periph);
#endif
}
return RT_EOK;
}
@@ -166,20 +197,35 @@ static rt_err_t gd32_adc_convert(struct rt_adc_device *device, rt_int8_t channel
}
adc_periph = (uint32_t)(adc->adc_periph);
#if defined SOC_SERIES_GD32E23x
adc_flag_clear(ADC_FLAG_EOC | ADC_FLAG_STRC);
#else
adc_flag_clear(adc_periph, ADC_FLAG_EOC | ADC_FLAG_STRC);
#endif
#if defined SOC_SERIES_GD32F4xx
adc_routine_channel_config(adc_periph, 0, channel, ADC_SAMPLETIME_480);
adc_software_trigger_enable(adc_periph, ADC_ROUTINE_CHANNEL);
#elif defined SOC_SERIES_GD32E23x
adc_regular_channel_config(0, channel, ADC_SAMPLETIME_13POINT5);
adc_software_trigger_enable(ADC_REGULAR_CHANNEL);
#else
adc_regular_channel_config(adc_periph, 0, channel, ADC_SAMPLETIME_13POINT5);
adc_software_trigger_enable(adc_periph, ADC_REGULAR_CHANNEL);
#endif
#if defined SOC_SERIES_GD32E23x
while (!adc_flag_get(ADC_FLAG_EOC))
#else
while (!adc_flag_get(adc_periph, ADC_FLAG_EOC))
#endif
{
if(timeout >= 100)
{
#if defined SOC_SERIES_GD32E23x
adc_flag_clear(ADC_FLAG_EOC | ADC_FLAG_STRC);
#else
adc_flag_clear(adc_periph, ADC_FLAG_EOC | ADC_FLAG_STRC);
#endif
LOG_E("Convert Timeout");
return -RT_ETIMEOUT;
}
@@ -192,11 +238,14 @@ static rt_err_t gd32_adc_convert(struct rt_adc_device *device, rt_int8_t channel
#if defined SOC_SERIES_GD32F4xx
*value = adc_routine_data_read(adc_periph);
adc_flag_clear(adc_periph, ADC_FLAG_EOC | ADC_FLAG_STRC);
#elif defined SOC_SERIES_GD32E23x
*value = adc_regular_data_read();
adc_flag_clear(ADC_FLAG_EOC | ADC_FLAG_STRC);
#else
*value = adc_regular_data_read(adc_periph);
#endif
adc_flag_clear(adc_periph, ADC_FLAG_EOC | ADC_FLAG_STRC);
#endif
return RT_EOK;
}
@@ -225,3 +274,4 @@ static int rt_hw_adc_init(void)
}
INIT_BOARD_EXPORT(rt_hw_adc_init);
#endif

View File

@@ -1,5 +1,5 @@
/*
* Copyright (c) 2006-2022, RT-Thread Development Team
* Copyright (c) 2006-2025, RT-Thread Development Team
*
* SPDX-License-Identifier: Apache-2.0
*
@@ -35,3 +35,4 @@ struct gd32_adc
#endif
#endif /* __DRV_ADC_H__ */

View File

@@ -12,6 +12,28 @@
#define _DRV_DMA_H_
#if defined SOC_SERIES_GD32E23x
#define DRV_DMA_CONFIG(chx) \
(struct dma_config) { \
.periph = DMA, \
.rcu = RCU_DMA, \
.channel = DMA_CH##chx, \
.irq = ((chx) == 0 ? DMA_Channel0_IRQn : \
(chx) == 1 ? DMA_Channel1_2_IRQn : \
(chx) == 2 ? DMA_Channel1_2_IRQn : \
(chx) == 3 ? DMA_Channel3_4_IRQn : \
(chx) == 4 ? DMA_Channel3_4_IRQn : (IRQn_Type)0) \
}
struct dma_config
{
uint32_t periph;
rcu_periph_enum rcu;
dma_channel_enum channel;
IRQn_Type irq;
};
#else
#define DRV_DMA_CONFIG(dmax, chx, subx) { \
.periph = DMA##dmax, \
.channel = DMA_CH##chx, \
@@ -29,4 +51,6 @@ struct dma_config
IRQn_Type irq;
};
#endif
#endif /* _DRV_DMA_H_ */

View File

@@ -1,5 +1,5 @@
/*
* Copyright (c) 2006-2022, RT-Thread Development Team
* Copyright (c) 2006-2025, RT-Thread Development Team
*
* SPDX-License-Identifier: Apache-2.0
*
@@ -182,6 +182,27 @@ static const struct pin_index pins[] =
#endif
};
#if defined SOC_SERIES_GD32E23x
static const struct pin_irq_map pin_irq_map[] =
{
{GPIO_PIN_0, EXTI0_1_IRQn},
{GPIO_PIN_1, EXTI0_1_IRQn},
{GPIO_PIN_2, EXTI2_3_IRQn},
{GPIO_PIN_3, EXTI2_3_IRQn},
{GPIO_PIN_4, EXTI4_15_IRQn},
{GPIO_PIN_5, EXTI4_15_IRQn},
{GPIO_PIN_6, EXTI4_15_IRQn},
{GPIO_PIN_7, EXTI4_15_IRQn},
{GPIO_PIN_8, EXTI4_15_IRQn},
{GPIO_PIN_9, EXTI4_15_IRQn},
{GPIO_PIN_10, EXTI4_15_IRQn},
{GPIO_PIN_11, EXTI4_15_IRQn},
{GPIO_PIN_12, EXTI4_15_IRQn},
{GPIO_PIN_13, EXTI4_15_IRQn},
{GPIO_PIN_14, EXTI4_15_IRQn},
{GPIO_PIN_15, EXTI4_15_IRQn},
};
#else
static const struct pin_irq_map pin_irq_map[] =
{
{GPIO_PIN_0, EXTI0_IRQn},
@@ -201,6 +222,7 @@ static const struct pin_irq_map pin_irq_map[] =
{GPIO_PIN_14, EXTI10_15_IRQn},
{GPIO_PIN_15, EXTI10_15_IRQn},
};
#endif
struct rt_pin_irq_hdr pin_irq_hdr_tab[] =
{
@@ -257,7 +279,7 @@ static void gd32_pin_mode(rt_device_t dev, rt_base_t pin, rt_uint8_t mode)
const struct pin_index *index = RT_NULL;
rt_uint32_t pin_mode = 0;
#if defined SOC_SERIES_GD32F4xx || defined SOC_SERIES_GD32H7xx || defined SOC_SERIES_GD32F5xx
#if defined SOC_SERIES_GD32F4xx || defined SOC_SERIES_GD32H7xx || defined SOC_SERIES_GD32F5xx || defined SOC_SERIES_GD32E23x
rt_uint32_t pin_pupd = 0, pin_odpp = 0;
#endif
@@ -269,7 +291,7 @@ static void gd32_pin_mode(rt_device_t dev, rt_base_t pin, rt_uint8_t mode)
/* GPIO Periph clock enable */
rcu_periph_clock_enable(index->clk);
#if defined SOC_SERIES_GD32F4xx || defined SOC_SERIES_GD32H7xx || defined SOC_SERIES_GD32F5xx
#if defined SOC_SERIES_GD32F4xx || defined SOC_SERIES_GD32H7xx || defined SOC_SERIES_GD32F5xx || defined SOC_SERIES_GD32E23x
pin_mode = GPIO_MODE_OUTPUT;
#else
pin_mode = GPIO_MODE_OUT_PP;
@@ -279,7 +301,7 @@ static void gd32_pin_mode(rt_device_t dev, rt_base_t pin, rt_uint8_t mode)
{
case PIN_MODE_OUTPUT:
/* output setting */
#if defined SOC_SERIES_GD32F4xx || defined SOC_SERIES_GD32H7xx || defined SOC_SERIES_GD32F5xx
#if defined SOC_SERIES_GD32F4xx || defined SOC_SERIES_GD32H7xx || defined SOC_SERIES_GD32F5xx || defined SOC_SERIES_GD32E23x
pin_mode = GPIO_MODE_OUTPUT;
pin_pupd = GPIO_PUPD_NONE;
pin_odpp = GPIO_OTYPE_PP;
@@ -289,7 +311,7 @@ static void gd32_pin_mode(rt_device_t dev, rt_base_t pin, rt_uint8_t mode)
break;
case PIN_MODE_OUTPUT_OD:
/* output setting: od. */
#if defined SOC_SERIES_GD32F4xx || defined SOC_SERIES_GD32H7xx || defined SOC_SERIES_GD32F5xx
#if defined SOC_SERIES_GD32F4xx || defined SOC_SERIES_GD32H7xx || defined SOC_SERIES_GD32F5xx || defined SOC_SERIES_GD32E23x
pin_mode = GPIO_MODE_OUTPUT;
pin_pupd = GPIO_PUPD_NONE;
pin_odpp = GPIO_OTYPE_OD;
@@ -299,7 +321,7 @@ static void gd32_pin_mode(rt_device_t dev, rt_base_t pin, rt_uint8_t mode)
break;
case PIN_MODE_INPUT:
/* input setting: not pull. */
#if defined SOC_SERIES_GD32F4xx || defined SOC_SERIES_GD32H7xx || defined SOC_SERIES_GD32F5xx
#if defined SOC_SERIES_GD32F4xx || defined SOC_SERIES_GD32H7xx || defined SOC_SERIES_GD32F5xx || defined SOC_SERIES_GD32E23x
pin_mode = GPIO_MODE_INPUT;
pin_pupd = GPIO_PUPD_PULLUP | GPIO_PUPD_PULLDOWN;
#else
@@ -308,7 +330,7 @@ static void gd32_pin_mode(rt_device_t dev, rt_base_t pin, rt_uint8_t mode)
break;
case PIN_MODE_INPUT_PULLUP:
/* input setting: pull up. */
#if defined SOC_SERIES_GD32F4xx || defined SOC_SERIES_GD32H7xx || defined SOC_SERIES_GD32F5xx
#if defined SOC_SERIES_GD32F4xx || defined SOC_SERIES_GD32H7xx || defined SOC_SERIES_GD32F5xx || defined SOC_SERIES_GD32E23x
pin_mode = GPIO_MODE_INPUT;
pin_pupd = GPIO_PUPD_PULLUP;
#else
@@ -317,7 +339,7 @@ static void gd32_pin_mode(rt_device_t dev, rt_base_t pin, rt_uint8_t mode)
break;
case PIN_MODE_INPUT_PULLDOWN:
/* input setting: pull down. */
#if defined SOC_SERIES_GD32F4xx || defined SOC_SERIES_GD32H7xx || defined SOC_SERIES_GD32F5xx
#if defined SOC_SERIES_GD32F4xx || defined SOC_SERIES_GD32H7xx || defined SOC_SERIES_GD32F5xx || defined SOC_SERIES_GD32E23x
pin_mode = GPIO_MODE_INPUT;
pin_pupd = GPIO_PUPD_PULLDOWN;
#else
@@ -328,7 +350,7 @@ static void gd32_pin_mode(rt_device_t dev, rt_base_t pin, rt_uint8_t mode)
break;
}
#if defined SOC_SERIES_GD32F4xx || defined SOC_SERIES_GD32F5xx
#if defined SOC_SERIES_GD32F4xx || defined SOC_SERIES_GD32F5xx || defined SOC_SERIES_GD32E23x
gpio_mode_set(index->gpio_periph, pin_mode, pin_pupd, index->pin);
if(pin_mode == GPIO_MODE_OUTPUT)
{
@@ -449,6 +471,7 @@ static rt_err_t gd32_pin_attach_irq(struct rt_device *device, rt_base_t pin,
rt_hw_interrupt_enable(level);
return RT_EOK;
}
if (pin_irq_hdr_tab[hdr_index].pin != -1)
{
rt_hw_interrupt_enable(level);
@@ -555,15 +578,20 @@ static rt_err_t gd32_pin_irq_enable(struct rt_device *device, rt_base_t pin, rt_
#if defined SOC_SERIES_GD32F4xx || defined SOC_SERIES_GD32H7xx || defined SOC_SERIES_GD32F5xx
rcu_periph_clock_enable(RCU_SYSCFG);
#elif defined SOC_SERIES_GD32E23x
rcu_periph_clock_enable(RCU_CFGCMP);
#else
rcu_periph_clock_enable(RCU_AF);
#endif
/* enable and set interrupt priority */
#if defined SOC_SERIES_GD32E23x
nvic_irq_enable(irqmap->irqno, 5U);
#else
nvic_irq_enable(irqmap->irqno, 5U, 0U);
#endif
/* connect EXTI line to GPIO pin */
#if defined SOC_SERIES_GD32F4xx || defined SOC_SERIES_GD32H7xx || defined SOC_SERIES_GD32F5xx
#if defined SOC_SERIES_GD32F4xx || defined SOC_SERIES_GD32H7xx || defined SOC_SERIES_GD32F5xx || defined SOC_SERIES_GD32E23x
syscfg_exti_line_config(index->port_src, index->pin_src);
#else
gpio_exti_source_select(index->port_src, index->pin_src);
@@ -630,6 +658,47 @@ void GD32_GPIO_EXTI_IRQHandler(rt_int8_t exti_line)
}
}
#if defined SOC_SERIES_GD32E23x
void EXTI0_1_IRQHandler(void)
{
rt_interrupt_enter();
GD32_GPIO_EXTI_IRQHandler(0);
GD32_GPIO_EXTI_IRQHandler(1);
rt_interrupt_leave();
}
void EXTI2_3_IRQHandler(void)
{
rt_interrupt_enter();
GD32_GPIO_EXTI_IRQHandler(2);
GD32_GPIO_EXTI_IRQHandler(3);
rt_interrupt_leave();
}
void EXTI4_15_IRQHandler(void)
{
rt_interrupt_enter();
GD32_GPIO_EXTI_IRQHandler(4);
GD32_GPIO_EXTI_IRQHandler(5);
GD32_GPIO_EXTI_IRQHandler(6);
GD32_GPIO_EXTI_IRQHandler(7);
GD32_GPIO_EXTI_IRQHandler(8);
GD32_GPIO_EXTI_IRQHandler(9);
GD32_GPIO_EXTI_IRQHandler(10);
GD32_GPIO_EXTI_IRQHandler(11);
GD32_GPIO_EXTI_IRQHandler(12);
GD32_GPIO_EXTI_IRQHandler(13);
GD32_GPIO_EXTI_IRQHandler(14);
GD32_GPIO_EXTI_IRQHandler(15);
rt_interrupt_leave();
}
#else
void EXTI0_IRQHandler(void)
{
rt_interrupt_enter();
@@ -687,6 +756,7 @@ void EXTI10_15_IRQHandler(void)
GD32_GPIO_EXTI_IRQHandler(15);
rt_interrupt_leave();
}
#endif
int rt_hw_pin_init(void)
{
@@ -700,3 +770,4 @@ int rt_hw_pin_init(void)
INIT_BOARD_EXPORT(rt_hw_pin_init);
#endif

View File

@@ -1,5 +1,5 @@
/*
* Copyright (c) 2006-2022, RT-Thread Development Team
* Copyright (c) 2006-2025, RT-Thread Development Team
*
* SPDX-License-Identifier: Apache-2.0
*
@@ -33,11 +33,13 @@ extern "C" {
#include "gd32e50x_gpio.h"
#elif defined SOC_SERIES_GD32F5xx
#include "gd32f5xx_gpio.h"
#elif defined SOC_SERIES_GD32E23x
#include "gd32e23x_gpio.h"
#endif
#define __GD32_PORT(port) GPIO##port
#if defined SOC_SERIES_GD32F4xx || defined SOC_SERIES_GD32H7xx || defined SOC_SERIES_GD32F5xx
#if defined SOC_SERIES_GD32F4xx || defined SOC_SERIES_GD32H7xx || defined SOC_SERIES_GD32F5xx || defined SOC_SERIES_GD32E23x
#define GD32_PIN(index, port, pin) {index, RCU_GPIO##port, \
GPIO##port, GPIO_PIN_##pin, \
EXTI_SOURCE_GPIO##port, \

View File

@@ -1,5 +1,5 @@
/*
* Copyright (c) 2006-2022, RT-Thread Development Team
* Copyright (c) 2006-2025, RT-Thread Development Team
*
* SPDX-License-Identifier: Apache-2.0
*
@@ -24,17 +24,92 @@ typedef struct {
static gd32_rtc_device g_gd32_rtc_dev;
/**
* @brief Helper function: Convert BCD value to binary.
* @param val: BCD value.
* @return Binary value.
*/
static rt_uint8_t bcd_to_bin(rt_uint8_t val)
{
return (val & 0x0F) + ((val >> 4) & 0x0F) * 10;
}
/**
* @brief Helper function: Convert binary to BCD.
* @param val: Binary value.
* @return BCD value.
*/
static rt_uint8_t bin_to_bcd(rt_uint8_t val)
{
return ((val / 10) << 4) | (val % 10);
}
static time_t get_rtc_timestamp(void)
{
#if defined SOC_SERIES_GD32E23x
struct tm tm_new;
rtc_parameter_struct rtc_current_time;
rtc_current_time_get(&rtc_current_time);
tm_new.tm_year = bcd_to_bin(rtc_current_time.rtc_year) + 100; /* tm_year: years since 1900 */
tm_new.tm_mon = bcd_to_bin(rtc_current_time.rtc_month) - 1; /* tm_mon: month (0 = January, 11 = December) */
tm_new.tm_mday = bcd_to_bin(rtc_current_time.rtc_date);
tm_new.tm_hour = bcd_to_bin(rtc_current_time.rtc_hour);
tm_new.tm_min = bcd_to_bin(rtc_current_time.rtc_minute);
tm_new.tm_sec = bcd_to_bin(rtc_current_time.rtc_second);
return mktime(&tm_new);
#else
time_t rtc_counter;
rtc_counter = (time_t)rtc_counter_get();
return rtc_counter;
#endif
}
static rt_err_t set_rtc_timestamp(time_t time_stamp)
{
#if defined SOC_SERIES_GD32E23x
struct tm *p_tm;
rtc_parameter_struct rtc_init_struct;
p_tm = gmtime(&time_stamp);
/* GD32 RTC uses year starting from 2000; thus tm_year must be at least 100 (i.e., 2000 - 1900) */
if (p_tm->tm_year < 100)
{
return -RT_ERROR;
}
rtc_init_struct.rtc_year = bin_to_bcd(p_tm->tm_year - 100);
rtc_init_struct.rtc_month = bin_to_bcd(p_tm->tm_mon + 1);
rtc_init_struct.rtc_date = bin_to_bcd(p_tm->tm_mday);
rtc_init_struct.rtc_day_of_week = bin_to_bcd(p_tm->tm_wday == 0 ? 7 : p_tm->tm_wday);
rtc_init_struct.rtc_hour = bin_to_bcd(p_tm->tm_hour);
rtc_init_struct.rtc_minute = bin_to_bcd(p_tm->tm_min);
rtc_init_struct.rtc_second = bin_to_bcd(p_tm->tm_sec);
rtc_init_struct.rtc_display_format = RTC_24HOUR;
#if defined(BSP_RTC_USING_LSI)
rtc_init_struct.rtc_factor_asyn = 39;
rtc_init_struct.rtc_factor_syn = 999;
#elif defined(BSP_RTC_USING_LSE)
rtc_init_struct.rtc_factor_asyn = 127;
rtc_init_struct.rtc_factor_syn = 255;
#endif
if (rtc_init(&rtc_init_struct) != SUCCESS)
{
LOG_E("Failed to set RTC time.");
return -RT_ERROR;
}
return RT_EOK;
#else
uint32_t rtc_counter;
rtc_counter = (uint32_t)time_stamp;
@@ -51,6 +126,7 @@ static rt_err_t set_rtc_timestamp(time_t time_stamp)
rtc_lwoff_wait();
return RT_EOK;
#endif
}
static rt_err_t rt_gd32_rtc_control(rt_device_t dev, int cmd, void *args)
@@ -94,7 +170,9 @@ static int rt_hw_rtc_init(void)
rcu_periph_clock_enable(RCU_PMU);
pmu_backup_write_enable();
#ifndef SOC_SERIES_GD32E23x
rcu_periph_clock_enable(RCU_BKPI);
#endif
rtc_counter = get_rtc_timestamp();
/* once the rtc clock source has been selected, if can't be changed
@@ -145,3 +223,4 @@ static int rt_hw_rtc_init(void)
}
INIT_DEVICE_EXPORT(rt_hw_rtc_init);
#endif

View File

@@ -1,5 +1,5 @@
/*
* Copyright (c) 2006-2022, RT-Thread Development Team
* Copyright (c) 2006-2025, RT-Thread Development Team
*
* SPDX-License-Identifier: Apache-2.0
*
@@ -44,6 +44,9 @@ static const struct gd32_spi spi_bus_obj[] = {
GPIOA,
#if defined SOC_SERIES_GD32F4xx
GPIO_AF_5,
#endif
#if defined SOC_SERIES_GD32E23x
GPIO_AF_0,
#endif
GPIO_PIN_5,
GPIO_PIN_6,
@@ -62,7 +65,15 @@ static const struct gd32_spi spi_bus_obj[] = {
#if defined SOC_SERIES_GD32F4xx
GPIO_AF_5,
#endif
#if defined SOC_SERIES_GD32E23x
GPIO_AF_0,
#endif
#if defined SOC_SERIES_GD32E23x
GPIO_PIN_13,
#else
GPIO_PIN_12,
#endif
GPIO_PIN_14,
GPIO_PIN_15,
},
@@ -141,12 +152,16 @@ static void gd32_spi_init(struct gd32_spi *gd32_spi)
rcu_periph_clock_enable(gd32_spi->spi_clk);
rcu_periph_clock_enable(gd32_spi->gpio_clk);
#if defined SOC_SERIES_GD32F4xx
#if defined SOC_SERIES_GD32F4xx || defined SOC_SERIES_GD32E23x
/*GPIO pin configuration*/
gpio_af_set(gd32_spi->spi_port, gd32_spi->alt_func_num, gd32_spi->sck_pin | gd32_spi->mosi_pin | gd32_spi->miso_pin);
gpio_mode_set(gd32_spi->spi_port, GPIO_MODE_AF, GPIO_PUPD_NONE, gd32_spi->sck_pin | gd32_spi->mosi_pin | gd32_spi->miso_pin);
#if defined SOC_SERIES_GD32E23x
gpio_output_options_set(gd32_spi->spi_port, GPIO_OTYPE_PP, GPIO_OSPEED_50MHZ, gd32_spi->sck_pin | gd32_spi->mosi_pin | gd32_spi->miso_pin);
#else
gpio_output_options_set(gd32_spi->spi_port, GPIO_OTYPE_PP, GPIO_OSPEED_MAX, gd32_spi->sck_pin | gd32_spi->mosi_pin | gd32_spi->miso_pin);
#endif
#else
/* Init SPI SCK MOSI */
gpio_init(gd32_spi->spi_port, GPIO_MODE_AF_PP, GPIO_OSPEED_50MHZ, gd32_spi->sck_pin | gd32_spi->mosi_pin);
@@ -168,7 +183,7 @@ static rt_err_t spi_configure(struct rt_spi_device* device,
RT_ASSERT(device != RT_NULL);
RT_ASSERT(configuration != RT_NULL);
//Init SPI
/* Init SPI */
gd32_spi_init(spi_device);
/* data_width */
@@ -197,6 +212,9 @@ static rt_err_t spi_configure(struct rt_spi_device* device,
LOG_D("CK_APB2 freq: %d\n", rcu_clock_freq_get(CK_APB2));
LOG_D("max freq: %d\n", max_hz);
#if defined SOC_SERIES_GD32E23x
spi_src = CK_APB2;
#else
if (spi_periph == SPI1 || spi_periph == SPI2)
{
spi_src = CK_APB1;
@@ -205,6 +223,7 @@ static rt_err_t spi_configure(struct rt_spi_device* device,
{
spi_src = CK_APB2;
}
#endif
spi_apb_clock = rcu_clock_freq_get(spi_src);
if(max_hz >= spi_apb_clock/2)
@@ -318,15 +337,15 @@ static rt_ssize_t spixfer(struct rt_spi_device* device, struct rt_spi_message* m
data = *send_ptr++;
}
// Todo: replace register read/write by gd32f4 lib
//Wait until the transmit buffer is empty
/* Todo: replace register read/write by gd32f4 lib */
/* Wait until the transmit buffer is empty */
while(RESET == spi_i2s_flag_get(spi_periph, SPI_FLAG_TBE));
// Send the byte
/* Send the byte */
spi_i2s_data_transmit(spi_periph, data);
//Wait until a data is received
/* Wait until a data is received */
while(RESET == spi_i2s_flag_get(spi_periph, SPI_FLAG_RBNE));
// Get the received data
/* Get the received data */
data = spi_i2s_data_receive(spi_periph);
if(recv_ptr != RT_NULL)
@@ -351,14 +370,14 @@ static rt_ssize_t spixfer(struct rt_spi_device* device, struct rt_spi_message* m
data = *send_ptr++;
}
//Wait until the transmit buffer is empty
/* Wait until the transmit buffer is empty */
while(RESET == spi_i2s_flag_get(spi_periph, SPI_FLAG_TBE));
// Send the byte
/* Send the byte */
spi_i2s_data_transmit(spi_periph, data);
//Wait until a data is received
/* Wait until a data is received */
while(RESET == spi_i2s_flag_get(spi_periph, SPI_FLAG_RBNE));
// Get the received data
/* Get the received data */
data = spi_i2s_data_receive(spi_periph);
if(recv_ptr != RT_NULL)
@@ -438,3 +457,4 @@ INIT_BOARD_EXPORT(rt_hw_spi_init);
#endif /* BSP_USING_SPI0 || BSP_USING_SPI1 || BSP_USING_SPI2 || BSP_USING_SPI3 || BSP_USING_SPI4*/
#endif /* RT_USING_SPI */

View File

@@ -1,5 +1,5 @@
/*
* Copyright (c) 2006-2022, RT-Thread Development Team
* Copyright (c) 2006-2025, RT-Thread Development Team
*
* SPDX-License-Identifier: Apache-2.0
*
@@ -34,7 +34,7 @@ struct gd32_spi
rcu_periph_enum gpio_clk;
struct rt_spi_bus *spi_bus;
uint32_t spi_port;
#if defined SOC_SERIES_GD32F4xx
#if defined SOC_SERIES_GD32F4xx || defined SOC_SERIES_GD32E23x
uint32_t alt_func_num;
#endif
uint16_t sck_pin;
@@ -49,3 +49,4 @@ rt_err_t rt_hw_spi_device_attach(const char *bus_name, const char *device_name,
#endif
#endif /* __DRV_SPI_H__ */

View File

@@ -1,5 +1,5 @@
/*
* Copyright (c) 2006-2022, RT-Thread Development Team
* Copyright (c) 2006-2025, RT-Thread Development Team
*
* SPDX-License-Identifier: Apache-2.0
*
@@ -154,27 +154,31 @@ void UART7_IRQHandler(void)
static const struct gd32_uart uart_obj[] = {
#ifdef BSP_USING_UART0
{
USART0, // uart peripheral index
USART0_IRQn, // uart iqrn
RCU_USART0, // uart periph clock
USART0, /* uart peripheral index */
USART0_IRQn, /* uart iqrn */
RCU_USART0, /* uart periph clock */
#if defined SOC_SERIES_GD32F4xx || defined SOC_SERIES_GD32F5xx
RCU_GPIOA, RCU_GPIOA, // tx gpio clock, rx gpio clock
GPIOA, GPIO_AF_7, GPIO_PIN_9, // tx port, tx alternate, tx pin
GPIOA, GPIO_AF_7, GPIO_PIN_10, // rx port, rx alternate, rx pin
RCU_GPIOA, RCU_GPIOA, /* tx gpio clock, rx gpio clock */
GPIOA, GPIO_AF_7, GPIO_PIN_9, /* tx port, tx alternate, tx pin */
GPIOA, GPIO_AF_7, GPIO_PIN_10, /* rx port, rx alternate, rx pin */
#elif defined SOC_SERIES_GD32H7xx
RCU_GPIOF, // periph clock, tx gpio clock
RCU_GPIOF, // periph clock, rx gpio clock
GPIOF, GPIO_AF_4, GPIO_PIN_4, // tx port, tx alternate, tx pin
GPIOF, GPIO_AF_4, GPIO_PIN_5, // rx port, rx alternate, rx pin
RCU_GPIOF, /* periph clock, tx gpio clock */
RCU_GPIOF, /* periph clock, rx gpio clock */
GPIOF, GPIO_AF_4, GPIO_PIN_4, /* tx port, tx alternate, tx pin */
GPIOF, GPIO_AF_4, GPIO_PIN_5, /* rx port, rx alternate, rx pin */
#elif defined SOC_SERIES_GD32E50x
RCU_GPIOA, RCU_GPIOA, // tx gpio clock, rx gpio clock
GPIOA, 0, GPIO_PIN_9, // tx port, tx alternate, tx pin
GPIOA, 0, GPIO_PIN_10, // rx port, rx alternate, rx pin
0, // afio remap cfg
RCU_GPIOA, RCU_GPIOA, /* tx gpio clock, rx gpio clock */
GPIOA, 0, GPIO_PIN_9, /* tx port, tx alternate, tx pin */
GPIOA, 0, GPIO_PIN_10, /* rx port, rx alternate, rx pin */
0, /* afio remap cfg */
#elif defined SOC_SERIES_GD32E23x
RCU_GPIOA, RCU_GPIOA,
GPIOA, GPIO_AF_1, GPIO_PIN_9,
GPIOA, GPIO_AF_1, GPIO_PIN_10,
#else
RCU_GPIOA, RCU_GPIOA, // tx gpio clock, rx gpio clock
GPIOA, GPIO_PIN_9, // tx port, tx pin
GPIOA, GPIO_PIN_10, // rx port, rx pin
RCU_GPIOA, RCU_GPIOA, /* tx gpio clock, rx gpio clock */
GPIOA, GPIO_PIN_9, /* tx port, tx pin */
GPIOA, GPIO_PIN_10, /* rx port, rx pin */
#endif
&serial0,
"uart0",
@@ -183,22 +187,26 @@ static const struct gd32_uart uart_obj[] = {
#ifdef BSP_USING_UART1
{
USART1, // uart peripheral index
USART1_IRQn, // uart iqrn
RCU_USART1, // uart periph clock
USART1, /* uart peripheral index */
USART1_IRQn, /* uart iqrn */
RCU_USART1, /* uart periph clock */
#if defined SOC_SERIES_GD32F4xx || defined SOC_SERIES_GD32H7xx || defined SOC_SERIES_GD32F5xx
RCU_GPIOA, RCU_GPIOA, // tx gpio clock, rx gpio clock
GPIOA, GPIO_AF_7, GPIO_PIN_2, // tx port, tx alternate, tx pin
GPIOA, GPIO_AF_7, GPIO_PIN_3, // rx port, rx alternate, rx pin
RCU_GPIOA, RCU_GPIOA, /* tx gpio clock, rx gpio clock */
GPIOA, GPIO_AF_7, GPIO_PIN_2, /* tx port, tx alternate, tx pin */
GPIOA, GPIO_AF_7, GPIO_PIN_3, /* rx port, rx alternate, rx pin */
#elif defined SOC_SERIES_GD32E50x
RCU_GPIOA, RCU_GPIOA, // tx gpio clock, rx gpio clock
GPIOA, 0, GPIO_PIN_2, // tx port, tx alternate, tx pin
GPIOA, 0, GPIO_PIN_3, // rx port, rx alternate, rx pin
0, // afio remap cfg
RCU_GPIOA, RCU_GPIOA, /* tx gpio clock, rx gpio clock */
GPIOA, 0, GPIO_PIN_2, /* tx port, tx alternate, tx pin */
GPIOA, 0, GPIO_PIN_3, /* rx port, rx alternate, rx pin */
0, /* afio remap cfg */
#elif defined SOC_SERIES_GD32E23x
RCU_GPIOA, RCU_GPIOA,
GPIOA, GPIO_AF_1, GPIO_PIN_14,
GPIOA, GPIO_AF_1, GPIO_PIN_15,
#else
RCU_GPIOA, RCU_GPIOA, // periph clock, tx gpio clock, rt gpio clock
GPIOA, GPIO_PIN_2, // tx port, tx pin
GPIOA, GPIO_PIN_3, // rx port, rx pin
RCU_GPIOA, RCU_GPIOA, /* periph clock, tx gpio clock, rt gpio clock */
GPIOA, GPIO_PIN_2, /* tx port, tx pin */
GPIOA, GPIO_PIN_3, /* rx port, rx pin */
#endif
&serial1,
"uart1",
@@ -207,22 +215,22 @@ static const struct gd32_uart uart_obj[] = {
#ifdef BSP_USING_UART2
{
USART2, // uart peripheral index
USART2_IRQn, // uart iqrn
RCU_USART2, // uart periph clock
USART2, /* uart peripheral index */
USART2_IRQn, /* uart iqrn */
RCU_USART2, /* uart periph clock */
#if defined SOC_SERIES_GD32F4xx || defined SOC_SERIES_GD32H7xx || defined SOC_SERIES_GD32F5xx
RCU_GPIOB, RCU_GPIOB, // tx gpio clock, rt gpio clock
GPIOB, GPIO_AF_7, GPIO_PIN_10, // tx port, tx alternate, tx pin
GPIOB, GPIO_AF_7, GPIO_PIN_11, // rx port, rx alternate, rx pin
RCU_GPIOB, RCU_GPIOB, /* tx gpio clock, rt gpio clock */
GPIOB, GPIO_AF_7, GPIO_PIN_10, /* tx port, tx alternate, tx pin */
GPIOB, GPIO_AF_7, GPIO_PIN_11, /* rx port, rx alternate, rx pin */
#elif defined SOC_SERIES_GD32E50x
RCU_GPIOB, RCU_GPIOB, // tx gpio clock, rx gpio clock
GPIOB, 0, GPIO_PIN_10, // tx port, tx alternate, tx pin
GPIOB, 0, GPIO_PIN_11, // rx port, rx alternate, rx pin
0, // afio remap cfg
RCU_GPIOB, RCU_GPIOB, /* tx gpio clock, rx gpio clock */
GPIOB, 0, GPIO_PIN_10, /* tx port, tx alternate, tx pin */
GPIOB, 0, GPIO_PIN_11, /* rx port, rx alternate, rx pin */
0, /* afio remap cfg */
#else
RCU_GPIOB, RCU_GPIOB, // tx gpio clock, rt gpio clock
GPIOB, GPIO_PIN_10, // tx port, tx pin
GPIOB, GPIO_PIN_11, // rx port, rx pin
RCU_GPIOB, RCU_GPIOB, /* tx gpio clock, rt gpio clock */
GPIOB, GPIO_PIN_10, /* tx port, tx pin */
GPIOB, GPIO_PIN_11, /* rx port, rx pin */
#endif
&serial2,
"uart2",
@@ -231,22 +239,22 @@ static const struct gd32_uart uart_obj[] = {
#ifdef BSP_USING_UART3
{
UART3, // uart peripheral index
UART3_IRQn, // uart iqrn
RCU_UART3, // uart periph clock
UART3, /* uart peripheral index */
UART3_IRQn, /* uart iqrn */
RCU_UART3, /* uart periph clock */
#if defined SOC_SERIES_GD32F4xx || defined SOC_SERIES_GD32F5xx
RCU_GPIOC, RCU_GPIOC, // tx gpio clock, rt gpio clock
GPIOC, GPIO_AF_8, GPIO_PIN_10, // tx port, tx alternate, tx pin
GPIOC, GPIO_AF_8, GPIO_PIN_11, // rx port, rx alternate, rx pin
RCU_GPIOC, RCU_GPIOC, /* tx gpio clock, rt gpio clock */
GPIOC, GPIO_AF_8, GPIO_PIN_10, /* tx port, tx alternate, tx pin */
GPIOC, GPIO_AF_8, GPIO_PIN_11, /* rx port, rx alternate, rx pin */
#elif defined SOC_SERIES_GD32E50x
RCU_GPIOC, RCU_GPIOC, // tx gpio clock, rx gpio clock
GPIOC, 0, GPIO_PIN_10, // tx port, tx alternate, tx pin
GPIOC, 0, GPIO_PIN_11, // rx port, rx alternate, rx pin
0, // afio remap cfg
RCU_GPIOC, RCU_GPIOC, /* tx gpio clock, rx gpio clock */
GPIOC, 0, GPIO_PIN_10, /* tx port, tx alternate, tx pin */
GPIOC, 0, GPIO_PIN_11, /* rx port, rx alternate, rx pin */
0, /* afio remap cfg */
#else
RCU_GPIOC, RCU_GPIOC, // periph clock, tx gpio clock, rt gpio clock
GPIOC, GPIO_PIN_10, // tx port, tx pin
GPIOC, GPIO_PIN_11, // rx port, rx pin
RCU_GPIOC, RCU_GPIOC, /* periph clock, tx gpio clock, rt gpio clock */
GPIOC, GPIO_PIN_10, /* tx port, tx pin */
GPIOC, GPIO_PIN_11, /* rx port, rx pin */
#endif
&serial3,
"uart3",
@@ -255,19 +263,19 @@ static const struct gd32_uart uart_obj[] = {
#ifdef BSP_USING_UART4
{
UART4, // uart peripheral index
UART4_IRQn, // uart iqrn
RCU_UART4, RCU_GPIOC, RCU_GPIOD, // periph clock, tx gpio clock, rt gpio clock
UART4, /* uart peripheral index */
UART4_IRQn, /* uart iqrn */
RCU_UART4, RCU_GPIOC, RCU_GPIOD, /* periph clock, tx gpio clock, rt gpio clock */
#if defined SOC_SERIES_GD32F4xx || defined SOC_SERIES_GD32F5xx
GPIOC, GPIO_AF_8, GPIO_PIN_12, // tx port, tx alternate, tx pin
GPIOD, GPIO_AF_8, GPIO_PIN_2, // rx port, rx alternate, rx pin
GPIOC, GPIO_AF_8, GPIO_PIN_12, /* tx port, tx alternate, tx pin */
GPIOD, GPIO_AF_8, GPIO_PIN_2, /* rx port, rx alternate, rx pin */
#elif defined SOC_SERIES_GD32E50x
GPIOC, 0, GPIO_PIN_12, // tx port, tx alternate, tx pin
GPIOD, 0, GPIO_PIN_2, // rx port, rx alternate, rx pin
0, // afio remap cfg
GPIOC, 0, GPIO_PIN_12, /* tx port, tx alternate, tx pin */
GPIOD, 0, GPIO_PIN_2, /* rx port, rx alternate, rx pin */
0, /* afio remap cfg */
#else
GPIOC, GPIO_PIN_12, // tx port, tx pin
GPIOD, GPIO_PIN_2, // rx port, rx pin
GPIOC, GPIO_PIN_12, /* tx port, tx pin */
GPIOD, GPIO_PIN_2, /* rx port, rx pin */
#endif
&serial4,
"uart4",
@@ -276,19 +284,19 @@ static const struct gd32_uart uart_obj[] = {
#ifdef BSP_USING_UART5
{
USART5, // uart peripheral index
USART5_IRQn, // uart iqrn
RCU_USART5, RCU_GPIOC, RCU_GPIOC, // periph clock, tx gpio clock, rt gpio clock
USART5, /* uart peripheral index */
USART5_IRQn, /* uart iqrn */
RCU_USART5, RCU_GPIOC, RCU_GPIOC, /* periph clock, tx gpio clock, rt gpio clock */
#if defined SOC_SERIES_GD32F4xx || defined SOC_SERIES_GD32F5xx
GPIOC, GPIO_AF_8, GPIO_PIN_6, // tx port, tx alternate, tx pin
GPIOC, GPIO_AF_8, GPIO_PIN_7, // rx port, rx alternate, rx pin
GPIOC, GPIO_AF_8, GPIO_PIN_6, /* tx port, tx alternate, tx pin */
GPIOC, GPIO_AF_8, GPIO_PIN_7, /* rx port, rx alternate, rx pin */
#elif defined SOC_SERIES_GD32E50x
GPIOC, AFIO_PC6_USART5_CFG, GPIO_PIN_6, // tx port, tx alternate, tx pin
GPIOC, AFIO_PC7_USART5_CFG, GPIO_PIN_7, // rx port, rx alternate, rx pin
0, // afio remap cfg
GPIOC, AFIO_PC6_USART5_CFG, GPIO_PIN_6, /* tx port, tx alternate, tx pin */
GPIOC, AFIO_PC7_USART5_CFG, GPIO_PIN_7, /* rx port, rx alternate, rx pin */
0, /* afio remap cfg */
#else
GPIOC, GPIO_PIN_6, // tx port, tx pin
GPIOC, GPIO_PIN_7, // rx port, rx pin
GPIOC, GPIO_PIN_6, /* tx port, tx pin */
GPIOC, GPIO_PIN_7, /* rx port, rx pin */
#endif
&serial5,
"uart5",
@@ -297,15 +305,15 @@ static const struct gd32_uart uart_obj[] = {
#ifdef BSP_USING_UART6
{
UART6, // uart peripheral index
UART6_IRQn, // uart iqrn
RCU_UART6, RCU_GPIOE, RCU_GPIOE, // periph clock, tx gpio clock, rt gpio clock
UART6, /* uart peripheral index */
UART6_IRQn, /* uart iqrn */
RCU_UART6, RCU_GPIOE, RCU_GPIOE, /* periph clock, tx gpio clock, rt gpio clock */
#if defined SOC_SERIES_GD32F4xx || defined SOC_SERIES_GD32F5xx
GPIOE, GPIO_AF_8, GPIO_PIN_7, // tx port, tx alternate, tx pin
GPIOE, GPIO_AF_8, GPIO_PIN_8, // rx port, rx alternate, rx pin
GPIOE, GPIO_AF_8, GPIO_PIN_7, /* tx port, tx alternate, tx pin */
GPIOE, GPIO_AF_8, GPIO_PIN_8, /* rx port, rx alternate, rx pin */
#else
GPIOE, GPIO_PIN_7, // tx port, tx pin
GPIOE, GPIO_PIN_8, // rx port, rx pin
GPIOE, GPIO_PIN_7, /* tx port, tx pin */
GPIOE, GPIO_PIN_8, /* rx port, rx pin */
#endif
&serial6,
"uart6",
@@ -314,15 +322,15 @@ static const struct gd32_uart uart_obj[] = {
#ifdef BSP_USING_UART7
{
UART7, // uart peripheral index
UART7_IRQn, // uart iqrn
RCU_UART7, RCU_GPIOE, RCU_GPIOE, // periph clock, tx gpio clock, rt gpio clock
UART7, /* uart peripheral index */
UART7_IRQn, /* uart iqrn */
RCU_UART7, RCU_GPIOE, RCU_GPIOE, /* periph clock, tx gpio clock, rt gpio clock */
#if defined SOC_SERIES_GD32F4xx || defined SOC_SERIES_GD32F5xx
GPIOE, GPIO_AF_8, GPIO_PIN_0, // tx port, tx alternate, tx pin
GPIOE, GPIO_AF_8, GPIO_PIN_1, // rx port, rx alternate, rx pin
GPIOE, GPIO_AF_8, GPIO_PIN_0, /* tx port, tx alternate, tx pin */
GPIOE, GPIO_AF_8, GPIO_PIN_1, /* rx port, rx alternate, rx pin */
#else
GPIOE, GPIO_PIN_0, // tx port, tx pin
GPIOE, GPIO_PIN_1, // rx port, rx pin
GPIOE, GPIO_PIN_0, /* tx port, tx pin */
GPIOE, GPIO_PIN_1, /* rx port, rx pin */
#endif
&serial7,
"uart7",
@@ -347,7 +355,7 @@ void gd32_uart_gpio_init(struct gd32_uart *uart)
rcu_periph_clock_enable(uart->rx_gpio_clk);
rcu_periph_clock_enable(uart->per_clk);
#if defined SOC_SERIES_GD32F4xx || defined SOC_SERIES_GD32F5xx
#if defined SOC_SERIES_GD32F4xx || defined SOC_SERIES_GD32F5xx || defined SOC_SERIES_GD32E23x
/* connect port to USARTx_Tx */
gpio_af_set(uart->tx_port, uart->tx_af, uart->tx_pin);
@@ -598,3 +606,4 @@ int rt_hw_usart_init(void)
}
#endif

View File

@@ -1,5 +1,5 @@
/*
* Copyright (c) 2006-2022, RT-Thread Development Team
* Copyright (c) 2006-2025, RT-Thread Development Team
*
* SPDX-License-Identifier: Apache-2.0
*
@@ -24,30 +24,30 @@ extern "C" {
/* GD32 uart driver */
// Todo: compress uart info
/* Todo: compress uart info */
struct gd32_uart
{
uint32_t uart_periph; //Todo: 3bits
IRQn_Type irqn; //Todo: 7bits
rcu_periph_enum per_clk; //Todo: 5bits
rcu_periph_enum tx_gpio_clk; //Todo: 5bits
rcu_periph_enum rx_gpio_clk; //Todo: 5bits
uint32_t tx_port; //Todo: 4bits
#if defined SOC_SERIES_GD32F4xx || defined SOC_SERIES_GD32H7xx || defined SOC_SERIES_GD32F5xx
uint16_t tx_af; //Todo: 4bits
uint32_t uart_periph; /* Todo: 3bits */
IRQn_Type irqn; /* Todo: 7bits */
rcu_periph_enum per_clk; /* Todo: 5bits */
rcu_periph_enum tx_gpio_clk; /* Todo: 5bits */
rcu_periph_enum rx_gpio_clk; /* Todo: 5bits */
uint32_t tx_port; /* Todo: 4bits */
#if defined SOC_SERIES_GD32F4xx || defined SOC_SERIES_GD32H7xx || defined SOC_SERIES_GD32F5xx || defined SOC_SERIES_GD32E23x
uint16_t tx_af; /* Todo: 4bits */
#elif defined SOC_SERIES_GD32E50x
uint32_t tx_af; //alternate1 cfg
uint32_t tx_af; /* alternate1 cfg */
#endif
uint16_t tx_pin; //Todo: 4bits
uint32_t rx_port; //Todo: 4bits
#if defined SOC_SERIES_GD32F4xx || defined SOC_SERIES_GD32H7xx || defined SOC_SERIES_GD32F5xx
uint16_t rx_af; //Todo: 4bits
uint16_t tx_pin; /* Todo: 4bits */
uint32_t rx_port; /* Todo: 4bits */
#if defined SOC_SERIES_GD32F4xx || defined SOC_SERIES_GD32H7xx || defined SOC_SERIES_GD32F5xx || defined SOC_SERIES_GD32E23x
uint16_t rx_af; /* Todo: 4bits */
#elif defined SOC_SERIES_GD32E50x
uint32_t rx_af; //alternate1 cfg
uint32_t rx_af; /* alternate1 cfg */
#endif
uint16_t rx_pin; //Todo: 4bits
uint16_t rx_pin; /* Todo: 4bits */
#if defined SOC_SERIES_GD32E50x
uint32_t uart_remap; //remap
uint32_t uart_remap; /* remap */
#endif
struct rt_serial_device * serial;
@@ -61,3 +61,4 @@ int rt_hw_usart_init(void);
#endif
#endif /* __DRV_USART_H__ */

View File

@@ -1,5 +1,5 @@
/*
* Copyright (c) 2006-2024, RT-Thread Development Team
* Copyright (c) 2006-2025, RT-Thread Development Team
*
* SPDX-License-Identifier: Apache-2.0
*
@@ -53,21 +53,34 @@ static struct gd32_uart uart_obj[] = {
#ifdef BSP_USING_UART0
{
"uart0",
USART0, // uart peripheral index
USART0_IRQn, // uart iqrn
RCU_USART0, RCU_GPIOA, RCU_GPIOA, // periph clock, tx gpio clock, rt gpio clock
USART0, /* uart peripheral index */
USART0_IRQn, /* uart iqrn */
RCU_USART0, RCU_GPIOA, RCU_GPIOA, /* periph clock, tx gpio clock, rt gpio clock */
#if defined SOC_SERIES_GD32F4xx || defined SOC_SERIES_GD32F5xx
GPIOA, GPIO_AF_7, GPIO_PIN_9, // tx port, tx alternate, tx pin
GPIOA, GPIO_AF_7, GPIO_PIN_10, // rx port, rx alternate, rx pin
GPIOA, GPIO_AF_7, GPIO_PIN_9, /* tx port, tx alternate, tx pin */
GPIOA, GPIO_AF_7, GPIO_PIN_10, /* rx port, rx alternate, rx pin */
#elif defined SOC_SERIES_GD32E23x
GPIOA, GPIO_AF_1, GPIO_PIN_9,
GPIOA, GPIO_AF_1, GPIO_PIN_10,
#else
GPIOA, GPIO_PIN_9, // tx port, tx pin
GPIOA, GPIO_PIN_10, // rx port, rx pin
GPIOA, GPIO_PIN_9, /* tx port, tx pin */
GPIOA, GPIO_PIN_10, /* rx port, rx pin */
#endif
#if defined SOC_SERIES_GD32E23x
#ifdef BSP_UART0_RX_USING_DMA
.dma.rx = DRV_DMA_CONFIG(2),
#endif
#ifdef BSP_UART0_TX_USING_DMA
.dma.tx = DRV_DMA_CONFIG(1),
#endif
#else
#ifdef BSP_UART0_RX_USING_DMA
.dma.rx = DRV_DMA_CONFIG(1, 5, 4),
#endif
#ifdef BSP_UART0_TX_USING_DMA
.dma.tx = DRV_DMA_CONFIG(1, 7, 4),
#endif
#endif
},
#endif
@@ -75,21 +88,33 @@ static struct gd32_uart uart_obj[] = {
#ifdef BSP_USING_UART1
{
"uart1",
USART1, // uart peripheral index
USART1_IRQn, // uart iqrn
RCU_USART1, RCU_GPIOA, RCU_GPIOA, // periph clock, tx gpio clock, rt gpio clock
USART1, /* uart peripheral index */
USART1_IRQn, /* uart iqrn */
RCU_USART1, RCU_GPIOA, RCU_GPIOA, /* periph clock, tx gpio clock, rt gpio clock */
#if defined SOC_SERIES_GD32F4xx || defined SOC_SERIES_GD32F5xx
GPIOA, GPIO_AF_7, GPIO_PIN_2, // tx port, tx alternate, tx pin
GPIOA, GPIO_AF_7, GPIO_PIN_3, // rx port, rx alternate, rx pin
GPIOA, GPIO_AF_7, GPIO_PIN_2, /* tx port, tx alternate, tx pin */
GPIOA, GPIO_AF_7, GPIO_PIN_3, /* rx port, rx alternate, rx pin */
#elif defined SOC_SERIES_GD32E23x
GPIOA, GPIO_AF_1, GPIO_PIN_14,
GPIOA, GPIO_AF_1, GPIO_PIN_15,
#else
GPIOA, GPIO_PIN_2, // tx port, tx pin
GPIOA, GPIO_PIN_3, // rx port, rx pin
GPIOA, GPIO_PIN_2, /* tx port, tx pin */
GPIOA, GPIO_PIN_3, /* rx port, rx pin */
#endif
#if defined SOC_SERIES_GD32E23x
#ifdef BSP_UART1_RX_USING_DMA
.dma.rx = DRV_DMA_CONFIG(4),
#endif
#ifdef BSP_UART1_TX_USING_DMA
.dma.tx = DRV_DMA_CONFIG(3),
#endif
#else
#ifdef BSP_UART1_RX_USING_DMA
.dma.rx = DRV_DMA_CONFIG(0, 5, 4),
#endif
#ifdef BSP_UART1_TX_USING_DMA
.dma.tx = DRV_DMA_CONFIG(0, 6, 4),
#endif
#endif
},
#endif
@@ -97,15 +122,15 @@ static struct gd32_uart uart_obj[] = {
#ifdef BSP_USING_UART2
{
"uart2",
USART2, // uart peripheral index
USART2_IRQn, // uart iqrn
RCU_USART2, RCU_GPIOB, RCU_GPIOB, // periph clock, tx gpio clock, rt gpio clock
USART2, /* uart peripheral index */
USART2_IRQn, /* uart iqrn */
RCU_USART2, RCU_GPIOB, RCU_GPIOB, /* periph clock, tx gpio clock, rt gpio clock */
#if defined SOC_SERIES_GD32F4xx || defined SOC_SERIES_GD32F5xx
GPIOB, GPIO_AF_7, GPIO_PIN_10, // tx port, tx alternate, tx pin
GPIOB, GPIO_AF_7, GPIO_PIN_11, // rx port, rx alternate, rx pin
GPIOB, GPIO_AF_7, GPIO_PIN_10, /* tx port, tx alternate, tx pin */
GPIOB, GPIO_AF_7, GPIO_PIN_11, /* rx port, rx alternate, rx pin */
#else
GPIOB, GPIO_PIN_10, // tx port, tx pin
GPIOB, GPIO_PIN_11, // rx port, rx pin
GPIOB, GPIO_PIN_10, /* tx port, tx pin */
GPIOB, GPIO_PIN_11, /* rx port, rx pin */
#endif
#ifdef BSP_UART2_RX_USING_DMA
.dma.rx = DRV_DMA_CONFIG(0, 1, 4),
@@ -119,15 +144,15 @@ static struct gd32_uart uart_obj[] = {
#ifdef BSP_USING_UART3
{
"uart3",
UART3, // uart peripheral index
UART3_IRQn, // uart iqrn
RCU_UART3, RCU_GPIOC, RCU_GPIOC, // periph clock, tx gpio clock, rt gpio clock
UART3, /* uart peripheral index */
UART3_IRQn, /* uart iqrn */
RCU_UART3, RCU_GPIOC, RCU_GPIOC, /* periph clock, tx gpio clock, rt gpio clock */
#if defined SOC_SERIES_GD32F4xx || defined SOC_SERIES_GD32F5xx
GPIOC, GPIO_AF_8, GPIO_PIN_10, // tx port, tx alternate, tx pin
GPIOC, GPIO_AF_8, GPIO_PIN_11, // rx port, rx alternate, rx pin
GPIOC, GPIO_AF_8, GPIO_PIN_10, /* tx port, tx alternate, tx pin */
GPIOC, GPIO_AF_8, GPIO_PIN_11, /* rx port, rx alternate, rx pin */
#else
GPIOC, GPIO_PIN_10, // tx port, tx pin
GPIOC, GPIO_PIN_11, // rx port, rx pin
GPIOC, GPIO_PIN_10, /* tx port, tx pin */
GPIOC, GPIO_PIN_11, /* rx port, rx pin */
#endif
#ifdef BSP_UART3_RX_USING_DMA
.dma.rx = DRV_DMA_CONFIG(0, 2, 4),
@@ -141,15 +166,15 @@ static struct gd32_uart uart_obj[] = {
#ifdef BSP_USING_UART4
{
"uart4",
UART4, // uart peripheral index
UART4_IRQn, // uart iqrn
RCU_UART4, RCU_GPIOC, RCU_GPIOD, // periph clock, tx gpio clock, rt gpio clock
UART4, /* uart peripheral index */
UART4_IRQn, /* uart iqrn */
RCU_UART4, RCU_GPIOC, RCU_GPIOD, /* periph clock, tx gpio clock, rt gpio clock */
#if defined SOC_SERIES_GD32F4xx || defined SOC_SERIES_GD32F5xx
GPIOC, GPIO_AF_8, GPIO_PIN_12, // tx port, tx alternate, tx pin
GPIOD, GPIO_AF_8, GPIO_PIN_2, // rx port, rx alternate, rx pin
GPIOC, GPIO_AF_8, GPIO_PIN_12, /* tx port, tx alternate, tx pin */
GPIOD, GPIO_AF_8, GPIO_PIN_2, /* rx port, rx alternate, rx pin */
#else
GPIOC, GPIO_PIN_12, // tx port, tx pin
GPIOD, GPIO_PIN_2, // rx port, rx pin
GPIOC, GPIO_PIN_12, /* tx port, tx pin */
GPIOD, GPIO_PIN_2, /* rx port, rx pin */
#endif
#ifdef BSP_UART4_RX_USING_DMA
.dma.rx = DRV_DMA_CONFIG(0, 0, 4),
@@ -163,15 +188,15 @@ static struct gd32_uart uart_obj[] = {
#ifdef BSP_USING_UART5
{
"uart5",
USART5, // uart peripheral index
USART5_IRQn, // uart iqrn
RCU_USART5, RCU_GPIOC, RCU_GPIOC, // periph clock, tx gpio clock, rt gpio clock
USART5, /* uart peripheral index */
USART5_IRQn, /* uart iqrn */
RCU_USART5, RCU_GPIOC, RCU_GPIOC, /* periph clock, tx gpio clock, rt gpio clock */
#if defined SOC_SERIES_GD32F4xx || defined SOC_SERIES_GD32F5xx
GPIOC, GPIO_AF_8, GPIO_PIN_6, // tx port, tx alternate, tx pin
GPIOC, GPIO_AF_8, GPIO_PIN_7, // rx port, rx alternate, rx pin
GPIOC, GPIO_AF_8, GPIO_PIN_6, /* tx port, tx alternate, tx pin */
GPIOC, GPIO_AF_8, GPIO_PIN_7, /* rx port, rx alternate, rx pin */
#else
GPIOC, GPIO_PIN_6, // tx port, tx pin
GPIOC, GPIO_PIN_7, // rx port, rx pin
GPIOC, GPIO_PIN_6, /* tx port, tx pin */
GPIOC, GPIO_PIN_7, /* rx port, rx pin */
#endif
#ifdef BSP_UART5_RX_USING_DMA
.dma.rx = DRV_DMA_CONFIG(1, 1, 5),
@@ -185,15 +210,15 @@ static struct gd32_uart uart_obj[] = {
#ifdef BSP_USING_UART6
{
"uart6",
UART6, // uart peripheral index
UART6_IRQn, // uart iqrn
RCU_UART6, RCU_GPIOE, RCU_GPIOE, // periph clock, tx gpio clock, rt gpio clock
UART6, /* uart peripheral index */
UART6_IRQn, /* uart iqrn */
RCU_UART6, RCU_GPIOE, RCU_GPIOE, /* periph clock, tx gpio clock, rt gpio clock */
#if defined SOC_SERIES_GD32F4xx || defined SOC_SERIES_GD32F5xx
GPIOE, GPIO_AF_8, GPIO_PIN_7, // tx port, tx alternate, tx pin
GPIOE, GPIO_AF_8, GPIO_PIN_8, // rx port, rx alternate, rx pin
GPIOE, GPIO_AF_8, GPIO_PIN_7, /* tx port, tx alternate, tx pin */
GPIOE, GPIO_AF_8, GPIO_PIN_8, /* rx port, rx alternate, rx pin */
#else
GPIOE, GPIO_PIN_7, // tx port, tx pin
GPIOE, GPIO_PIN_8, // rx port, rx pin
GPIOE, GPIO_PIN_7, /* tx port, tx pin */
GPIOE, GPIO_PIN_8, /* rx port, rx pin */
#endif
#ifdef BSP_UART6_RX_USING_DMA
.dma.rx = DRV_DMA_CONFIG(0, 3, 5),
@@ -207,15 +232,15 @@ static struct gd32_uart uart_obj[] = {
#ifdef BSP_USING_UART7
{
"uart7",
UART7, // uart peripheral index
UART7_IRQn, // uart iqrn
RCU_UART7, RCU_GPIOE, RCU_GPIOE, // periph clock, tx gpio clock, rt gpio clock
UART7, /* uart peripheral index */
UART7_IRQn, /* uart iqrn */
RCU_UART7, RCU_GPIOE, RCU_GPIOE, /* periph clock, tx gpio clock, rt gpio clock */
#if defined SOC_SERIES_GD32F4xx || defined SOC_SERIES_GD32F5xx
GPIOE, GPIO_AF_8, GPIO_PIN_0, // tx port, tx alternate, tx pin
GPIOE, GPIO_AF_8, GPIO_PIN_1, // rx port, rx alternate, rx pin
GPIOE, GPIO_AF_8, GPIO_PIN_0, /* tx port, tx alternate, tx pin */
GPIOE, GPIO_AF_8, GPIO_PIN_1, /* rx port, rx alternate, rx pin */
#else
GPIOE, GPIO_PIN_0, // tx port, tx pin
GPIOE, GPIO_PIN_1, // rx port, rx pin
GPIOE, GPIO_PIN_0, /* tx port, tx pin */
GPIOE, GPIO_PIN_1, /* rx port, rx pin */
#endif
#ifdef BSP_UART7_RX_USING_DMA
.dma.rx = DRV_DMA_CONFIG(0, 6, 5),
@@ -240,7 +265,11 @@ static void dma_recv_isr (struct rt_serial_device *serial)
recv_len = 0;
level = rt_hw_interrupt_disable();
#if defined SOC_SERIES_GD32E23x
counter = dma_transfer_number_get(uart->dma.rx.channel);
#else
counter = dma_transfer_number_get(uart->dma.rx.periph, uart->dma.rx.channel);
#endif
if (counter <= uart->dma.last_index)
{
recv_len = uart->dma.last_index - counter;
@@ -377,6 +406,17 @@ static void dma_rx_isr (struct rt_serial_device *serial)
RT_ASSERT(serial != RT_NULL);
uart = rt_container_of(serial, struct gd32_uart, serial);
#if defined SOC_SERIES_GD32E23x
if ((dma_interrupt_flag_get(uart->dma.rx.channel, DMA_INT_FLAG_HTF) != RESET) ||
(dma_interrupt_flag_get(uart->dma.rx.channel, DMA_INT_FLAG_FTF) != RESET))
{
dma_recv_isr(serial);
/* clear dma flag */
dma_interrupt_flag_clear(uart->dma.rx.channel, DMA_INT_FLAG_HTF);
dma_interrupt_flag_clear(uart->dma.rx.channel, DMA_INT_FLAG_FTF);
}
#else
if ((dma_interrupt_flag_get(uart->dma.rx.periph, uart->dma.rx.channel, DMA_INT_FLAG_HTF) != RESET) ||
(dma_interrupt_flag_get(uart->dma.rx.periph, uart->dma.rx.channel, DMA_INT_FLAG_FTF) != RESET))
{
@@ -386,6 +426,7 @@ static void dma_rx_isr (struct rt_serial_device *serial)
dma_interrupt_flag_clear(uart->dma.rx.periph, uart->dma.rx.channel, DMA_INT_FLAG_HTF);
dma_interrupt_flag_clear(uart->dma.rx.periph, uart->dma.rx.channel, DMA_INT_FLAG_FTF);
}
#endif
}
#endif
@@ -405,6 +446,24 @@ static void dma_tx_isr (struct rt_serial_device *serial)
RT_ASSERT(serial != RT_NULL);
uart = rt_container_of(serial, struct gd32_uart, serial);
#if defined SOC_SERIES_GD32E23x
{
rt_size_t trans_total_index;
/* clear dma flag */
dma_interrupt_flag_clear(uart->dma.tx.channel, DMA_INT_FLAG_FTF);
/* disable dma tx channel */
dma_channel_disable(uart->dma.tx.channel);
trans_total_index = dma_transfer_number_get(uart->dma.tx.channel);
if (trans_total_index == 0)
{
rt_hw_serial_isr(serial, RT_SERIAL_EVENT_TX_DMADONE);
}
}
#else
if (dma_interrupt_flag_get(uart->dma.tx.periph, uart->dma.tx.channel, DMA_INT_FLAG_FTF) != RESET)
{
rt_size_t trans_total_index;
@@ -422,6 +481,7 @@ static void dma_tx_isr (struct rt_serial_device *serial)
rt_hw_serial_isr(serial, RT_SERIAL_EVENT_TX_DMADONE);
}
}
#endif
}
#endif
@@ -535,7 +595,35 @@ void UART7_IRQHandler (void)
}
#endif /* BSP_USING_UART7 */
#if define SOC_SERIES_GD32E23x
#if define BSP_UART0_RX_USING_DMA || define BSP_UART0_TX_USING_DMA
void DMA_Channel1_2_IRQHandler(void)
{
/* enter interrupt */
rt_interrupt_enter();
if (dma_interrupt_flag_get(DMA_CH1, DMA_INT_FLAG_FTF) != RESET)
{
dma_interrupt_flag_clear(DMA_CH1, DMA_INT_FLAG_G);
dma_tx_isr(&uart_obj[UART0_INDEX].serial);
}
if (dma_interrupt_flag_get(DMA_CH2, DMA_INT_FLAG_HTF) != RESET)
{
dma_interrupt_flag_clear(DMA_CH2, DMA_INT_FLAG_HTF);
dma_recv_isr(&uart_obj[UART0_INDEX].serial);
}
else if (dma_interrupt_flag_get(DMA_CH2, DMA_INT_FLAG_FTF) != RESET)
{
dma_interrupt_flag_clear(DMA_CH2, DMA_INT_FLAG_FTF);
dma_recv_isr(&uart_obj[UART0_INDEX].serial);
}
/* leave interrupt */
rt_interrupt_leave();
}
#endif
#else
#ifdef BSP_UART0_RX_USING_DMA
void DMA1_Channel5_IRQHandler (void)
{
@@ -549,7 +637,37 @@ void DMA1_Channel7_IRQHandler (void)
dma_tx_isr(&uart_obj[UART0_INDEX].serial);
}
#endif
#endif
#if defined SOC_SERIES_GD32E23x
#if defined BSP_UART1_RX_USING_DMA || defined BSP_UART1_TX_USING_DMA
void DMA_Channel3_4_IRQHandler(void)
{
rt_interrupt_enter();
if (dma_interrupt_flag_get(DMA_CH3, DMA_INT_FLAG_FTF) != RESET)
{
dma_interrupt_flag_clear(DMA_CH3, DMA_INT_FLAG_G);
dma_tx_isr(&uart_obj[UART1_INDEX].serial);
}
if (dma_interrupt_flag_get(DMA_CH4, DMA_INT_FLAG_HTF) != RESET)
{
dma_interrupt_flag_clear(DMA_CH4, DMA_INT_FLAG_HTF);
dma_recv_isr(&uart_obj[UART1_INDEX].serial);
}
if (dma_interrupt_flag_get(DMA_CH4, DMA_INT_FLAG_FTF) != RESET)
{
dma_interrupt_flag_clear(DMA_CH4, DMA_INT_FLAG_FTF);
dma_recv_isr(&uart_obj[UART1_INDEX].serial);
}
rt_interrupt_leave();
}
#endif
#else
#ifdef BSP_UART1_RX_USING_DMA
void DMA0_Channel5_IRQHandler (void)
{
@@ -563,6 +681,7 @@ void DMA0_Channel6_IRQHandler (void)
dma_tx_isr(&uart_obj[UART1_INDEX].serial);
}
#endif
#endif
#ifdef BSP_UART2_RX_USING_DMA
void DMA0_Channel1_IRQHandler (void)
@@ -664,7 +783,7 @@ void gd32_uart_gpio_init (struct gd32_uart *uart)
rcu_periph_clock_enable(uart->rx_gpio_clk);
rcu_periph_clock_enable(uart->per_clk);
#if defined SOC_SERIES_GD32F4xx || defined SOC_SERIES_GD32F5xx
#if defined SOC_SERIES_GD32F4xx || defined SOC_SERIES_GD32F5xx || defined SOC_SERIES_GD32E23x
/* connect port to USARTx_Tx */
gpio_af_set(uart->tx_port, uart->tx_af, uart->tx_pin);
@@ -756,9 +875,46 @@ static rt_err_t gd32_uart_configure (struct rt_serial_device *serial, struct ser
#ifdef RT_SERIAL_USING_DMA
static void _uart_dma_receive (struct gd32_uart *uart, rt_uint8_t *buffer, rt_uint32_t size)
{
dma_single_data_parameter_struct dma_init_struct = { 0 };
/* clear all the interrupt flags */
#if defined SOC_SERIES_GD32E23x
dma_flag_clear(uart->dma.rx.channel, DMA_FLAG_G);
dma_flag_clear(uart->dma.rx.channel, DMA_FLAG_FTF);
dma_flag_clear(uart->dma.rx.channel, DMA_FLAG_HTF);
dma_flag_clear(uart->dma.rx.channel, DMA_FLAG_ERR);
dma_channel_disable(uart->dma.rx.channel);
dma_deinit(uart->dma.rx.channel);
/* configure receive DMA */
rcu_periph_clock_enable(uart->dma.rx.rcu);
dma_deinit(uart->dma.rx.channel);
dma_parameter_struct dma_init_struct = { 0 };
dma_init_struct.periph_addr = (uint32_t)&USART_RDATA(uart->periph);
dma_init_struct.periph_inc = DMA_PERIPH_INCREASE_DISABLE;
dma_init_struct.memory_addr = (uint32_t)buffer;
dma_init_struct.memory_inc = DMA_MEMORY_INCREASE_ENABLE;
dma_init_struct.periph_width = DMA_PERIPHERAL_WIDTH_8BIT;
dma_init_struct.memory_width = DMA_MEMORY_WIDTH_8BIT;
dma_init_struct.direction = DMA_PERIPHERAL_TO_MEMORY;
dma_init_struct.number = size;
dma_init_struct.priority = DMA_PRIORITY_HIGH;
dma_init(uart->dma.rx.channel, &dma_init_struct);
/* enable transmit complete interrupt */
nvic_irq_enable(uart->dma.rx.irq, 2);
dma_interrupt_enable(uart->dma.rx.channel, DMA_CHXCTL_HTFIE);
dma_interrupt_enable(uart->dma.rx.channel, DMA_CHXCTL_FTFIE);
/* enable dma channel */
dma_channel_enable(uart->dma.rx.channel);
/* enable usart idle interrupt */
usart_interrupt_enable(uart->periph, USART_INT_IDLE);
/* enable dma receive */
usart_dma_receive_config(uart->periph, USART_DENR_ENABLE);
#else
dma_flag_clear(uart->dma.rx.periph, uart->dma.rx.channel, DMA_FLAG_FEE);
dma_flag_clear(uart->dma.rx.periph, uart->dma.rx.channel, DMA_FLAG_SDE);
dma_flag_clear(uart->dma.rx.periph, uart->dma.rx.channel, DMA_FLAG_TAE);
@@ -771,6 +927,8 @@ static void _uart_dma_receive (struct gd32_uart *uart, rt_uint8_t *buffer, rt_ui
rcu_periph_clock_enable(uart->dma.rx.rcu);
dma_deinit(uart->dma.rx.periph, uart->dma.rx.channel);
dma_single_data_parameter_struct dma_init_struct = { 0 };
dma_init_struct.number = size;
dma_init_struct.memory0_addr = (uint32_t)buffer;
dma_init_struct.periph_addr = (uint32_t)&USART_DATA(uart->periph);
@@ -796,10 +954,19 @@ static void _uart_dma_receive (struct gd32_uart *uart, rt_uint8_t *buffer, rt_ui
/* enable dma receive */
usart_dma_receive_config(uart->periph, USART_RECEIVE_DMA_ENABLE);
#endif
}
static void _uart_dma_transmit (struct gd32_uart *uart, rt_uint8_t *buffer, rt_uint32_t size)
{
#if defined SOC_SERIES_GD32E23x
DMA_CHMADDR(uart->dma.tx.channel) = (uint32_t)buffer;
DMA_CHCNT(uart->dma.tx.channel) = size;
usart_dma_transmit_config(uart->periph, USART_DENT_ENABLE);
dma_channel_enable(uart->dma.tx.channel);
#else
/* Set the data length and data pointer */
DMA_CHM0ADDR(uart->dma.tx.periph, uart->dma.tx.channel) = (uint32_t)buffer;
DMA_CHCNT(uart->dma.tx.periph, uart->dma.tx.channel) = size;
@@ -809,12 +976,12 @@ static void _uart_dma_transmit (struct gd32_uart *uart, rt_uint8_t *buffer, rt_u
/* enable dma channel */
dma_channel_enable(uart->dma.tx.periph, uart->dma.tx.channel);
#endif
}
static void gd32_dma_config (struct rt_serial_device *serial, rt_ubase_t flag)
{
struct gd32_uart *uart;
dma_single_data_parameter_struct dma_init_struct = { 0 };
RT_ASSERT(serial != RT_NULL);
uart = rt_container_of(serial, struct gd32_uart, serial);
@@ -824,6 +991,35 @@ static void gd32_dma_config (struct rt_serial_device *serial, rt_ubase_t flag)
/* enable rx dma */
if (flag == RT_DEVICE_FLAG_DMA_TX)
{
#if defined SOC_SERIES_GD32E23x
dma_flag_clear(uart->dma.tx.channel, DMA_FLAG_G);
dma_flag_clear(uart->dma.tx.channel, DMA_FLAG_FTF);
dma_flag_clear(uart->dma.tx.channel, DMA_FLAG_HTF);
dma_flag_clear(uart->dma.tx.channel, DMA_FLAG_ERR);
dma_channel_disable(uart->dma.tx.channel);
dma_deinit(uart->dma.tx.channel);
/* configure receive DMA */
rcu_periph_clock_enable(uart->dma.tx.rcu);
dma_deinit( uart->dma.tx.channel);
dma_parameter_struct dma_init_struct = { 0 };
dma_init_struct.periph_addr = (uint32_t)&USART_TDATA(uart->periph);
dma_init_struct.periph_inc = DMA_PERIPH_INCREASE_DISABLE;
dma_init_struct.memory_inc = DMA_MEMORY_INCREASE_ENABLE;
dma_init_struct.periph_width = DMA_PERIPHERAL_WIDTH_8BIT;
dma_init_struct.memory_width = DMA_MEMORY_WIDTH_8BIT;
dma_init_struct.direction = DMA_MEMORY_TO_PERIPHERAL;
dma_init_struct.priority = DMA_PRIORITY_HIGH;
dma_init(uart->dma.tx.channel, &dma_init_struct);
/* enable tx dma interrupt */
nvic_irq_enable(uart->dma.tx.irq, 2);
/* enable transmit complete interrupt */
dma_interrupt_enable(uart->dma.tx.channel, DMA_INT_FTF);
#else
/* clear all the interrupt flags */
dma_flag_clear(uart->dma.tx.periph, uart->dma.tx.channel, DMA_FLAG_FEE);
dma_flag_clear(uart->dma.tx.periph, uart->dma.tx.channel, DMA_FLAG_SDE);
@@ -837,6 +1033,8 @@ static void gd32_dma_config (struct rt_serial_device *serial, rt_ubase_t flag)
rcu_periph_clock_enable(uart->dma.tx.rcu);
dma_deinit(uart->dma.tx.periph, uart->dma.tx.channel);
dma_single_data_parameter_struct dma_init_struct = { 0 };
dma_init_struct.periph_addr = (uint32_t)&USART_DATA(uart->periph);
dma_init_struct.periph_memory_width = DMA_PERIPH_WIDTH_8BIT;
dma_init_struct.periph_inc = DMA_PERIPH_INCREASE_DISABLE;
@@ -852,6 +1050,7 @@ static void gd32_dma_config (struct rt_serial_device *serial, rt_ubase_t flag)
/* enable transmit complete interrupt */
dma_interrupt_enable(uart->dma.tx.periph, uart->dma.tx.channel, DMA_CHXCTL_FTFIE);
#endif
}
/* enable rx dma */
@@ -918,13 +1117,21 @@ static rt_err_t gd32_uart_control (struct rt_serial_device *serial, int cmd, voi
{
usart_interrupt_disable(uart->periph, USART_INT_RBNE);
NVIC_DisableIRQ(uart->dma.rx.irq);
#if defined SOC_SERIES_GD32E23x
dma_deinit(uart->dma.rx.channel);
#else
dma_deinit(uart->dma.rx.periph, uart->dma.rx.channel);
#endif
}
else if(ctrl_arg == RT_DEVICE_FLAG_DMA_TX)
{
usart_interrupt_disable(uart->periph, USART_INT_TBE);
NVIC_DisableIRQ(uart->dma.tx.irq);
#if defined SOC_SERIES_GD32E23x
dma_deinit(uart->dma.tx.channel);
#else
dma_deinit(uart->dma.tx.periph, uart->dma.tx.channel);
#endif
}
#endif
break;
@@ -1189,3 +1396,4 @@ int rt_hw_usart_init (void)
}
#endif

View File

@@ -1,5 +1,5 @@
/*
* Copyright (c) 2006-2024, RT-Thread Development Team
* Copyright (c) 2006-2025, RT-Thread Development Team
*
* SPDX-License-Identifier: Apache-2.0
*
@@ -32,12 +32,12 @@ struct gd32_uart
rcu_periph_enum tx_gpio_clk;
rcu_periph_enum rx_gpio_clk;
uint32_t tx_port;
#if defined SOC_SERIES_GD32F4xx
#if defined SOC_SERIES_GD32F4xx || defined SOC_SERIES_GD32E23x
uint16_t tx_af;
#endif
uint16_t tx_pin;
uint32_t rx_port;
#if defined SOC_SERIES_GD32F4xx
#if defined SOC_SERIES_GD32F4xx || defined SOC_SERIES_GD32E23x
uint16_t rx_af;
#endif
uint16_t rx_pin;
@@ -63,3 +63,4 @@ int rt_hw_usart_init(void);
#endif
#endif /* __DRV_USART_V2_H__ */

View File

@@ -27,8 +27,10 @@ def dist_do_building(BSP_ROOT, dist_dir):
print("=> copy gd32 bsp library")
library_dir = os.path.join(dist_dir, 'libraries')
library_path = os.path.join(os.path.dirname(BSP_ROOT), 'libraries')
bsp_copy_files(os.path.join(library_path, rtconfig.BSP_LIBRARY_TYPE),
os.path.join(library_dir, rtconfig.BSP_LIBRARY_TYPE))
# Only copy specific library when BSP_LIBRARY_TYPE is not None
if rtconfig.BSP_LIBRARY_TYPE is not None:
bsp_copy_files(os.path.join(library_path, rtconfig.BSP_LIBRARY_TYPE),
os.path.join(library_dir, rtconfig.BSP_LIBRARY_TYPE))
print("=> copy bsp drivers")
bsp_copy_files(os.path.join(library_path, 'gd32_drivers'), os.path.join(library_dir, 'gd32_drivers'))