AI工具写的环形缓冲区

This commit is contained in:
yelvlab 2025-08-11 20:11:46 +08:00
parent c6c90800d4
commit 4a488429bf
13 changed files with 470 additions and 154 deletions

View File

@ -27,6 +27,8 @@ set(TARGET_SRC
# Add new source files here
Src/uart.c
Src/led.c
Src/uart_ring_buffer.c
Src/command.c
)
#

View File

@ -1,6 +1,11 @@
#ifndef BOARD_CONFIG_H
#define BOARD_CONFIG_H
/* >>>>>>>>>>>>>>>>>>>>[RS485 PHY DEFINE]<<<<<<<<<<<<<<<<<<<< */
// #define RS485_MAX13487 //RS485 PHY : MAX13487 (AutoDir)
#undef RS485_MAX13487 //RS485 PHY : SP3487 (no AutoDir)
/******************************************************************************/
#define LED_PORT GPIOA
@ -17,6 +22,7 @@
#define RS485_PHY USART0
#define RS485_BAUDRATE 115200U
#define RS485_EN_PIN GPIO_PIN_1
#define RS485_IRQ USART0_IRQn
/******************************************************************************/

10
Inc/command.h Normal file
View File

@ -0,0 +1,10 @@
#ifndef COMMAND_H
#define COMMAND_H
#include <stdint.h>
#include <stdbool.h>
void command_process(void);
void handle_command(const uint8_t *cmd, uint8_t len);
#endif // COMMAND_H

View File

@ -1,47 +1,27 @@
/*!
\file systick.h
\brief the header file of systick
\version 2025-02-10, V2.4.0, demo 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.
*/
/**
* ************************************************************************
*
* @file systick.h
* @author GD32
* @brief
*
* ************************************************************************
* @copyright Copyright (c) 2024 GD32
* ************************************************************************
*/
#ifndef SYS_TICK_H
#define SYS_TICK_H
#include <stdint.h>
/* function declarations */
/* configure systick */
void systick_config(void);
/* delay a time in milliseconds */
void delay_ms(uint32_t count);
/* delay decrement */
void delay_decrement(void);
#endif /* SYS_TICK_H */
/* delay a time in microseconds */
void delay_us(uint32_t count);
#endif /* SYS_TICK_H */

View File

@ -3,13 +3,15 @@
#include "gd32e23x.h"
#define RX_BUFFER_SIZE 32
typedef enum {
UART_PRINTF_USART0 = 0,
UART_PRINTF_USART1 = 1,
UART_PRINTF_BOTH = 2
} uart_printf_port_t;
void uart0_init(void);
void uart_set_printf_port(uart_printf_port_t port);
void rs485_init(void);
// void uart_set_printf_port(uart_printf_port_t port);
#endif // UART_H

14
Inc/uart_ring_buffer.h Normal file
View File

@ -0,0 +1,14 @@
#ifndef UART_RING_BUFFER_H
#define UART_RING_BUFFER_H
#include <stdint.h>
#include <stdbool.h>
#define UART_RX_BUFFER_SIZE 128
void uart_ring_buffer_init(void);
uint16_t uart_rx_available(void);
int uart_rx_get(void);
void uart_rx_put(uint8_t data);
void uart_rx_clear(void);
#endif // UART_RING_BUFFER_H

197
Src/command.c Normal file
View File

@ -0,0 +1,197 @@
#include "command.h"
#include "uart_ring_buffer.h"
#include "led.h"
#include <stdint.h>
#include <stdbool.h>
#include <stdio.h>
/*
Host -> Device
[0] HEADER = 0xD5
[1] BOARD_TYPE = 0x03
[2] LEN =
[3..(3+LEN-1)]
[last] CRC = 1 (last-1) 8
"M1" / "M2" / "M3"
Device -> Host 0xB5
[0] 0xB5, [1] TYPE( 0xF0=OK, 0xF1..=), [2] LEN, [3..] payload, [last] CRC
*/
// 旧工程中的外部状态与复位函数(本工程暂不直接使用,按要求保留为注释):
// extern bool g_statusSwitch; // 来自其他业务模块
// void fwdgt_reset_mcu(void); // 看门狗复位
#define PROTOCOL_PACKAGE_HEADER 0xD5
#define PROTOCOL_BOARD_TYPE 0x03
#define PROTOCOL_PACKAGE_LENGTH 0x02
/* 可选的应答类型定义(与示例保持一致,可按需扩展) */
#define RESP_HEADER 0xB5
#define RESP_TYPE_OK 0xF0
#define RESP_TYPE_CRC_ERR 0xF1
#define RESP_TYPE_HEADER_ERR 0xF2
#define RESP_TYPE_TYPE_ERR 0xF3
#define RESP_TYPE_LEN_ERR 0xF4
#define CMD_BUF_SIZE 64
/* 计算 CRC从索引 1 累加到 len-2不含 HEADER 与 CRC 字节) */
static uint8_t proto_sum_crc(const uint8_t *data, uint8_t len)
{
uint8_t crc = 0;
if (len < 3) return 0; // 最少应为 header + X + crc
for (uint8_t i = 1; i < (uint8_t)(len - 1); i++) {
crc += data[i];
}
return crc;
}
/* 发送应答header(0xB5), type, len, payload[len], crc */
static void send_response(uint8_t type, const uint8_t *payload, uint8_t len)
{
uint8_t buf_len = (uint8_t)(3 + len + 1);
uint8_t buf[16]; // 简单场景足够,必要时可增大
if (buf_len > sizeof(buf)) return; // 防御
buf[0] = RESP_HEADER;
buf[1] = type;
buf[2] = len;
for (uint8_t i = 0; i < len; i++) buf[3 + i] = payload ? payload[i] : 0;
buf[buf_len - 1] = proto_sum_crc(buf, buf_len);
for (uint8_t i = 0; i < buf_len; i++) {
printf("%c", buf[i]);
}
}
void handle_command(const uint8_t *cmd, uint8_t len) {
// 期望帧D5 03 02 'M' '1' CRC或 'M2'/'M3'
if (len < 6) return; // 最小长度 3+2+1
uint8_t payload_len = cmd[2];
if (payload_len < 2) return; // 我们期望 2 字节命令
char c0 = (char)cmd[3];
char c1 = (char)cmd[4];
if (c0 == 'M' && c1 == '1') {
led_on();
// g_statusSwitch = true; // 保留但注释:切换业务状态
// OK: 返回 "ok"
const uint8_t ok[] = { 'o', 'k' };
send_response(RESP_TYPE_OK, ok, sizeof(ok));
} else if (c0 == 'M' && c1 == '2') {
led_off();
// g_statusSwitch = false; // 保留但注释:切换业务状态
const uint8_t ok[] = { 'o', 'k' };
send_response(RESP_TYPE_OK, ok, sizeof(ok));
} else if (c0 == 'M' && c1 == '3') {
const uint8_t ok[] = { 'o', 'k' };
send_response(RESP_TYPE_OK, ok, sizeof(ok));
// fwdgt_reset_mcu(); // 保留但注释:触发 MCU 复位(依赖外部实现)
// 或NVIC_SystemReset();(需包含 CMSIS 头)
} else {
const uint8_t err[] = { 'e','r','r', 0x3C };
send_response(RESP_TYPE_HEADER_ERR, err, sizeof(err));
}
}
void command_process(void) {
static uint8_t cmd_buf[CMD_BUF_SIZE];
static uint8_t cmd_len = 0;
static uint8_t expected_total = 0; // 0 表示尚未确定总长度
while (uart_rx_available() > 0) {
int byte = uart_rx_get();
if (byte < 0) break;
if (cmd_len == 0) {
if ((uint8_t)byte == PROTOCOL_PACKAGE_HEADER) {
cmd_buf[cmd_len++] = (uint8_t)byte;
expected_total = 0; // 等待进一步字段以确定长度
} else {
// 丢弃非起始字节
}
continue;
}
// 累积后续字节
cmd_buf[cmd_len++] = (uint8_t)byte;
// 当到达长度字段(索引 2确定总长度3 + LEN + 1
if (cmd_len == 3) {
uint8_t payload_len = cmd_buf[2];
expected_total = (uint8_t)(3 + payload_len + 1);
if (expected_total > CMD_BUF_SIZE) {
// 异常:长度超界,复位状态机
cmd_len = 0;
expected_total = 0;
}
continue;
}
if (expected_total > 0 && cmd_len == expected_total) {
// 到帧尾,进行各项校验
bool ok = true;
if (cmd_buf[0] != PROTOCOL_PACKAGE_HEADER) {
const uint8_t err[] = { 'e','r','r', 0x3E }; // header 错
send_response(RESP_TYPE_HEADER_ERR, err, sizeof(err));
ok = false;
}
if (ok && cmd_buf[1] != PROTOCOL_BOARD_TYPE) {
const uint8_t err[] = { 'e','r','r', 0x3F }; // type 错
send_response(RESP_TYPE_TYPE_ERR, err, sizeof(err));
ok = false;
}
if (ok && cmd_buf[2] != PROTOCOL_PACKAGE_LENGTH) {
const uint8_t err[] = { 'e','r','r', 0x40 }; // length 错
send_response(RESP_TYPE_LEN_ERR, err, sizeof(err));
ok = false;
}
if (ok) {
uint8_t crc_calc = proto_sum_crc(cmd_buf, expected_total);
uint8_t crc_recv = cmd_buf[expected_total - 1];
if (crc_calc != crc_recv) {
const uint8_t err[] = { 'e','r','r', 0x3D }; // crc 错
send_response(RESP_TYPE_CRC_ERR, err, sizeof(err));
ok = false;
}
}
if (ok) {
handle_command(cmd_buf, expected_total);
}
// 复位,等待下一帧
cmd_len = 0;
expected_total = 0;
}
if (cmd_len >= CMD_BUF_SIZE) {
// 防御:缓冲溢出,复位状态机
cmd_len = 0;
expected_total = 0;
}
}
}
// -----------------------------------------------------------------------------
// 下列为与传感器相关的报告函数占位,按要求“保留但注释掉”。
// 原工程中依赖 ldc1612/tmp112a 读数并通过 0xB5 帧打印上报。
// 若后续集成这些传感器驱动,可解注释并补齐实现。
//
// static uint8_t package_header[3] = {0xB5, 0xF0, 0x04};
// static uint8_t package_data[4] = {0};
//
// void eddy_current_value_report(void) {
// uint32_t eddy_current_value_uint32 = ldc1612_get_raw_channel_result(CHANNEL_0);
// (void)eddy_current_value_uint32;
// // 按原协议组帧并 printf 发送B5 F0 04 [data3..data0] CRC
// }
//
// void tempture_value_report(void) {
// uint32_t temperature_uint32 = tmp112a_get_raw_channel_result();
// (void)temperature_uint32;
// // 按原协议组帧并 printf 发送B5 F0 04 [data3..data0] CRC
// }

View File

@ -34,6 +34,8 @@ OF SUCH DAMAGE.
#include "gd32e23x_it.h"
#include "systick.h"
#include "uart.h"
#include "uart_ring_buffer.h"
/*!
\brief this function handles NMI exception
@ -93,7 +95,12 @@ void PendSV_Handler(void)
\param[out] none
\retval none
*/
void SysTick_Handler(void)
{
delay_decrement();
void SysTick_Handler(void) {
}
void USART0_IRQHandler(void) {
if (RESET != usart_interrupt_flag_get(USART0, USART_INT_FLAG_RBNE)) {
uint8_t data = usart_data_receive(USART0);
uart_rx_put(data);
}
}

View File

@ -8,11 +8,11 @@ void led_init(void) {
}
void led_on(void) {
gpio_bit_set(LED_PORT, LED_PIN);
gpio_bit_reset(LED_PORT, LED_PIN);
}
void led_off(void) {
gpio_bit_reset(LED_PORT, LED_PIN);
gpio_bit_set(LED_PORT, LED_PIN);
}
void led_toggle(void) {

View File

@ -37,6 +37,15 @@ OF SUCH DAMAGE.
#include "uart.h"
#include "led.h"
#include <stdio.h>
#include "board_config.h"
#include "uart_ring_buffer.h"
#include "command.h"
void uart_puts(const char *s) {
while (*s) {
usart_data_transmit(RS485_PHY, (uint8_t)*s++);
}
}
/*!
\brief main function
@ -46,17 +55,28 @@ OF SUCH DAMAGE.
*/
int main(void)
{
systick_config();
uart0_init();
// uart1_init(115200); // 如需使用USART1请初始化
// printf("Hello USART0!\r\n");
// uart_set_printf_port(UART_PRINTF_USART1); // 切换printf到USART1
// uart_set_printf_port(UART_PRINTF_BOTH); // 同时输出到USART0和USART1
setbuf(stdout, NULL);
systick_config();
rs485_init();
// rcu_periph_clock_enable(RCU_GPIOA);
// gpio_mode_set(GPIOA, GPIO_MODE_OUTPUT, GPIO_PUPD_NONE, GPIO_PIN_1);
// gpio_output_options_set(GPIOA, GPIO_OTYPE_PP, GPIO_OSPEED_50MHZ, GPIO_PIN_1);
// gpio_bit_set(GPIOA, GPIO_PIN_1);
led_init();
printf("Hello USART0!");
led_off();
while(1){
led_toggle();
delay_ms(200);
// led_toggle();
// 发送数据到 USART0
// usart_data_transmit(RS485_PHY, (uint8_t)'H');
// printf("Hello USART0!");
delay_ms(100);
command_process();
}
}

View File

@ -1,83 +1,91 @@
/*!
\file systick.c
\brief the systick configuration file
\version 2025-02-10, V2.4.0, demo 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.
*/
/**
* ************************************************************************
*
* @file systick.c
* @author GD32
* @brief SysTick
*
* ************************************************************************
* @copyright Copyright (c) 2024 GD32
* ************************************************************************
*/
#include "gd32e23x.h"
#include "systick.h"
volatile static uint32_t delay;
volatile static float count_1us = 0;
volatile static float count_1ms = 0;
/*!
\brief configure systick
\param[in] none
\param[out] none
\retval none
*/
/**
* ************************************************************************
* @brief SysTick
*
*
* ************************************************************************
*/
void systick_config(void)
{
/* setup systick timer for 1000Hz interrupts */
if (SysTick_Config(SystemCoreClock / 1000U)){
/* capture error */
while (1){
}
}
/* configure the systick handler priority */
NVIC_SetPriority(SysTick_IRQn, 0x00U);
//设置了 SysTick 定时器的时钟源为 HCLK/8
systick_clksource_set(SYSTICK_CLKSOURCE_HCLK_DIV8);
//计算了每微秒所需的 SysTick 计数值
count_1us = (float)SystemCoreClock/8000000;
//计算了每毫秒所需的 SysTick 计数值
count_1ms = (float)count_1us * 1000;
}
/*!
\brief delay a time in milliseconds
\param[in] count: count in milliseconds
\param[out] none
\retval none
*/
/**
* ************************************************************************
* @brief delay_us
*
* @param[in] count
*
* ************************************************************************
*/
void delay_us(uint32_t count)
{
uint32_t ctl;
//设置 SysTick 计数器的装载值
SysTick->LOAD = (uint32_t)(count * count_1us);
//清零 SysTick 计数器,以确保计数器从零开始计数
SysTick->VAL = 0x0000U;
//使能 SysTick 定时器,开始进行计数
SysTick->CTRL = SysTick_CTRL_ENABLE_Msk;
//等待 SysTick 计数器的计数值达到装载值时退出
do
{
ctl = SysTick->CTRL; //读取 CTRL 寄存器的值
}while((ctl & SysTick_CTRL_ENABLE_Msk)&&!(ctl & SysTick_CTRL_COUNTFLAG_Msk));
//循环退出,禁用 SysTick 定时器
SysTick->CTRL &= ~SysTick_CTRL_ENABLE_Msk;
//将 SysTick 计数器的当前值清零,以便下次使用
SysTick->VAL = 0x0000U;
}
/**
* ************************************************************************
* @brief delay_ms
*
* @param[in] count
*
* ************************************************************************
*/
void delay_ms(uint32_t count)
{
delay = count;
uint32_t ctl;
while(0U != delay){
}
}
/*!
\brief delay decrement
\param[in] none
\param[out] none
\retval none
*/
void delay_decrement(void)
{
if (0U != delay){
delay--;
}
}
//设置 SysTick 计数器的装载值
SysTick->LOAD = (uint32_t)(count * count_1ms);
//清零 SysTick 计数器,以确保计数器从零开始计数
SysTick->VAL = 0x0000U;
//使能 SysTick 定时器,开始进行计数
SysTick->CTRL = SysTick_CTRL_ENABLE_Msk;
//等待 SysTick 计数器的计数值达到装载值时退出
do
{
ctl = SysTick->CTRL; //读取 CTRL 寄存器的值
}while((ctl&SysTick_CTRL_ENABLE_Msk)&&!(ctl & SysTick_CTRL_COUNTFLAG_Msk));
//循环退出,禁用 SysTick 定时器
SysTick->CTRL &= ~SysTick_CTRL_ENABLE_Msk;
//将 SysTick 计数器的当前值清零,以便下次使用
SysTick->VAL = 0x0000U;
}

View File

@ -5,7 +5,9 @@
#include "board_config.h"
void uart0_init(void) {
void rs485_init(void) {
#ifndef RS485_MAX13487
/* 使能 GPIOA 和 USART0 时钟 */
rcu_periph_clock_enable(RS485_GPIO_RCU);
rcu_periph_clock_enable(RS485_RCU);
@ -16,50 +18,84 @@ void uart0_init(void) {
gpio_mode_set(RS485_GPIO_PORT, GPIO_MODE_AF, GPIO_PUPD_PULLUP, RS485_TX_PIN | RS485_RX_PIN);
gpio_output_options_set(RS485_GPIO_PORT, GPIO_OTYPE_PP, GPIO_OSPEED_50MHZ, RS485_TX_PIN | RS485_RX_PIN);
gpio_mode_set(RS485_GPIO_PORT, GPIO_MODE_OUTPUT, GPIO_PUPD_NONE, RS485_EN_PIN);
gpio_mode_set(RS485_GPIO_PORT, GPIO_MODE_AF, GPIO_PUPD_NONE, RS485_EN_PIN);
gpio_output_options_set(RS485_GPIO_PORT, GPIO_OTYPE_PP, GPIO_OSPEED_50MHZ, RS485_EN_PIN);
/* 配置波特率、数据位、停止位等 */
usart_deinit(RS485_PHY);
usart_word_length_set(RS485_PHY, USART_WL_8BIT);
usart_stop_bit_set(RS485_PHY, USART_STB_1BIT);
usart_parity_config(RS485_PHY, USART_PM_NONE);
usart_baudrate_set(RS485_PHY, RS485_BAUDRATE);
usart_receive_config(RS485_PHY, USART_RECEIVE_ENABLE);
usart_transmit_config(RS485_PHY, USART_TRANSMIT_ENABLE);
usart_driver_assertime_config(RS485_PHY, 0x01);
usart_driver_deassertime_config(RS485_PHY, 0x01);
usart_driver_deassertime_config(RS485_PHY, 0x10);
usart_rs485_driver_enable(RS485_PHY);
usart_enable(RS485_PHY);
// TODO NVIC
nvic_irq_enable(USART0_IRQn, 0);
usart_interrupt_enable(RS485_PHY, USART_INT_RBNE);
// usart_interrupt_enable(RS485_PHY, USART_INT_IDLE);
#else
rcu_periph_clock_enable(RS485_GPIO_RCU);
rcu_periph_clock_enable(RS485_RCU);
gpio_af_set(RS485_GPIO_PORT, GPIO_AF_1, GPIO_PIN_2 | GPIO_PIN_3);
/* configure USART Tx&Rx as alternate function push-pull */
gpio_mode_set(RS485_GPIO_PORT, GPIO_MODE_AF, GPIO_PUPD_PULLUP, RS485_TX_PIN | RS485_RX_PIN);
gpio_output_options_set(RS485_GPIO_PORT, GPIO_OTYPE_PP, GPIO_OSPEED_10MHZ, RS485_TX_PIN | RS485_RX_PIN);
/* configure RS485 EN Pin */
gpio_mode_set(RS485_GPIO_PORT, GPIO_MODE_OUTPUT, GPIO_PUPD_NONE, RS485_EN_PIN);
gpio_output_options_set(RS485_GPIO_PORT, GPIO_OTYPE_PP, GPIO_OSPEED_50MHZ, RS485_EN_PIN);
gpio_bit_write(RS485_GPIO_PORT, RS485_EN_PIN, SET);
/* USART configure */
usart_deinit(RS485_PHY);
usart_baudrate_set(RS485_PHY, RS485_BAUDRATE);
usart_receive_config(RS485_PHY, USART_RECEIVE_ENABLE);
usart_transmit_config(RS485_PHY, USART_TRANSMIT_ENABLE);
usart_enable(RS485_PHY);
nvic_irq_enable(USART0_IRQn, 0);
usart_interrupt_enable(RS485_PHY, USART_INT_RBNE);
usart_interrupt_enable(RS485_PHY, USART_INT_IDLE);
#endif // RS485_MAX13487
}
static uart_printf_port_t g_printf_port = UART_PRINTF_USART0;
// static uart_printf_port_t g_printf_port = UART_PRINTF_USART0;
void uart_set_printf_port(uart_printf_port_t port) {
g_printf_port = port;
}
// void uart_set_printf_port(uart_printf_port_t port) {
// g_printf_port = port;
// }
// printf 重定向,支持多串口
int __io_putchar(int ch) {
switch (g_printf_port) {
case UART_PRINTF_USART0:
while (usart_flag_get(USART0, USART_FLAG_TBE) == RESET) {}
usart_data_transmit(USART0, (uint8_t)ch);
break;
case UART_PRINTF_USART1:
while (usart_flag_get(USART1, USART_FLAG_TBE) == RESET) {}
usart_data_transmit(USART1, (uint8_t)ch);
break;
case UART_PRINTF_BOTH:
while (usart_flag_get(USART0, USART_FLAG_TBE) == RESET) {}
usart_data_transmit(USART0, (uint8_t)ch);
while (usart_flag_get(USART1, USART_FLAG_TBE) == RESET) {}
usart_data_transmit(USART1, (uint8_t)ch);
break;
default:
break;
}
return ch;
}
// // printf 重定向,支持多串口
// int __io_putchar(int ch) {
// switch (g_printf_port) {
// case UART_PRINTF_USART0:
// while (usart_flag_get(USART0, USART_FLAG_TBE) == RESET) {}
// usart_data_transmit(USART0, (uint8_t)ch);
// break;
// case UART_PRINTF_USART1:
// while (usart_flag_get(USART1, USART_FLAG_TBE) == RESET) {}
// usart_data_transmit(USART1, (uint8_t)ch);
// break;
// case UART_PRINTF_BOTH:
// while (usart_flag_get(USART0, USART_FLAG_TBE) == RESET) {}
// usart_data_transmit(USART0, (uint8_t)ch);
// while (usart_flag_get(USART1, USART_FLAG_TBE) == RESET) {}
// usart_data_transmit(USART1, (uint8_t)ch);
// break;
// default:
// break;
// }
// return ch;
// }

34
Src/uart_ring_buffer.c Normal file
View File

@ -0,0 +1,34 @@
#include "uart_ring_buffer.h"
static volatile uint8_t uart_rx_buffer[UART_RX_BUFFER_SIZE];
static volatile uint16_t uart_rx_write = 0;
static volatile uint16_t uart_rx_read = 0;
void uart_ring_buffer_init(void) {
uart_rx_write = 0;
uart_rx_read = 0;
}
uint16_t uart_rx_available(void) {
return (uart_rx_write + UART_RX_BUFFER_SIZE - uart_rx_read) % UART_RX_BUFFER_SIZE;
}
int uart_rx_get(void) {
if (uart_rx_read == uart_rx_write) return -1; // 空
uint8_t data = uart_rx_buffer[uart_rx_read];
uart_rx_read = (uart_rx_read + 1) % UART_RX_BUFFER_SIZE;
return data;
}
void uart_rx_put(uint8_t data) {
uint16_t next = (uart_rx_write + 1) % UART_RX_BUFFER_SIZE;
if (next != uart_rx_read) { // 缓冲区未满
uart_rx_buffer[uart_rx_write] = data;
uart_rx_write = next;
}
}
void uart_rx_clear(void) {
uart_rx_write = 0;
uart_rx_read = 0;
}