release dev branch

This commit is contained in:
2025-08-17 02:58:32 +08:00
parent f82ab23898
commit 5cdd7ca58c
34 changed files with 5220 additions and 181 deletions

View File

@@ -1,6 +1,33 @@
#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)
/* >>>>>>>>>>>>>>>>>>>>[IIC TYPE DEFINE]<<<<<<<<<<<<<<<<<<<< */
// #define SOFTWARE_IIC // IIC Type : Software IIC
#undef SOFTWARE_IIC // IIC Type : Hardware IIC
/* >>>>>>>>>>>>>>>>>>>>[DEBUG ASSERTIONS DEFINE]<<<<<<<<<<<<<<<<<<<< */
// #define DEBUG_VERBOSE // Debug Assertions Status : Debug Verbose Information
#undef DEBUG_VERBOSE // Debug Assertions Status : No Debug Verbose Information
/******************************************************************************/
#define RCU_GPIO_I2C RCU_GPIOF
#define RCU_I2C RCU_I2C0
#define I2C_SCL_PORT GPIOF
#define I2C_SCL_PIN GPIO_PIN_1
#define I2C_SDA_PORT GPIOF
#define I2C_SDA_PIN GPIO_PIN_0
#define I2C_GPIO_AF GPIO_AF_1
#define I2C_DEBUG_UART USART0
/******************************************************************************/
#define LED_PORT GPIOA
@@ -9,4 +36,16 @@
/******************************************************************************/
#define RS485_RCU RCU_USART0
#define RS485_GPIO_RCU RCU_GPIOA
#define RS485_GPIO_PORT GPIOA
#define RS485_TX_PIN GPIO_PIN_2
#define RS485_RX_PIN GPIO_PIN_3
#define RS485_PHY USART0
#define RS485_BAUDRATE 115200U
#define RS485_EN_PIN GPIO_PIN_1
#define RS485_IRQ USART0_IRQn
/******************************************************************************/
#endif //BOARD_CONFIG_H

106
Inc/command.h Normal file
View File

@@ -0,0 +1,106 @@
/**
* @file command.h
* @brief 串口命令解析与处理模块接口声明。
* @details 提供基于环形缓冲区的串口协议解析、命令处理及状态管理功能,
* 支持格式为 D5 03 LEN [cmd] CRC 的命令帧解析与响应。
*/
#ifndef COMMAND_H
#define COMMAND_H
#include <stdint.h>
#include <stdbool.h>
/**
* @defgroup Command 命令处理模块
* @brief 串口命令解析与处理
* @{
*/
/** @brief 传感器周期上报使能标志 */
extern volatile bool g_sensor_report_enabled;
/**
* @section Command_Protocol 协议格式
* 接收命令帧格式:
* @code
* [0] HEADER = 0xD5 // 包头标识
* [1] BOARD_TYPE = 0x03 // 板卡类型标识
* [2] LEN = 数据区字节数 // 有效载荷长度
* [3..(3+LEN-1)] 数据 // 命令数据
* [last] CRC // 校验码从索引1累加到len-2的低8位
* @endcode
*
* 响应帧格式:
* @code
* [0] HEADER = 0xB5 // 响应包头
* [1] TYPE // 响应类型0xF0=成功0xF1..=错误类型)
* [2] LEN // 响应数据长度
* [3..(3+LEN-1)] 数据 // 响应数据
* [last] CRC // 校验码
* @endcode
*
* @section Command_Usage 使用说明
* 1) 初始化环形缓冲区:
* @code{.c}
* uart_ring_buffer_init();
* @endcode
*
* 2) 在主循环中调用命令处理:
* @code{.c}
* while(1) {
* command_process(); // 处理接收到的命令
* // 其他业务逻辑
* }
* @endcode
*
* 3) 查询传感器上报状态:
* @code{.c}
* if(get_sensor_report_enabled()) {
* // 执行传感器数据上报
* }
* @endcode
*/
/**
* @brief 获取传感器周期上报使能状态。
* @return bool 上报状态。
* @retval true 传感器周期上报已启用。
* @retval false 传感器周期上报已禁用。
* @ingroup Command
*/
bool get_sensor_report_enabled(void);
/**
* @brief 设置传感器周期上报使能状态。
* @param enabled 上报使能标志。
* @arg true 启用传感器周期上报。
* @arg false 禁用传感器周期上报。
* @note 推荐通过此函数修改状态,便于后续功能扩展。
* @ingroup Command
*/
void set_sensor_report_status(bool enabled);
/**
* @brief 处理串口环形缓冲区中的命令数据。
* @details 基于状态机的非阻塞协议解析器,处理完整的命令帧并自动响应。
* 每次调用处理缓冲区中所有可用数据,遇到错误时自动重置状态机。
* @note 使用静态变量维护解析状态,函数不可重入。
* @warning 依赖环形缓冲区正确实现,建议在主循环中周期调用。
* @ingroup Command
*/
void command_process(void);
/**
* @brief 解析并处理完整的命令帧。
* @param cmd 指向完整命令帧的缓冲区从包头0xD5开始
* @param len 命令帧总长度(字节)。
* @note 内部函数,由 command_process() 调用,一般不直接使用。
* @ingroup Command
*/
void handle_command(const uint8_t *cmd, uint8_t len);
/** @} */ // end of Command group
void eddy_current_report(void);
#endif // COMMAND_H

127
Inc/i2c.h Normal file
View File

@@ -0,0 +1,127 @@
//
// Created by dell on 24-12-20.
//
#ifndef I2C_H
#define I2C_H
#include "gd32e23x_it.h"
#include "gd32e23x.h"
#include "systick.h"
#include <stdbool.h>
#include <string.h>
#include <stdio.h>
#include <stdlib.h>
#include <math.h>
#include "board_config.h"
/******************************************************************************/
#define I2C_SPEED 100000U /* 100kHz */
#define I2C_TIME_OUT 5000U /* 5000 loops timeout */
#define I2C_MAX_RETRY 3U /* Maximum retry attempts */
#define I2C_DELAY_10US 10U /* Delay in microseconds for bus reset */
#define I2C_RECOVERY_CLOCKS 9U /* Clock pulses for bus recovery */
#define I2C_MASTER_ADDRESS 0x00U /* Master address (not used) */
/* Legacy compatibility */
#define I2C_OK 1
#define I2C_FAIL 0
#define I2C_END 1
/******************************************************************************/
/* I2C result enumeration */
typedef enum {
I2C_RESULT_SUCCESS = 0, /* Operation successful */
I2C_RESULT_TIMEOUT, /* Timeout occurred */
I2C_RESULT_NACK, /* No acknowledge received */
I2C_RESULT_BUS_BUSY, /* Bus is busy */
I2C_RESULT_ERROR, /* General error */
I2C_RESULT_INVALID_PARAM, /* Invalid parameter */
I2C_RECOVERY_OK,
I2C_RECOVERY_SDA_STUCK_LOW,
I2C_RECOVERY_SCL_STUCK_LOW
} i2c_result_t;
/* I2C state machine enumeration */
typedef enum {
I2C_STATE_IDLE = 0, /* Idle state */
I2C_STATE_START, /* Generate start condition */
I2C_STATE_SEND_ADDRESS, /* Send slave address */
I2C_STATE_CLEAR_ADDRESS, /* Clear address flag */
I2C_STATE_TRANSMIT_REG, /* Transmit register address */
I2C_STATE_TRANSMIT_DATA, /* Transmit data */
I2C_STATE_RESTART, /* Generate restart condition */
I2C_STATE_RECEIVE_DATA, /* Receive data */
I2C_STATE_STOP, /* Generate stop condition */
I2C_STATE_ERROR, /* Error state */
I2C_STATE_END
} i2c_state_t;
/******************************************************************************/
/* Function declarations */
/*!
\brief configure the I2C interface
\param[in] none
\param[out] none
\retval i2c_result_t
*/
i2c_result_t i2c_config(void);
/*!
\brief reset I2C bus with proper recovery
\param[in] none
\param[out] none
\retval i2c_result_t
*/
i2c_result_t i2c_bus_reset(void);
/*!
\brief scan I2C bus for devices
\param[in] none
\param[out] none
\retval none
*/
void i2c_scan(void);
/*!
\brief write 16-bit data to I2C device
\param[in] slave_addr: 7-bit slave address
\param[in] reg_addr: register address
\param[in] data: pointer to 2-byte data array
\param[out] none
\retval i2c_result_t
*/
i2c_result_t i2c_write_16bits(uint8_t slave_addr, uint8_t reg_addr, uint8_t data[2]);
/*!
\brief read 16-bit data from I2C device
\param[in] slave_addr: 7-bit slave address
\param[in] reg_addr: register address
\param[out] data: pointer to 2-byte data buffer
\retval i2c_result_t
*/
i2c_result_t i2c_read_16bits(uint8_t slave_addr, uint8_t reg_addr, uint8_t *data);
/*!
\brief read 16-bit data from I2C device
\param[in] slave_addr: 7-bit slave address
\param[in] reg_addr: register address
\param[out] data: pointer to 2-byte data buffer
\retval i2c_result_t
*/
i2c_result_t i2c_read_16bits(uint8_t slave_addr, uint8_t reg_addr, uint8_t *data);
/*!
\brief get status string for debugging
\param[in] status: i2c_result_t value
\param[out] none
\retval const char* status string
*/
const char* i2c_get_status_string(i2c_result_t status);
#endif //I2C_H

121
Inc/ldc1612.h Normal file
View File

@@ -0,0 +1,121 @@
//
// Created by dell on 24-12-3.
//
#ifndef LDC1612_H
#define LDC1612_H
#include "gd32e23x_it.h"
#include "gd32e23x.h"
#include "systick.h"
#include <stdbool.h>
#include <string.h>
#include <stdio.h>
#include <stdlib.h>
#include <math.h>
#include "board_config.h"
#include "soft_i2c.h"
#include "i2c.h"
/***************************************************************************/
/* IIC Interface Selection */
#ifdef SOFTWARE_IIC
#define LDC1612_IIC_WRITE_16BITS(addr, reg, data) soft_i2c_write_16bits(addr, reg, data)
#define LDC1612_IIC_READ_16BITS(addr, reg, data) soft_i2c_read_16bits(addr, reg, data)
#define LDC1612_IIC_TYPE_STR "Software IIC"
#else
#define LDC1612_IIC_WRITE_16BITS(addr, reg, data) i2c_write_16bits(addr, reg, data)
#define LDC1612_IIC_READ_16BITS(addr, reg, data) i2c_read_16bits(addr, reg, data)
#define LDC1612_IIC_TYPE_STR "Hardware IIC"
#endif
/***************************************************************************/
#define LDC1612_ADDR 0x2B
/*Register Rddr*/
/***************************************************************************/
#define CONVERTION_RESULT_REG_START 0X00
#define SET_CONVERSION_TIME_REG_START 0X08
#define SET_CONVERSION_OFFSET_REG_START 0X0C
#define SET_LC_STABILIZE_REG_START 0X10
#define SET_FREQ_REG_START 0X14
#define SENSOR_STATUS_REG 0X18
#define ERROR_CONFIG_REG 0X19
#define SENSOR_CONFIG_REG 0X1A
#define MUL_CONFIG_REG 0X1B
#define SENSOR_RESET_REG 0X1C
#define SET_DRIVER_CURRENT_REG 0X1E
#define READ_MANUFACTURER_ID 0X7E
#define READ_DEVICE_ID 0X7F
/******************************************************************************/
#define CHANNEL_0 0
#define CHANNEL_1 1
/*************************MUX_CONFIG********************************************/
#define LDC1612_MUX_CONFIG 0x0200
/***********************SENSOR_CONFIG********************************************/
#define LDC1612_SENSOR_CONFIG_CH0 0x1601 //
/****************************CONVERSION_TIME************************************/
#define LDC1612_CONVERSION_TIME_CH0 0x1000 // 0x1000=4096个时钟周期
#define LC_STABILIZE_TIME_CH0 0x0020 // 0x0020=32个时钟周期
/**************************DRIVE_CURRENT****************************************/
#define LDC1612_DRIVE_CURRENT 0x9000 //A000
/**************************SENSOR_CONFIG***************************************/
#define LDC1612_SLEEP_MODE 0x2801
/**************************OTHER_CONFIG*****************************************/
#define LDC1612_ERROR_CONFIG 0x0000
#define SET_CONVERSION_OFFSET_CH0 0x0000
#define LDC1612_RESET_DEV 0x8000 //[15:0] 0b1000 0000 0000 0000
/******************************************************************************/
#define COIL_RP_KOM 7.2
#define COIL_L_UH 33
#define COIL_C_PF 150
#define COIL_Q_FACTOR 35.97
#define COIL_FREQ_HZ 2262000
/******************************************************************************/
typedef enum {
LDC1612_STATUS_SUCCESS = 0,
LDC1612_STATUS_ERROR,
LDC1612_STATUS_TIMEOUT,
LDC1612_STATUS_INVALID_PARAM,
LDC1612_STATUS_NO_COIL,
LDC1612_STATUS_UNDER_RANGE,
LDC1612_STATUS_OVER_RANGE
} ldc1612_status_t;
/******************************************************************************/
ldc1612_status_t ldc1612_init(void);
ldc1612_status_t ldc1612_reset_sensor(void);
ldc1612_status_t ldc1612_config_single_channel(uint8_t channel);
uint16_t ldc1612_get_manufacturer_id(void);
uint16_t ldc1612_get_deveice_id(void);
uint32_t ldc1612_get_raw_channel_result(uint8_t channel);
uint32_t ldc1612_parse_raw_result(uint32_t raw_result);
uint16_t ldc1612_get_sensor_status(void);
bool ldc1612_is_data_ready(uint8_t channel);
#endif //LDC1612_H

View File

@@ -8,5 +8,6 @@ void led_init(void);
void led_on(void);
void led_off(void);
void led_toggle(void);
void led_heart_beat(void);
#endif // LED_H

28
Inc/sensor_example.h Normal file
View File

@@ -0,0 +1,28 @@
//
// Sensor Usage Example Header
// 传感器使用示例头文件
//
#ifndef SENSOR_EXAMPLE_H
#define SENSOR_EXAMPLE_H
#include "gd32e23x.h"
#include "board_config.h"
/*!
\brief 传感器初始化示例
\param[in] none
\param[out] none
\retval none
*/
void sensors_init_example(void);
/*!
\brief 传感器读取示例
\param[in] none
\param[out] none
\retval none
*/
void sensors_read_example(void);
#endif // SENSOR_EXAMPLE_H

52
Inc/soft_i2c.h Normal file
View File

@@ -0,0 +1,52 @@
//
// Created by dell on 24-12-28.
//
#ifndef SOFT_I2C_H
#define SOFT_I2C_H
#include "gd32e23x_it.h"
#include "gd32e23x.h"
#include "systick.h"
#include "board_config.h"
/******************************************************************************/
#define I2C_SCL_HIGH() gpio_bit_set(I2C_SCL_PORT, I2C_SCL_PIN)
#define I2C_SCL_LOW() gpio_bit_reset(I2C_SCL_PORT, I2C_SCL_PIN)
#define I2C_SDA_HIGH() gpio_bit_set(I2C_SDA_PORT, I2C_SDA_PIN)
#define I2C_SDA_LOW() gpio_bit_reset(I2C_SDA_PORT, I2C_SDA_PIN)
#define I2C_SDA_READ() gpio_input_bit_get(I2C_SDA_PORT, I2C_SDA_PIN)
/******************************************************************************/
#define SOFT_I2C_OK 1
#define SOFT_I2C_FAIL 0
#define SOFT_I2C_END 1
/******************************************************************************/
void soft_i2c_delay(void);
void soft_i2c_config(void);
void soft_i2c_start(void);
void soft_i2c_stop(void);
void soft_i2c_send_ack(void);
void soft_i2c_send_nack(void);
uint8_t soft_i2c_wait_ack(void);
void soft_i2c_send_byte(uint8_t data);
uint8_t soft_i2c_receive_byte(uint8_t ack);
uint8_t soft_i2c_write_16bits(uint8_t slave_addr, uint8_t reg_addr, uint8_t data[2]);
uint8_t soft_i2c_read_16bits(uint8_t slave_addr, uint8_t reg_addr, uint8_t *data);
#endif //SOFT_I2C_H

View File

@@ -1,47 +1,36 @@
/*!
\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 10 microseconds */
void delay_10us(uint32_t count);
/* delay a time in milliseconds */
void delay_ms(uint32_t count);
/* delay decrement */
/* decrement delay counters */
void delay_decrement(void);
#endif /* SYS_TICK_H */
// /* delay function that doesn't interfere with SysTick interrupt */
// void delay_ms_safe(uint32_t count);
// /* delay a time in microseconds (safe version) */
// void delay_us_safe(uint32_t count);
#endif /* SYS_TICK_H */

155
Inc/tmp112.h Normal file
View File

@@ -0,0 +1,155 @@
//
// Created by dell on 24-12-20.
// TMP112A Temperature Sensor Driver Header
//
#ifndef TMP112_H
#define TMP112_H
#include "gd32e23x_it.h"
#include "gd32e23x.h"
#include "systick.h"
#include <stdbool.h>
#include <string.h>
#include <stdio.h>
#include <stdlib.h>
#include <math.h>
#include "board_config.h"
#include "i2c.h"
/******************************************************************************/
/* TMP112A I2C Address */
#define TMP112A_ADDR (0x48) // 7-bit address (ADD0=GND)
/* Register Addresses */
/******************************************************************************/
#define TMP112A_TEMP_REG 0x00 // 温度寄存器
#define TMP112A_CONFIG_REG 0x01 // 配置寄存器
#define TMP112A_TLOW_REG 0x02 // 低温阈值寄存器
#define TMP112A_THIGH_REG 0x03 // 高温阈值寄存器
/* Configuration Register Bits */
/******************************************************************************/
#define TMP112A_CONFIG_OS (1 << 15) // One-shot
#define TMP112A_CONFIG_R1 (1 << 14) // Converter resolution bit 1
#define TMP112A_CONFIG_R0 (1 << 13) // Converter resolution bit 0
#define TMP112A_CONFIG_F1 (1 << 12) // Fault queue bit 1
#define TMP112A_CONFIG_F0 (1 << 11) // Fault queue bit 0
#define TMP112A_CONFIG_POL (1 << 10) // Polarity
#define TMP112A_CONFIG_TM (1 << 9) // Thermostat mode
#define TMP112A_CONFIG_SD (1 << 8) // Shutdown
#define TMP112A_CONFIG_CR1 (1 << 7) // Conversion rate bit 1
#define TMP112A_CONFIG_CR0 (1 << 6) // Conversion rate bit 0
#define TMP112A_CONFIG_AL (1 << 5) // Alert
#define TMP112A_CONFIG_EM (1 << 4) // Extended mode
/* Resolution Settings */
/******************************************************************************/
#define TMP112A_RESOLUTION_9BIT 0x0000 // 9-bit (0.5°C)
#define TMP112A_RESOLUTION_10BIT 0x2000 // 10-bit (0.25°C)
#define TMP112A_RESOLUTION_11BIT 0x4000 // 11-bit (0.125°C)
#define TMP112A_RESOLUTION_12BIT 0x6000 // 12-bit (0.0625°C)
/* Conversion Rate Settings */
/******************************************************************************/
#define TMP112A_RATE_0_25HZ 0x0000 // 0.25 Hz (4s)
#define TMP112A_RATE_1HZ 0x0040 // 1 Hz (1s)
#define TMP112A_RATE_4HZ 0x0080 // 4 Hz (250ms)
#define TMP112A_RATE_8HZ 0x00C0 // 8 Hz (125ms)
/* Default Configuration */
/******************************************************************************/
#define TMP112A_CONFIG_DEFAULT (TMP112A_RESOLUTION_12BIT | TMP112A_RATE_4HZ)
/* Temperature Conversion Constants */
/******************************************************************************/
#define TMP112A_TEMP_RESOLUTION 0.0625f // 12-bit resolution (°C/LSB)
#define TMP112A_TEMP_MIN -55.0f // 最低温度 (°C)
#define TMP112A_TEMP_MAX 125.0f // 最高温度 (°C)
/* Status Definitions */
/******************************************************************************/
typedef enum {
TMP112A_STATUS_SUCCESS = 0,
TMP112A_STATUS_ERROR,
TMP112A_STATUS_TIMEOUT,
TMP112A_STATUS_INVALID_PARAM,
TMP112A_STATUS_OUT_OF_RANGE
} tmp112a_status_t;
typedef struct {
uint16_t raw_data;
float temperature_c;
float temperature_f;
bool alert_flag;
} tmp112a_result_t;
/******************************************************************************/
/* Function Declarations */
/*!
\brief 初始化TMP112A传感器
\param[in] none
\param[out] none
\retval tmp112a_status_t
*/
tmp112a_status_t tmp112a_init(void);
/*!
\brief 配置TMP112A传感器
\param[in] config: 配置值
\param[out] none
\retval tmp112a_status_t
*/
tmp112a_status_t tmp112a_config(uint16_t config);
/*!
\brief 读取温度
\param[in] none
\param[out] result: 结果结构体指针
\retval tmp112a_status_t
*/
tmp112a_status_t tmp112a_read_temperature(tmp112a_result_t *result);
/*!
\brief 设置温度阈值
\param[in] low_temp: 低温阈值 (°C)
\param[in] high_temp: 高温阈值 (°C)
\param[out] none
\retval tmp112a_status_t
*/
tmp112a_status_t tmp112a_set_thresholds(float low_temp, float high_temp);
/*!
\brief 进入关机模式
\param[in] none
\param[out] none
\retval tmp112a_status_t
*/
tmp112a_status_t tmp112a_shutdown(void);
/*!
\brief 退出关机模式
\param[in] none
\param[out] none
\retval tmp112a_status_t
*/
tmp112a_status_t tmp112a_wakeup(void);
/*!
\brief 单次转换
\param[in] none
\param[out] result: 结果结构体指针
\retval tmp112a_status_t
*/
tmp112a_status_t tmp112a_one_shot(tmp112a_result_t *result);
/*!
\brief 获取状态字符串
\param[in] status: 状态码
\param[out] none
\retval const char* 状态字符串
*/
const char* tmp112a_get_status_string(tmp112a_status_t status);
#endif //TMP112_H

View File

@@ -3,14 +3,6 @@
#include "gd32e23x.h"
typedef enum {
UART_PRINTF_USART0 = 0,
UART_PRINTF_USART1 = 1,
UART_PRINTF_BOTH = 2
} uart_printf_port_t;
void uart0_init(uint32_t baudrate);
void uart1_init(uint32_t baudrate);
void uart_set_printf_port(uart_printf_port_t port);
void rs485_init(void);
#endif // UART_H

119
Inc/uart_ring_buffer.h Normal file
View File

@@ -0,0 +1,119 @@
/**
* @file uart_ring_buffer.h
* @brief 简单高效的环形接收缓冲区(字节队列)接口声明。
* @details 提供字节写入/读取、可读长度查询、清空与丢弃统计等 API
* 适用于中断接收(写)与主循环解析(读)的典型嵌入式串口场景。
*/
#ifndef UART_RING_BUFFER_H
#define UART_RING_BUFFER_H
#include <stdint.h>
#include <stdbool.h>
/**
* @def UART_RX_BUFFER_SIZE
* @brief 接收环形缓冲区容量(单位:字节)。
* @note 采用“预留一格”区分空/满策略,最大可用容量为 UART_RX_BUFFER_SIZE-1。
*/
#define UART_RX_BUFFER_SIZE 64
/**
* @defgroup RingBuffer 环形缓冲区
* @brief 字节环形缓冲区(接收端)
* @{
*/
/**
* @section RingBuffer_Usage 使用说明
* 典型用法:中断接收(写入环形缓冲)、主循环解析(读取环形缓冲)。
*
* 1) 初始化
* @code{.c}
* uart_ring_buffer_init();
* @endcode
*
* 2) 使能串口接收非空中断RBNE并开启中断以 USART0 为例)
* @code{.c}
* usart_interrupt_enable(USART0, USART_INT_RBNE);
* nvic_irq_enable(USART0_IRQn, 2, 0); // 根据工程需要设置优先级
* @endcode
*
* 3) 在中断服务函数中写入环形缓冲(参考你当前工程的写法)
* @code{.c}
* void USART0_IRQHandler(void) {
* if (RESET != usart_interrupt_flag_get(USART0, USART_INT_FLAG_RBNE)) {
* uint8_t data = usart_data_receive(USART0);
* (void)uart_ring_buffer_put(data); // 缓冲满时丢弃并计数
* }
* }
* @endcode
*
* 4) 在主循环中读取处理
* @code{.c}
* while (uart_ring_buffer_available() > 0) {
* int b = uart_ring_buffer_get();
* if (b >= 0) {
* // 处理字节 b
* }
* }
* @endcode
*
* @note 缓冲区满时新字节会被丢弃,可用 uart_ring_buffer_drop_count() 查看累计丢弃数。
* @note 采用“预留一格”区分空/满,最大可用容量为 UART_RX_BUFFER_SIZE-1。
*/
/**
* @brief 初始化环形缓冲区。
* @details 复位读/写索引与丢弃计数,准备接收数据。
* @note 若在中断环境使用,初始化前建议关闭相关接收中断以避免并发竞争。
* @ingroup RingBuffer
*/
void uart_ring_buffer_init(void);
/**
* @brief 获取当前可读的字节数。
* @details 返回范围为 [0, UART_RX_BUFFER_SIZE-1]。
* @return 可读字节数uint8_t
* @note 预留一个空槽区分“空/满”,因此满时返回 UART_RX_BUFFER_SIZE-1。
* @ingroup RingBuffer
*/
uint8_t uart_ring_buffer_available(void);
/**
* @brief 从环形缓冲区读取一个字节。
* @details 若缓冲区非空,返回队头字节并推进读指针;若为空,返回 -1。
* @return 读取到的字节0..255),或 -1 表示缓冲区为空。
* @retval -1 缓冲区为空,无数据可读。
* @ingroup RingBuffer
*/
int uart_ring_buffer_get(void);
/**
* @brief 向环形缓冲区写入一个字节。
* @param data 待写入的字节。
* @return 是否写入成功。
* @retval true 写入成功。
* @retval false 写入失败(缓冲区已满,数据被丢弃并计数)。
* @note 如需改为“覆盖写入”策略,可在满时先推进读指针再写入。
* @ingroup RingBuffer
*/
bool uart_ring_buffer_put(uint8_t data);
/**
* @brief 清空环形缓冲区。
* @details 复位读/写索引与丢弃计数,相当于逻辑上丢弃所有已接收数据,不擦除数据区内容。
* @ingroup RingBuffer
*/
void uart_ring_buffer_clear(void);
/**
* @brief 获取因缓冲区满而被丢弃的字节累计数量。
* @details 该计数在 init/clear 时清零。
* @return 丢弃的累计字节数。
* @ingroup RingBuffer
*/
uint32_t uart_ring_buffer_drop_count(void);
/** @} */
#endif // UART_RING_BUFFER_H