diff --git a/bsp/k230/.config b/bsp/k230/.config index fe8a8a9a6e9..48d24617eec 100644 --- a/bsp/k230/.config +++ b/bsp/k230/.config @@ -114,8 +114,6 @@ CONFIG_RT_KLIBC_USING_VSNPRINTF_LOG10_TAYLOR_TERMS=4 # # CONFIG_RT_KLIBC_USING_USER_STRNLEN is not set # end of rt_strnlen options - -# CONFIG_RT_UTEST_TC_USING_KLIBC is not set # end of klibc options CONFIG_RT_NAME_MAX=16 @@ -192,7 +190,7 @@ CONFIG_RT_USING_DEVICE_OPS=y # CONFIG_RT_USING_THREADSAFE_PRINTF is not set CONFIG_RT_USING_CONSOLE=y CONFIG_RT_CONSOLEBUF_SIZE=256 -CONFIG_RT_CONSOLE_DEVICE_NAME="uart" +CONFIG_RT_CONSOLE_DEVICE_NAME="uart0" CONFIG_RT_VER_NUM=0x50201 CONFIG_RT_USING_STDC_ATOMIC=y CONFIG_RT_BACKTRACE_LEVEL_MAX_NR=32 @@ -1593,6 +1591,13 @@ CONFIG_PKG_ZLIB_VER="latest" # # CONFIG_BSP_USING_ADC is not set # CONFIG_BSP_USING_TS is not set +CONFIG_BSP_USING_UART=y +CONFIG_BSP_UART_USING_DMA=y +CONFIG_BSP_USING_UART0=y +# CONFIG_BSP_USING_UART1 is not set +# CONFIG_BSP_USING_UART2 is not set +# CONFIG_BSP_USING_UART3 is not set +# CONFIG_BSP_USING_UART4 is not set # CONFIG_BSP_USING_PWM is not set CONFIG_BSP_USING_HARDLOCK=y CONFIG_BSP_USING_SDIO=y diff --git a/bsp/k230/board/Kconfig b/bsp/k230/board/Kconfig index 4cef88069e5..4c88e5df886 100644 --- a/bsp/k230/board/Kconfig +++ b/bsp/k230/board/Kconfig @@ -10,6 +10,37 @@ menu "Drivers Configuration" select RT_USING_TS default n + menuconfig BSP_USING_UART + bool "Enable UART" + select RT_USING_UART + default y + + if BSP_USING_UART + config BSP_UART_USING_DMA + bool "Enable UART with DMA" + default y + + config BSP_USING_UART0 + bool "Enable UART0" + default y + + config BSP_USING_UART1 + bool "Enable UART1" + default n + + config BSP_USING_UART2 + bool "Enable UART2" + default n + + config BSP_USING_UART3 + bool "Enable UART3" + default n + + config BSP_USING_UART4 + bool "Enable UART4" + default n + endif + menuconfig BSP_USING_PWM bool "Enable PWM" select RT_USING_PWM diff --git a/bsp/k230/drivers/interdrv/uart/drv_uart.c b/bsp/k230/drivers/interdrv/uart/drv_uart.c index 71090417f22..db959811d17 100644 --- a/bsp/k230/drivers/interdrv/uart/drv_uart.c +++ b/bsp/k230/drivers/interdrv/uart/drv_uart.c @@ -1,24 +1,52 @@ +/* Copyright (c) 2023, Canaan Bright Sight Co., Ltd + * + * 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. + * + * 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. + */ /* - * Copyright (c) 2019-2020 + * Copyright (c) 2006-2025 RT-Thread Development Team * * SPDX-License-Identifier: Apache-2.0 - * */ #include #include #include #include - +#include #include "board.h" +#include "drv_pdma.h" +#include #include "drv_uart.h" #include "riscv_io.h" #define UART_DEFAULT_BAUDRATE 115200 #define UART_CLK 50000000 -#define UART_ADDR UART0_BASE_ADDR -#define UART_IRQ K230_IRQ_UART0 - +#define PDMA_CH_INVALID 0xFF +#define UART0_IRQ K230_IRQ_UART0 +#define UART1_IRQ K230_IRQ_UART1 +#define UART2_IRQ K230_IRQ_UART2 +#define UART3_IRQ K230_IRQ_UART3 +#define UART4_IRQ K230_IRQ_UART4 #define UART_RBR (0x00) /* receive buffer register */ #define UART_THR (0x00) /* transmit holding register */ @@ -96,24 +124,197 @@ struct device_uart void* pa_base; rt_uint32_t irqno; }; +struct k230_uart_dev +{ + struct rt_serial_device serial; + struct device_uart uart; + const char *name; + rt_uint32_t pa_base; + rt_uint32_t uart_to_size; + rt_uint32_t irqno; -static rt_err_t rt_uart_configure(struct rt_serial_device *serial, struct serial_configure *cfg); -static rt_err_t uart_control(struct rt_serial_device *serial, int cmd, void *arg); -static int drv_uart_putc(struct rt_serial_device *serial, char c); -static int drv_uart_getc(struct rt_serial_device *serial); +#ifdef BSP_UART_USING_DMA + /* DMA info */ + rt_uint8_t dma_ch; + usr_pdma_cfg_t pdma_cfg; + rt_event_t dma_event; +#endif +}; -const struct rt_uart_ops _uart_ops = +static struct k230_uart_dev uart_devs[] = { - rt_uart_configure, - uart_control, - drv_uart_putc, - drv_uart_getc, - //TODO: add DMA support - RT_NULL +#ifdef BSP_USING_UART0 + { + .name = "uart0", + .pa_base = UART0_BASE_ADDR, + .uart_to_size = UART0_IO_SIZE, + .irqno = UART0_IRQ, + }, +#endif +#ifdef BSP_USING_UART1 + { + .name = "uart1", + .pa_base = UART1_BASE_ADDR, + .uart_to_size = UART1_IO_SIZE, + .irqno = UART1_IRQ, + }, +#endif +#ifdef BSP_USING_UART2 + { + .name = "uart2", + .pa_base = UART2_BASE_ADDR, + .uart_to_size = UART2_IO_SIZE, + .irqno = UART2_IRQ, + }, +#endif +#ifdef BSP_USING_UART3 + { + .name = "uart3", + .pa_base = UART3_BASE_ADDR, + .uart_to_size = UART3_IO_SIZE, + .irqno = UART3_IRQ, + }, +#endif +#ifdef BSP_USING_UART4 + { + .name = "uart4", + .pa_base = UART4_BASE_ADDR, + .uart_to_size = UART4_IO_SIZE, + .irqno = UART4_IRQ, + }, +#endif +#if !defined(BSP_USING_UART0) && !defined(BSP_USING_UART1) && !defined(BSP_USING_UART2) && !defined(BSP_USING_UART3) && !defined(BSP_USING_UART4) +#error "No UART device defined!" +#endif }; -struct rt_serial_device serial1; -struct device_uart uart1; +static int _drv_uart_putc(struct rt_serial_device *serial, char c); + +#ifdef BSP_UART_USING_DMA +typedef enum +{ + K230_UART_PDMA_EVENT_NONE, + K230_UART_PDMA_EVENT_COMPLETE, + K230_UART_PDMA_EVENT_TIMEOUT +} uart_pdma_event_t; + +static void _k230_uart_pdma_call_back(rt_uint8_t ch, rt_bool_t is_done) +{ + uart_pdma_event_t event_type = is_done ? K230_UART_PDMA_EVENT_COMPLETE : K230_UART_PDMA_EVENT_TIMEOUT; + for (size_t i = 0; i < sizeof(uart_devs)/sizeof(uart_devs[0]); i++) + { + struct k230_uart_dev *d = &uart_devs[i]; + if (d->dma_ch != PDMA_CH_INVALID && d->dma_ch == ch && d->dma_event != RT_NULL) + { + rt_event_send(d->dma_event, event_type); + return; + } + } +} + +static rt_err_t _uart_dma_init(struct k230_uart_dev *dev) +{ + rt_err_t err; + + usr_pdma_cfg_t *cfg = &dev->pdma_cfg; + + if (!strcmp(dev->name, "uart0")) + { + cfg->device = UART0_TX; + } + else if (!strcmp(dev->name, "uart1")) + { + cfg->device = UART1_TX; + } + else if (!strcmp(dev->name, "uart2")) + { + cfg->device = UART2_TX; + } + else if (!strcmp(dev->name, "uart3")) + { + cfg->device = UART3_TX; + } + else if (!strcmp(dev->name, "uart4")) + { + cfg->device = UART4_TX; + } + + cfg->dst_addr = (rt_uint8_t *)(uintptr_t)dev->pa_base; + + cfg->pdma_ch_cfg.ch_src_type = CONTINUE; + cfg->pdma_ch_cfg.ch_dev_hsize = PSBYTE1; + cfg->pdma_ch_cfg.ch_dat_endian = PDEFAULT; + cfg->pdma_ch_cfg.ch_dev_blen = PBURST_LEN_16; + cfg->pdma_ch_cfg.ch_priority = 7; // channel priority + cfg->pdma_ch_cfg.ch_dev_tout = 0xFFF; // device timeout + + return RT_EOK; +} + +static rt_ssize_t _uart_dma_write(struct rt_serial_device *serial, const void *buffer, rt_size_t size) +{ + struct k230_uart_dev *uart_dev = rt_container_of(serial, struct k230_uart_dev, serial); + rt_uint32_t recv_event; + rt_err_t err; + rt_uint8_t ch; + + err = k230_pdma_request_channel(&ch); + if (err != RT_EOK) + { + const char *ptr = buffer; + for (rt_size_t i = 0; i < size; i++) + { + _drv_uart_putc(serial, ptr[i]); + } + return size; + } + + uint32_t len = RT_ALIGN(size, 64); + uint8_t *buf = rt_malloc_align(len, 64); + rt_memcpy(buf, buffer, size); + rt_hw_cpu_dcache_clean((void*)buf, len); + void *buf_pa = rt_kmem_v2p(buf); + uart_dev->dma_ch = ch; + + err = k230_pdma_set_callback(ch, _k230_uart_pdma_call_back); + if (err != RT_EOK) + { + k230_pdma_release_channel(ch); + rt_free_align(buf); + return err; + } + + uart_dev->pdma_cfg.src_addr = buf_pa; + uart_dev->pdma_cfg.line_size = len; + rt_event_control(uart_dev->dma_event, RT_IPC_CMD_RESET, NULL); + + err = k230_pdma_config(ch, &uart_dev->pdma_cfg); + err = k230_pdma_start(ch); + + err = rt_event_recv(uart_dev->dma_event, + K230_UART_PDMA_EVENT_COMPLETE | K230_UART_PDMA_EVENT_TIMEOUT, + RT_EVENT_FLAG_OR | RT_EVENT_FLAG_CLEAR, + RT_WAITING_FOREVER, + &recv_event); + + k230_pdma_stop(ch); + k230_pdma_release_channel(ch); + uart_dev->dma_ch = PDMA_CH_INVALID; + rt_free_align(buf); + return size; +} + +static rt_ssize_t _uart_dma_tran(struct rt_serial_device *serial, rt_uint8_t *buf, rt_size_t size, int direction) +{ + rt_ssize_t len; + if (RT_SERIAL_DMA_TX == direction) + { + len = _uart_dma_write(serial, (void*)buf, size); + } + rt_hw_serial_isr(serial, RT_SERIAL_EVENT_TX_DMADONE); + return len; +} +#endif #define write32(addr, val) writel(val, (void*)(addr)) #define read32(addr) readl((void*)(addr)) @@ -150,7 +351,8 @@ static void _uart_init(void *uart_base) write32(uart_base + UART_IER, 0x00); /* Enable DLAB */ write32(uart_base + UART_LCR, 0x80); - if (bdiv) { + if (bdiv) + { /* Set divisor low byte */ write32(uart_base + UART_DLL, dll); /* Set divisor high byte */ @@ -176,7 +378,7 @@ static void _uart_init(void *uart_base) // write32(uart_base + UART_IER, 0x01); } -static void uart_set_isr(void *uart_base, uint8_t enable, uint32_t irq_type) +static void _uart_set_isr(void *uart_base, uint8_t enable, uint32_t irq_type) { uint32_t value; @@ -193,15 +395,7 @@ static void uart_set_isr(void *uart_base, uint8_t enable, uint32_t irq_type) write32(uart_base + UART_IER, value); } -/* - * UART interface - */ -static rt_err_t rt_uart_configure(struct rt_serial_device *serial, struct serial_configure *cfg) -{ - return (RT_EOK); -} - -static rt_err_t uart_control(struct rt_serial_device *serial, int cmd, void *arg) +static rt_err_t _uart_control(struct rt_serial_device *serial, int cmd, void *arg) { struct device_uart *uart = (struct device_uart*)serial->parent.user_data; @@ -228,7 +422,7 @@ static rt_err_t uart_control(struct rt_serial_device *serial, int cmd, void *arg if ((size_t)arg == RT_DEVICE_FLAG_INT_RX) #endif { - uart_set_isr((void*)(uart->hw_base), 0, UART_IER_RDI); + _uart_set_isr((void*)(uart->hw_base), 0, UART_IER_RDI); } break; @@ -239,14 +433,14 @@ static rt_err_t uart_control(struct rt_serial_device *serial, int cmd, void *arg if ((size_t)arg == RT_DEVICE_FLAG_INT_RX) #endif { - uart_set_isr((void*)(uart->hw_base), 1, UART_IER_RDI); + _uart_set_isr((void*)(uart->hw_base), 1, UART_IER_RDI); } break; #ifdef RT_USING_SERIAL_V2 case RT_DEVICE_CTRL_CONFIG: if (ctrl_flag & RT_DEVICE_FLAG_INT_RX) { - uart_set_isr((void*)(uart->hw_base), 1, UART_IER_RDI); + _uart_set_isr((void*)(uart->hw_base), 1, UART_IER_RDI); } break; #endif @@ -270,7 +464,7 @@ static rt_err_t uart_control(struct rt_serial_device *serial, int cmd, void *arg return (RT_EOK); } -static int drv_uart_putc(struct rt_serial_device *serial, char c) +static int _drv_uart_putc(struct rt_serial_device *serial, char c) { volatile uint32_t *sed_buf; volatile uint32_t *sta; @@ -288,7 +482,7 @@ static int drv_uart_putc(struct rt_serial_device *serial, char c) return (1); } -static int drv_uart_getc(struct rt_serial_device *serial) +static int _drv_uart_getc(struct rt_serial_device *serial) { struct device_uart *uart = (struct device_uart*)serial->parent.user_data; volatile uint32_t *lsr = (uint32_t *)(uart->hw_base + UART_LSR); @@ -301,7 +495,15 @@ static int drv_uart_getc(struct rt_serial_device *serial) return (int)*rbr; } -static void rt_hw_uart_isr(int irq, void *param) +/* + * UART interface + */ +static rt_err_t _rt_uart_configure(struct rt_serial_device *serial, struct serial_configure *cfg) +{ + return (RT_EOK); +} + +static void _rt_hw_uart_isr(int irq, void *param) { struct rt_serial_device *serial = (struct rt_serial_device*)param; struct device_uart *uart; @@ -349,37 +551,78 @@ static void rt_hw_uart_isr(int irq, void *param) } } -/* - * UART Initiation - */ +const struct rt_uart_ops _uart_ops = +{ + .configure = _rt_uart_configure, + .control = _uart_control, + .putc = _drv_uart_putc, + .getc = _drv_uart_getc, +#ifdef BSP_UART_USING_DMA + .dma_transmit = _uart_dma_tran +#else + .dma_transmit = RT_NULL +#endif +}; + int rt_hw_uart_init(void) { - struct rt_serial_device *serial; - struct device_uart *uart; struct serial_configure config = RT_SERIAL_CONFIG_DEFAULT; + rt_err_t ret; + for (int i = 0; i < sizeof(uart_devs)/sizeof(uart_devs[0]); i++) { - serial = &serial1; - uart = &uart1; + struct k230_uart_dev *dev = &uart_devs[i]; - serial->ops = &_uart_ops; - serial->config = config; - serial->config.baud_rate = UART_DEFAULT_BAUDRATE; + dev->serial.ops = &_uart_ops; + dev->serial.config = config; + dev->serial.config.baud_rate = UART_DEFAULT_BAUDRATE; - uart->pa_base = (void *)UART_ADDR; - uart->hw_base = (rt_base_t)rt_ioremap(uart->pa_base, 0x1000); - uart->irqno = UART_IRQ; + dev->uart.pa_base = (void *)(uintptr_t)dev->pa_base; + dev->uart.hw_base = (rt_base_t)rt_ioremap(dev->uart.pa_base, dev->uart_to_size); + dev->uart.irqno = dev->irqno; - _uart_init((void*)(uart->hw_base)); +#ifdef BSP_UART_USING_DMA + dev->dma_ch = PDMA_CH_INVALID; + dev->dma_event = (rt_event_t)rt_malloc(sizeof(struct rt_event)); + if (dev->dma_event == RT_NULL) + { + LOG_E("Failed to allocate memory for %s pdma_event!", dev->name); + return -RT_ENOMEM; + } - rt_hw_interrupt_install(uart->irqno, rt_hw_uart_isr, serial, "uart1"); - rt_hw_interrupt_umask(uart->irqno); + ret = rt_event_init(dev->dma_event, dev->name, RT_IPC_FLAG_FIFO); + if (ret != RT_EOK) + { + LOG_E("Failed to init pdma_event for %s!", dev->name); + rt_free(dev->dma_event); + return ret; + } - rt_hw_serial_register(serial, - RT_CONSOLE_DEVICE_NAME, - RT_DEVICE_FLAG_STREAM | RT_DEVICE_FLAG_RDWR | RT_DEVICE_FLAG_INT_RX, - uart); - } + ret = _uart_dma_init(dev); + if (ret != RT_EOK) + { + LOG_E("Failed to init DMA for %s, ret=%d\n", dev->name, ret); + return ret; + } +#endif - return 0; -} + _uart_init((void*)(dev->uart.hw_base)); + + rt_hw_interrupt_install(dev->uart.irqno, _rt_hw_uart_isr, &dev->serial, dev->name); + rt_hw_interrupt_umask(dev->uart.irqno); + + rt_uint32_t flags; + flags = RT_DEVICE_FLAG_STREAM | RT_DEVICE_FLAG_RDWR | RT_DEVICE_FLAG_INT_RX | RT_DEVICE_FLAG_INT_TX; +#ifdef BSP_UART_USING_DMA + flags = RT_DEVICE_FLAG_STREAM | RT_DEVICE_FLAG_RDWR | RT_DEVICE_FLAG_INT_RX | RT_DEVICE_FLAG_DMA_TX; +#endif + + ret = rt_hw_serial_register(&dev->serial, dev->name, flags, &dev->uart); + if (ret != RT_EOK) + { + LOG_E("Failed to register %s, ret=%d\n", dev->name, ret); + return ret; + } + } + return RT_EOK; +} \ No newline at end of file diff --git a/bsp/k230/drivers/interdrv/uart/drv_uart.h b/bsp/k230/drivers/interdrv/uart/drv_uart.h index a7a18d0ddea..f3d70372797 100644 --- a/bsp/k230/drivers/interdrv/uart/drv_uart.h +++ b/bsp/k230/drivers/interdrv/uart/drv_uart.h @@ -1,15 +1,36 @@ +/* Copyright (c) 2023, Canaan Bright Sight Co., Ltd + * + * 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. + * + * 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. + */ /* - * Copyright (c) 2019-2020, Xim + * Copyright (c) 2006-2025 RT-Thread Development Team * * SPDX-License-Identifier: Apache-2.0 - * */ #ifndef __DRV_UART_H__ #define __DRV_UART_H__ -void rt_hw_uart_start_rx_thread(); int rt_hw_uart_init(void); -void drv_uart_puts(char *str); // for syscall #endif /* __DRV_UART_H__ */ diff --git a/bsp/k230/drivers/utest/SConscript b/bsp/k230/drivers/utest/SConscript index 7ceb8e74812..92ea98982fc 100644 --- a/bsp/k230/drivers/utest/SConscript +++ b/bsp/k230/drivers/utest/SConscript @@ -23,6 +23,9 @@ if GetDepend('RT_UTEST_USING_ALL_CASES') or GetDepend('BSP_UTEST_DRIVERS'): if GetDepend('BSP_USING_TS'): src += ['test_ts.c'] + + if GetDepend('BSP_USING_UART'): + src += ['test_uart.c'] group = DefineGroup('utestcases', src, depend = ['']) diff --git a/bsp/k230/drivers/utest/test_uart.c b/bsp/k230/drivers/utest/test_uart.c new file mode 100644 index 00000000000..9ab5654df71 --- /dev/null +++ b/bsp/k230/drivers/utest/test_uart.c @@ -0,0 +1,165 @@ +/* Copyright (c) 2023, Canaan Bright Sight Co., Ltd + * + * 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. + * + * 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. + */ +/* + * Copyright (c) 2006-2025 RT-Thread Development Team + * + * SPDX-License-Identifier: Apache-2.0 + */ + +#include +#include +#include +#include "drv_uart.h" +#include + +/* + * 测试 UART0 在 DMA 模式下的数据发送功能,以及 UART0 在中断模式下的数据接收功能 + * + * 功能说明: + * 1. 发送测试(uart_tx_demo): + * - 查找名为 "uart0" 的串口设备; + * - 打开设备,并配置为 DMA 发送(DMA_TX)+ 流式传输(STREAM)模式; + * - 设置串口参数: + * - 波特率:115200; + * - 数据位:8 位; + * - 停止位:1 位; + * - 校验位:无; + * - 动态分配一段 2000 字节的内存作为发送缓冲区: + * - 填充 1999 个字符 '['; + * - 最后添加 '\0' 作为字符串结尾; + * - 调用 `rt_device_write` 接口,将缓冲区数据通过 UART0 DMA 方式发送出去; + * - 发送完成后关闭 UART0 设备并释放发送缓冲区内存。 + * + * 2. 接收测试(uart_rx_demo): + * - 查找名为 "uart0" 的串口设备; + * - 打开设备,并配置为中断接收(INT_RX)+ 流式传输(STREAM)模式; + * - 设置串口参数(波特率 115200,8N1,无校验); + * - 在 5 秒超时范围内循环读取 UART0 接收到的数据: + * - 如果有数据,则立即打印接收到的内容; + * - 如果没有数据,每隔 2.5 秒检查一次; + * - 超时或接收后关闭 UART0 设备。 + * + * 硬件说明: + * - 本测试基于 K230 平台; + * - uart_tx_demo 用于发送测试,可在串口调试工具上观察 1999 个 '[' 输出; + * - uart_rx_demo 用于接收测试,在 5 秒内通过外部串口助手发送数据,可在日志中看到接收结果; + * + */ + +#define UART0_DEV_NAME "uart0" +#define TEXT_LENGTH 2000 +#define TEXT_TIME 5 +#define RX_TEXT_PERIOD 2500 + +static void uart_tx_demo(void) +{ + rt_device_t uart_dev; + char *msg = rt_malloc(TEXT_LENGTH); + for (int i = 0; i < TEXT_LENGTH - 1; i++) + { + msg[i] = '['; + } + msg[TEXT_LENGTH-1]='\0'; + + rt_err_t ret; + + uart_dev = rt_device_find(UART0_DEV_NAME); + uassert_not_null(uart_dev); + + ret = rt_device_open(uart_dev, RT_DEVICE_FLAG_DMA_TX | RT_DEVICE_FLAG_STREAM); + uassert_int_equal(ret, RT_EOK); + + struct serial_configure config = RT_SERIAL_CONFIG_DEFAULT; + config.baud_rate = 115200; + config.data_bits = DATA_BITS_8; + config.stop_bits = STOP_BITS_1; + config.parity = PARITY_NONE; + ret = rt_device_control(uart_dev, RT_DEVICE_CTRL_CONFIG, &config); + uassert_int_equal(ret, RT_EOK); + + size_t len = TEXT_LENGTH; + ret = rt_device_write(uart_dev, 0, msg, len); + uassert_int_equal(ret, len); + ret = rt_device_close(uart_dev); + uassert_int_equal(ret, RT_EOK); + rt_free(msg); +} + +static void uart_rx_demo(void) +{ + rt_device_t uart_dev; + char rx_buf[32]; + rt_size_t rx_len; + + uart_dev = rt_device_find(UART0_DEV_NAME); + uassert_not_null(uart_dev); + + rt_err_t ret = rt_device_open(uart_dev, RT_DEVICE_FLAG_INT_RX | RT_DEVICE_FLAG_STREAM); + uassert_int_equal(ret, RT_EOK); + + struct serial_configure config = RT_SERIAL_CONFIG_DEFAULT; + config.baud_rate = 115200; + config.data_bits = DATA_BITS_8; + config.stop_bits = STOP_BITS_1; + config.parity = PARITY_NONE; + ret = rt_device_control(uart_dev, RT_DEVICE_CTRL_CONFIG, &config); + uassert_int_equal(ret, RT_EOK); + + LOG_I("UART RX demo: please send data to uart0 within 5s...\n"); + + rt_tick_t timeout = rt_tick_get() + RT_TICK_PER_SECOND * TEXT_TIME; + while (rt_tick_get() < timeout) + { + rx_len = rt_device_read(uart_dev, 0, rx_buf, sizeof(rx_buf) - 1); + if (rx_len > 0) + { + rx_buf[rx_len] = '\0'; + LOG_I("UART RX got %d bytes: %s\n", rx_len, rx_buf); + break; + } + rt_thread_mdelay(RX_TEXT_PERIOD); + } + + ret = rt_device_close(uart_dev); + uassert_int_equal(ret, RT_EOK); +} + +static void uart_testcase(void) +{ + UTEST_UNIT_RUN(uart_tx_demo); + UTEST_UNIT_RUN(uart_rx_demo); +} + +static rt_err_t utest_tc_init(void) +{ + return RT_EOK; +} + +static rt_err_t utest_tc_cleanup(void) +{ + return RT_EOK; +} + +UTEST_TC_EXPORT(uart_testcase, "uart", utest_tc_init, utest_tc_cleanup, 10); \ No newline at end of file diff --git a/bsp/k230/rtconfig.h b/bsp/k230/rtconfig.h index e4b87a3d3c4..9c521884a67 100644 --- a/bsp/k230/rtconfig.h +++ b/bsp/k230/rtconfig.h @@ -119,7 +119,7 @@ #define RT_USING_DEVICE_OPS #define RT_USING_CONSOLE #define RT_CONSOLEBUF_SIZE 256 -#define RT_CONSOLE_DEVICE_NAME "uart" +#define RT_CONSOLE_DEVICE_NAME "uart0" #define RT_VER_NUM 0x50201 #define RT_USING_STDC_ATOMIC #define RT_BACKTRACE_LEVEL_MAX_NR 32 @@ -578,6 +578,9 @@ /* Drivers Configuration */ +#define BSP_USING_UART +#define BSP_UART_USING_DMA +#define BSP_USING_UART0 #define BSP_USING_HARDLOCK #define BSP_USING_SDIO #define BSP_USING_SDIO0