8 Commits

42 changed files with 5702 additions and 281 deletions

View File

@ -48,7 +48,32 @@ extern "C" {
/* Exported macro ------------------------------------------------------------*/
/* USER CODE BEGIN EM */
/* 硬件模块启用/禁用宏定义 */
// 基准年份
#define XTELL_BASE_YEAR 2026
/**
* 宏定义3-4-5-4 固件版本编码
* y: Year (2026-2033)
* m: Month (1-12)
* d: Day (1-31)
* b: Build (0-15)
*/
#define MAKE_XTELL_CODE(y, m, d, b) ( \
((( (y) - XTELL_BASE_YEAR ) & 0x07) << 13) | \
(((m) & 0x0F) << 9) | \
(((d) & 0x1F) << 4) | \
(((b) & 0x0F) << 0) \
)
// 举例2026年3月19日第10次编译 (b=9)
// 计算过程: (0 << 13) | (3 << 9) | (19 << 4) | 9 = 0x0600 | 0x0130 | 0x0009
#define XTELL_FIRMWARE_CODE MAKE_XTELL_CODE(2026, 5, 10, 1)
// ---- - -- -
// | | | |
// | | | 编译次数
// | | 日
// | 月
// 年
#ifndef USE_W5500
#define USE_W5500 1 /* 默认启用W5500以太网模块 */
#endif
@ -56,11 +81,34 @@ extern "C" {
#ifndef USE_RS485
#define USE_RS485 1 /* 默认启用RS485通信模块 */
#endif
#ifndef USE_IO_MONITOR
#define USE_IO_MONITOR 1 /* 启用IO监控与心跳上报 */
#endif
/* =========================================================
🚀 核心协议常量定义 (RF433)
========================================================= */
#define PROTO_START_BYTE 0xAA
#define PROTO_TYPE_IO 0x10
#define PROTO_TYPE_NET 0x55
#define PROTO_TYPE_485 0x48
#define PROTO_TYPE_HB 0xAA
/* =========================================================
🚀 核心身份标识:烧录不同设备时,请务必修改这个数字!
比如设备A烧录时改为 0x01设备B烧录时改为 0x02
========================================================= */
#define MY_DEVICE_ID 0x01
#define MY_DEVICE_ID 101
/* =========================================================
🚀 开发调试开关
TEST_A701:
- 1: 测试环境 (A701室/本地测试),使用 192.168.6.x 网段
- 0: 生产环境 (实船/现场部署),使用 192.168.0.x 网段
========================================================= */
#define TEST_A701 0
/* USER CODE END EM */
/* Exported functions prototypes ---------------------------------------------*/

View File

@ -0,0 +1,55 @@
/**
******************************************************************************
* @file modbus_tcp_client.h
* @brief Modbus TCP 客户端模块头文件 (基于 W5500)
******************************************************************************
*/
#ifndef __MODBUS_TCP_CLIENT_H
#define __MODBUS_TCP_CLIENT_H
#include <stdint.h>
#include <stdbool.h>
#include "main.h"
/* Modbus TCP 配置 */
#if TEST_A701
#define MODBUS_SERVER_IP {192, 168, 0, 6} /* A701 测试服务器 */
#else
#define MODBUS_SERVER_IP {192, 168, 0, 1} /* 现场生产服务器 */
#endif
#define MODBUS_SERVER_PORT 502
#define MODBUS_UNIT_ID 1
#define MODBUS_POLL_INTERVAL 2000 /* 轮询间隔 (ms) */
/* 寄存器定义 */
#define TARGET_REG_ADDR 30 /* 逻辑 40031 */
/* 客户端状态枚举 */
typedef enum {
MODBUS_STATE_IDLE,
MODBUS_STATE_CONNECTING,
MODBUS_STATE_SEND_QUERY,
MODBUS_STATE_WAIT_RESPONSE,
MODBUS_STATE_ERROR_RETRY
} modbus_client_state_t;
/**
* @brief 初始化 Modbus TCP 客户端
* @param sn: W5500 Socket 编号
*/
void ModbusTCP_Client_Init(uint8_t sn);
/**
* @brief Modbus TCP 客户端任务处理 (主循环调用)
*/
void ModbusTCP_Client_Task(void);
/**
* @brief 获取最新成功读取的 Modbus 寄存器值
* @retval 16位寄存器值 (未读到时默认返回 0xFFFF)
*/
uint16_t ModbusTCP_Get_LastRegVal(void);
#endif

View File

@ -31,9 +31,9 @@ extern "C" {
#define UART_TX_BUFFER_SIZE 256
typedef enum {
PORT_UART1 = 0,
PORT_UART2 = 1,
PORT_UART3 = 2,
PORT_433 = 0, /* UART1 */
PORT_DEBUG = 1, /* UART2 */
PORT_RS485 = 2, /* UART3 */
PORT_COUNT
} port_id_t;
@ -64,6 +64,8 @@ typedef struct {
uint32_t tx_count;
uint32_t error_count;
bool initialized;
volatile bool csma_backoff_active;
volatile uint32_t csma_backoff_until;
} uart_port_context_t;
void MultiUART_Init(void);
@ -89,6 +91,7 @@ uint16_t MultiUART_ReadByte(port_id_t port_id, uint8_t *byte);
uint16_t MultiUART_GetTxAvailable(port_id_t port_id);
uint32_t MultiUART_GetOverflowCount(port_id_t port_id);
bool MultiUART_IsBusy(uint8_t port_id);
#ifdef __cplusplus
}

View File

@ -113,7 +113,7 @@ static uint32_t g_routed_count = 0;
* @brief 当前正在解析的端口ID
* @note 用于在多端口环境下跟踪当前处理哪个端口的数据
*/
static uint8_t g_current_parsing_port = PORT_UART2;
static uint8_t g_current_parsing_port = PORT_DEBUG;
/**
* @brief 接收原始字节日志缓冲区
@ -275,7 +275,7 @@ static void cmd_parser_response_callback(uint8_t source_port, const char *respon
* 1. 重置所有端口的解析状态
* 2. 清零所有日志缓冲区
* 3. 重置统计计数器
* 4. 设置默认解析端口为PORT_UART2
* 4. 设置默认解析端口为PORT_DEBUG
* 5. 注册响应回调函数到解析器
*/
void CmdRouter_Init(void)
@ -299,7 +299,7 @@ void CmdRouter_Init(void)
g_response_handler = NULL;
g_processed_count = 0;
g_routed_count = 0;
g_current_parsing_port = PORT_UART2;
g_current_parsing_port = PORT_DEBUG;
/*----------------------------------------------------------
* 注册响应回调函数
@ -348,7 +348,7 @@ void CmdRouter_Task(void)
* 第一阶段UART1处理(保持原有逻辑)
*----------------------------------------------------------*/
{
port_id_t port_id = PORT_UART1;
port_id_t port_id = PORT_433;
uint16_t rx_count = MultiUART_GetRxCount(port_id);
@ -380,11 +380,11 @@ void CmdRouter_Task(void)
LOG_DEBUG("UART3", "Protocol state: %d", UART3_Protocol_GetState());
uint8_t byte;
while (MultiUART_ReadByte(PORT_UART3, &byte) > 0) {
while (MultiUART_ReadByte(PORT_RS485, &byte) > 0) {
route_result_t route = UART3_Protocol_FeedByte(byte, current_tick);
switch (route) {
case ROUTE_CMD:
CmdParser_SetSourcePort(PORT_UART3);
CmdParser_SetSourcePort(PORT_RS485);
CmdParser_FeedByte(byte, current_tick);
LOG_DEBUG("UART3", "CMD byte: 0x%02X", byte);
break;
@ -422,7 +422,7 @@ void CmdRouter_Task(void)
int appended = snprintf(msg + msg_len, sizeof(msg) - msg_len, "*%02X\r\n", cs);
LOG_DEBUG("UART3", "Constructed message: %s", msg);
// 发送ASCII消息
MultiUART_SendString(PORT_UART1, msg);
MultiUART_SendString(PORT_433, msg);
LOG_INFO("UART3", "PASSTHROUGH: %d bytes sent as ASCII message", (int)length);
} else {
LOG_DEBUG("UART3", "No passthrough data");
@ -433,7 +433,7 @@ void CmdRouter_Task(void)
}
#else
{
port_id_t port_id = PORT_UART3;
port_id_t port_id = PORT_RS485;
uint16_t rx_count = MultiUART_GetRxCount(port_id);
@ -461,7 +461,7 @@ void CmdRouter_Task(void)
* 第三阶段:检查各端口日志缓冲区的超时状态
*----------------------------------------------------------*/
for (port_id_t port_id = 0; port_id < PORT_COUNT; port_id++) {
if (port_id == PORT_UART2) {
if (port_id == PORT_DEBUG) {
continue;
}

View File

@ -144,6 +144,6 @@ void DebugLog_Output(log_level_t level, const char *module, const char *fmt, ...
if (len > 0) {
UART2_Print_Send((const uint8_t *)buffer, len);
MultiUART_Send(PORT_UART3, (const uint8_t *)buffer, len); /* 增加:同时将日志发给 UART3 */
// MultiUART_Send(PORT_RS485, (const uint8_t *)buffer, len); /* 增加:同时将日志发给 RS485 */
}
}

View File

@ -213,7 +213,7 @@ static void send_di_event(uint8_t channel, uint8_t state)
memcpy(&rf_tx_buf[2], msg, msg_len); // 把真正的 DI 消息塞到第 2 个字节后面
/* 将带 ID 的完整包裹发送给 433 模块 */
MultiUART_Send(PORT_UART1, rf_tx_buf, msg_len + 2);
MultiUART_Send(PORT_433, rf_tx_buf, msg_len + 2);
/* ========================================================== */
DEBUG_LOG("RF433 TX: \"%s\"", msg);
@ -261,8 +261,8 @@ void IO_Monitor_Init(void)
/* 初始化扫描时间戳为0确保首次扫描立即执行 */
last_scan_tick = 0;
/* 使能自动上报功能 */
report_enabled = true;
/* 禁用旧的自动上报功能,改用 main.c 中的新协议上报 */
report_enabled = false;
/* 输出初始化完成日志,显示初始各通道状态掩码 */
DEBUG_LOG("Init OK, initial states: 0x%02X", IO_Monitor_GetAllStates());

View File

@ -47,6 +47,7 @@
#include "wiz_interface.h"
#include "wizchip_conf.h"
#include "loopback.h"
#include "modbus_tcp_client.h"
#endif
extern void wiz_timer_handler(void);
#if (RF433_MODE == RF433_MODE_TX) || (RF433_MODE == RF433_MODE_BOTH)
@ -85,11 +86,89 @@ static uint8_t u1_rx_buffer[256];
static volatile uint16_t u1_rx_len = 0;
static volatile uint32_t u1_last_rx_time = 0;
/* === 485 设备的接收缓存 (UART3) 增加这三行!=== */
/* === 485 设备的接收缓存 (UART3) === */
static uint8_t u3_rx_buffer[512];
static volatile uint16_t u3_rx_len = 0;
static volatile uint32_t u3_last_rx_time = 0;
static volatile uint32_t u3_ignore_until = 0;
/* === 协议处理全局变量 === */
static uint16_t g_hb_seq = 0; /* 心跳序列号 */
static uint32_t g_last_hb_tick = 0; /* 上次心跳时间 */
static uint8_t g_last_io_state = 0xFF; /* 上次记录的 IO 状态,用于变化检测 */
/* === W5500 外部变量声明 === */
#if USE_W5500
extern uint16_t local_port;
extern uint8_t ethernet_buf[];
#endif
/**
* @brief 判断单片机与 433 模块连接的串口是否正忙于传输
* @return bool: true=串口引擎忙(需避让), false=串口空闲
*/
bool RF433_UART_Is_Busy(void)
{
// 仅查询 UART1 的引擎状态,不关心模块 AUX
return MultiUART_IsBusy(PORT_433);
}
/**
* @brief 计算并发送 RF433 协议数据包
* @param type: 协议类型 (0x10, 0x55, 0x48, 0xAA)
* @param payload: 载荷数据指针
* @param len: 载荷长度
*/
void RF433_SendPacket(uint8_t type, const uint8_t *payload, uint8_t len)
{
uint8_t frame[260];
uint16_t frame_idx = 0;
uint8_t checksum = 0;
frame[frame_idx++] = PROTO_START_BYTE; // AA
frame[frame_idx++] = type; // TYPE
frame[frame_idx++] = (uint8_t)(len + 1 + 1); // LEN (ID + Payload + SUM)
frame[frame_idx++] = MY_DEVICE_ID; // ID
if (len > 0 && payload != NULL) {
memcpy(&frame[frame_idx], payload, len);
frame_idx += len;
}
/* 计算校验和 (Sum8) */
for (uint16_t i = 0; i < frame_idx; i++) {
checksum += frame[i];
}
frame[frame_idx++] = checksum;
/* 通过 MultiUART 发送 */
MultiUART_Send(PORT_433, frame, frame_idx);
}
/**
* @brief 检查 433 无线信道是否忙碌 (发送保护区)
* @return bool: true=忙碌(需避让), false=空闲
*/
bool RF433_Is_Air_Busy(void)
{
return (HAL_GPIO_ReadPin(AUX_GPIO_Port, AUX_Pin) == GPIO_PIN_RESET);
}
/**
* @brief 读取当前 4 路 DI 的合并状态
* @return uint8_t: Bit0-3 对应 DI1-4
*/
uint8_t IO_Get_Current_State(void)
{
uint8_t state = 0;
if (HAL_GPIO_ReadPin(MCU_DI1_GPIO_Port, MCU_DI1_Pin) == GPIO_PIN_SET) state |= (1 << 0);
if (HAL_GPIO_ReadPin(MCU_DI2_GPIO_Port, MCU_DI2_Pin) == GPIO_PIN_SET) state |= (1 << 1);
if (HAL_GPIO_ReadPin(MCU_DI3_GPIO_Port, MCU_DI3_Pin) == GPIO_PIN_SET) state |= (1 << 2);
if (HAL_GPIO_ReadPin(MCU_DI4_GPIO_Port, MCU_DI4_Pin) == GPIO_PIN_SET) state |= (1 << 3);
return state;
}
/* W5500 variables */
#if USE_W5500
#define SOCKET_ID 0
@ -185,8 +264,16 @@ int main(void)
printf("[DEBUG] 4. 进入 network_init()\r\n");
network_init(ethernet_buf, &default_net_info);
printf("[DEBUG] 5. network_init() 成功返回!\r\n");
printf("wizchip UDP example started\r\n");
printf("[DEBUG] 5. network_init() 成功返回!\n");
printf("--- Socket Status Diagnostic ---\n");
for (int i=0; i<8; i++) {
printf("Socket %d SR: 0x%02X\n", i, getSn_SR(i));
}
printf("--------------------------------\n");
printf("Modbus TCP Client starting\n");
ModbusTCP_Client_Init(1); // 暂时使用 Socket 1 进行测试,避开可能被污染的 Socket 0
#endif
/* ======================================= */
@ -229,9 +316,9 @@ int main(void)
rf433_rx_app_task();
#endif
/* W5500 UDP回环任务 */
/* W5500 UDP回环任务(为了测试 PING 功能,放到了单独的 Socket 2 */
#if USE_W5500
loopback_udps(SOCKET_ID, ethernet_buf, local_port);
loopback_udps(2, ethernet_buf, local_port);
#endif
@ -240,74 +327,36 @@ int main(void)
/* USER CODE BEGIN WHILE */
while (1)
{
/* === 1. 恢复系统的核心驱动引擎 === */
UART2_Print_Task();
MultiUART_Task();
IO_Monitor_Task();
/* === 1. 核心通信驱动引擎 (最高优先级) === */
UART2_Print_Task();
MultiUART_Task();
/* === 2. 网络轮询任务 === */
#if USE_W5500
loopback_udps(SOCKET_ID, ethernet_buf, local_port);
#endif
/* === 3. 极速无乱码透传 === */
/* === 方案 A从 433 收到无线数据 -> 给上位机解析 === */
/* === 2. 无线接收透传 (433 -> 485/Debug) === */
#if (RF433_MODE == RF433_MODE_RX) || (RF433_MODE == RF433_MODE_BOTH)
// 如果 433 收到无线数据,直接透传输出,不进行解码
if (u1_rx_len > 0 && (HAL_GetTick() - u1_last_rx_time > 20))
{
static uint8_t temp_buf1[256];
__disable_irq();
__disable_irq();
uint16_t len = u1_rx_len;
memcpy(temp_buf1, (uint8_t*)u1_rx_buffer, len);
u1_rx_len = 0;
u1_rx_len = 0;
__enable_irq();
/* 🚀 终极上位机协议:[0xAA帧头] + [设备ID] + [来源接口] + [数据长度] + [纯净数据] */
if (len >= 2 && temp_buf1[0] == 0xAA)
{
uint8_t sender_id = temp_buf1[1];
uint16_t payload_len = len - 2;
uint8_t* payload_data = &temp_buf1[2];
/* 默认 0x03 为 RS485 透传数据 */
uint8_t source_type = 0x03;
/* 判断是不是 $DI 标签 */
if (payload_len >= 3 && payload_data[0] == '$' && payload_data[1] == 'D' && payload_data[2] == 'I')
{
source_type = 0x01; /* 也是 DI 口数据,但不砍标签了,直接全发过去 */
}
/* 判断是不是网口 [NET] 标签 */
else if (payload_len >= 5 && payload_data[0] == '[' && payload_data[1] == 'N' && payload_data[2] == 'E' && payload_data[3] == 'T' && payload_data[4] == ']')
{
source_type = 0x02; /* 0x02 代表是 网络口 收到的数据 */
payload_data += 5; /* 砍掉 "[NET]" 标签 */
payload_len -= 5;
}
/* ========================================================== */
MultiUART_Send(PORT_RS485, (uint8_t*)u1_rx_buffer, len);
MultiUART_Send(PORT_DEBUG, (uint8_t*)u1_rx_buffer, len);
}
#endif
if (payload_len > 0) {
/* 重新组装终极协议帧 */
uint8_t upper_buf[260];
upper_buf[0] = 0xAA; // Byte 0: 魔法帧头
upper_buf[1] = sender_id; // Byte 1: 发送设备 ID
upper_buf[2] = source_type; // Byte 2: 数据来源 (1=DI, 2=NET, 3=485)
upper_buf[3] = (uint8_t)payload_len; // Byte 3: 真实数据长度
memcpy(&upper_buf[4], payload_data, payload_len); // Byte 4~末尾: 绝对纯净的数据
/* === 3. 核心发送保护区 (TX 优先调度) === */
// 只有当我们单片机正在往 433 模块灌数时,才进行避让
// 只要单片机串口引擎一空闲,主循环就立刻开始处理后续采集任务
if (RF433_UART_Is_Busy()) {
continue;
}
/* 发送给 485 和电脑上位机 */
MultiUART_Send(PORT_UART3, upper_buf, payload_len + 4);
MultiUART_Send(PORT_UART2, upper_buf, payload_len + 4);
}
}
else
{
/* 普通无帧头干扰数据,按原样透传 */
MultiUART_Send(PORT_UART3, temp_buf1, len);
MultiUART_Send(PORT_UART2, temp_buf1, len);
}
/* === 4. 实时数据采集与上报 (仅在非发射状态运行) === */
/* === 方案 B从 485 收到设备数据 -> 穿上包装(附加ID) -> 通过 433 无线发射 === */
// (A) 485 来源数据处理 (Type 0x48)
#if USE_RS485
if (u3_rx_len > 0 && (HAL_GetTick() - u3_last_rx_time > 20))
{
static uint8_t temp_buf3[512];
@ -317,19 +366,66 @@ int main(void)
u3_rx_len = 0;
__enable_irq();
/* 🚀 制作“快递包”:在最前面加上 [0xAA] 和 [本机ID] */
static uint8_t rf_tx_buf[515];
rf_tx_buf[0] = 0xAA; // 贴上魔法帧头
rf_tx_buf[1] = MY_DEVICE_ID; // 贴上本机的身份证号
memcpy(&rf_tx_buf[2], temp_buf3, len); // 把 485 收到的真实数据塞进后面
/* 把带有身份证的完整包裹,通过 433 发射到空气中 */
MultiUART_Send(PORT_UART1, rf_tx_buf, len + 2);
RF433_SendPacket(PROTO_TYPE_485, temp_buf3, len);
}
#endif
// (B) I/O 状态监控与变化上报 (Type 0x10)
#if USE_IO_MONITOR
IO_Monitor_Task(); // 执行去抖扫描
uint8_t current_io = IO_Monitor_GetAllStates();
if (current_io != g_last_io_state) {
if (g_last_io_state == 0xFF) {
g_last_io_state = current_io;
} else {
g_last_io_state = current_io;
RF433_SendPacket(PROTO_TYPE_IO, &current_io, 1);
}
}
#endif
// (C) 30秒系统心跳包 (Type 0xAA)
#if USE_IO_MONITOR
if (HAL_GetTick() - g_last_hb_tick >= 30000) {
g_last_hb_tick = HAL_GetTick();
uint8_t hb_payload[7];
uint8_t io_state = IO_Monitor_GetAllStates();
#if USE_W5500
uint8_t phy_link_status;
ctlwizchip(CW_GET_PHYLINK, (void *)&phy_link_status);
if (phy_link_status == PHY_LINK_ON) {
io_state |= 0x80;
}
#endif
hb_payload[0] = (uint8_t)(g_hb_seq >> 8);
hb_payload[1] = (uint8_t)(g_hb_seq & 0xFF);
hb_payload[2] = (uint8_t)(XTELL_FIRMWARE_CODE >> 8);
hb_payload[3] = (uint8_t)(XTELL_FIRMWARE_CODE & 0xFF);
hb_payload[4] = io_state;
uint16_t modbus_val = 0xFFFF;
#if USE_W5500
modbus_val = ModbusTCP_Get_LastRegVal();
#endif
hb_payload[5] = (uint8_t)(modbus_val >> 8);
hb_payload[6] = (uint8_t)(modbus_val & 0xFF);
g_hb_seq++;
RF433_SendPacket(PROTO_TYPE_HB, hb_payload, sizeof(hb_payload));
}
#endif
#if USE_W5500
ModbusTCP_Client_Task();
#endif
/* USER CODE END WHILE */
}
}
}
/* USER CODE END 3 */
/**
@ -433,7 +529,7 @@ void HAL_UART_TxCpltCallback(UART_HandleTypeDef *huart)
if (huart->Instance == USART1)
{
/* 调用多UART路由器的UART1发送完成回调 */
MultiUART_TxCpltCallback(PORT_UART1);
MultiUART_TxCpltCallback(PORT_433);
}
else if (huart->Instance == USART2)
{
@ -444,7 +540,7 @@ void HAL_UART_TxCpltCallback(UART_HandleTypeDef *huart)
{
/* 调用多UART路由器的UART3发送完成回调 */
MultiUART_TxCpltCallback(PORT_UART3);
MultiUART_TxCpltCallback(PORT_RS485);
}
}

View File

@ -0,0 +1,182 @@
/**
******************************************************************************
* @file modbus_tcp_client.c
* @brief Modbus TCP 客户端模块实现 (针对寄存器 40031 轮询)
******************************************************************************
*/
#include "modbus_tcp_client.h"
#include "socket.h"
#include "wizchip_conf.h"
#include "main.h"
#include "debug_log.h"
#include <string.h>
/* 私有变量 */
static uint8_t g_sn = 0;
static modbus_client_state_t g_state = MODBUS_STATE_IDLE;
static uint32_t g_last_tick = 0;
static uint16_t g_transaction_id = 0;
/* 保存最新的寄存器值,用于心跳上报和变化检测 */
static uint16_t s_last_reg_val = 0xFFFF;
uint16_t ModbusTCP_Get_LastRegVal(void)
{
return s_last_reg_val;
}
/* 服务器信息 */
static uint8_t dest_ip[4] = MODBUS_SERVER_IP;
static uint16_t dest_port = MODBUS_SERVER_PORT;
/**
* @brief 构造 Modbus TCP 请求包 (FC 03)
*/
static uint16_t build_read_request(uint8_t *buf, uint16_t addr, uint16_t qty)
{
g_transaction_id++;
/* MBAP Header */
buf[0] = (uint8_t)(g_transaction_id >> 8);
buf[1] = (uint8_t)(g_transaction_id & 0xFF);
buf[2] = 0x00; /* Protocol ID (0 for Modbus) */
buf[3] = 0x00;
buf[4] = 0x00; /* Length (6 bytes follow UnitID) */
buf[5] = 0x06;
buf[6] = MODBUS_UNIT_ID;
/* PDU */
buf[7] = 0x03; /* Function Code: Read Holding Registers */
buf[8] = (uint8_t)(addr >> 8);
buf[9] = (uint8_t)(addr & 0xFF);
buf[10] = (uint8_t)(qty >> 8);
buf[11] = (uint8_t)(qty & 0xFF);
return 12;
}
void ModbusTCP_Client_Init(uint8_t sn)
{
g_sn = sn;
g_state = MODBUS_STATE_IDLE;
g_last_tick = HAL_GetTick();
/* 动态重新加载配置,防止静态初始化带来的宏定义未生效问题 */
uint8_t ip[4] = MODBUS_SERVER_IP;
dest_ip[0] = ip[0]; dest_ip[1] = ip[1]; dest_ip[2] = ip[2]; dest_ip[3] = ip[3];
dest_port = MODBUS_SERVER_PORT;
LOG_INFO("MODBUS", "Client initialized on Socket %d, Target: %d.%d.%d.%d:%d",
sn, dest_ip[0], dest_ip[1], dest_ip[2], dest_ip[3], dest_port);
}
void ModbusTCP_Client_Task(void)
{
uint8_t tmp_buf[128]; // 临时接收缓存
uint16_t len; // 接收长度
int32_t ret; // 返回值
switch (g_state) // 客户端状态机切换
{
case MODBUS_STATE_IDLE: // 空闲状态
if (HAL_GetTick() - g_last_tick >= MODBUS_POLL_INTERVAL) { // 检查轮询间隔 (2秒)
g_state = MODBUS_STATE_CONNECTING; // 切换到连接状态
}
break;
case MODBUS_STATE_CONNECTING: // 连接中状态
{
uint8_t sr = getSn_SR(g_sn);
switch(sr) // 获取当前 Socket 状态
{
case SOCK_CLOSED: // 如果 Socket 已关闭
// 打开 TCP 模式的 Socket分配随机本地端口以避免冲突
if (socket(g_sn, Sn_MR_TCP, 50000 + (HAL_GetTick() % 10000), 0x00) == g_sn) {
LOG_DEBUG("MODBUS", "Socket opened");
}
break;
case SOCK_INIT: // Socket 初始化成功,开始连接
LOG_INFO("MODBUS", "Connecting to %d.%d.%d.%d:%d",
dest_ip[0], dest_ip[1], dest_ip[2], dest_ip[3], dest_port);
ret = connect(g_sn, dest_ip, dest_port); // 发起连接请求
if (ret != SOCK_OK) {
LOG_ERROR("MODBUS", "Connect failed: %d", ret);
close(g_sn);
g_state = MODBUS_STATE_IDLE;
g_last_tick = HAL_GetTick();
}
break;
case SOCK_ESTABLISHED: // 连接已建立
LOG_INFO("MODBUS", "TCP Connected!");
g_state = MODBUS_STATE_SEND_QUERY; // 切换到发送请求状态
break;
case SOCK_CLOSE_WAIT: // 对方已关闭连接
disconnect(g_sn); // 本地断开连接
break;
default:
if (HAL_GetTick() % 5000 == 0) { // 每 5 秒打印一次未处理的状态
LOG_WARN("MODBUS", "Unhandled socket state: 0x%02X", sr);
}
break;
}
break;
}
case MODBUS_STATE_SEND_QUERY: // 发送查询请求状态
len = build_read_request(tmp_buf, TARGET_REG_ADDR, 1); // 构造 Modbus TCP FC03 报文
ret = send(g_sn, tmp_buf, len); // 发送 TCP 数据
if (ret > 0) { // 发送成功
LOG_DEBUG("MODBUS", "Request sent (TID: %d)", g_transaction_id);
g_state = MODBUS_STATE_WAIT_RESPONSE; // 切换到等待响应状态
g_last_tick = HAL_GetTick(); // 更新计时器
} else { // 发送失败
LOG_ERROR("MODBUS", "Send failed, reconnecting...");
close(g_sn); // 关闭 Socket
g_state = MODBUS_STATE_IDLE; // 返回空闲重试
}
break;
case MODBUS_STATE_WAIT_RESPONSE: // 等待响应状态
len = getSn_RX_RSR(g_sn);
if (len >= 9) { // 至少需要 9 字节 (MBAP 头 7 字节 + PDU 至少 2 字节)
if (len > sizeof(tmp_buf)) len = sizeof(tmp_buf); // 防止缓存溢出
ret = recv(g_sn, tmp_buf, len); // 接收数据
/* 校验响应 (检查 MBAP 长度、功能码等) */
if (ret >= 9 && tmp_buf[7] == 0x03) { // 基本校验
uint16_t reg_val = (tmp_buf[9] << 8) | tmp_buf[10]; // 提取寄存器值
LOG_INFO("MODBUS", "Read Register %d OK: 0x%04X", TARGET_REG_ADDR + 40001, reg_val);
/* 如果检测到寄存器值发生变化,才通过 433 无线立即发送 */
if (reg_val != s_last_reg_val) {
s_last_reg_val = reg_val; // 更新缓存的值
uint8_t payload[2]; // 构造 433 负载
payload[0] = tmp_buf[9]; // 寄存器高位
payload[1] = tmp_buf[10]; // 寄存器低位
RF433_SendPacket(PROTO_TYPE_NET, payload, 2); // 打包并通过无线发出
LOG_INFO("MODBUS", "Value changed, sent over 433");
}
} else { // 响应格式非法
LOG_ERROR("MODBUS", "Invalid response format");
}
g_state = MODBUS_STATE_IDLE; // 返回空闲
g_last_tick = HAL_GetTick(); // 更新计时
} else if (HAL_GetTick() - g_last_tick > 3000) { // 等待超时 (3秒)
LOG_WARN("MODBUS", "Response timeout");
close(g_sn); // 关闭连接
g_state = MODBUS_STATE_IDLE; // 返回空闲重试
}
break;
default: // 异常保护
g_state = MODBUS_STATE_IDLE;
break;
}
}

View File

@ -16,14 +16,15 @@
* 4. 响应路由表
*
* 端口映射:
* - PORT_UART1: 连接RF433无线模块(用于无线数据收发)
* - PORT_UART2: 调试串口(用于日志和调试输出)
* - PORT_UART3: 预留扩展端口
* - PORT_433: 连接RF433无线模块(用于无线数据收发)
* - PORT_DEBUG: 调试串口(用于日志和调试输出)
* - PORT_RS485: 预留扩展端口
******************************************************************************
*/
#include "multi_uart_router.h"
#include "uart2_print.h"
#include "main.h"
#include <string.h>
#include <stdarg.h>
#include <stdio.h>
@ -41,6 +42,16 @@
#define DEBUG_LOG(fmt, ...)
#endif
/*==============================================================================
* CSMA/CA 随机退避相关
*============================================================================*/
static uint32_t csma_rand(uint32_t seed)
{
// static uint32_t seed = 12345;
seed = seed * 1103515245 + 12345;
return (seed >> 16) & 0x7FFF;
}
/*==============================================================================
* 全局变量定义
*============================================================================*/
@ -57,9 +68,9 @@ static uart_port_context_t g_port_ctx[PORT_COUNT];
* 使用常量初始化,在编译时确定,无运行时开销
*/
static UART_HandleTypeDef *const g_port_uart_map[PORT_COUNT] = {
[PORT_UART1] = &huart1, /**< RF433无线模块 */
[PORT_UART2] = &huart2, /**< 调试串口 */
[PORT_UART3] = &huart3, /**< 预留扩展 */
[PORT_433] = &huart1, /**< RF433无线模块 */
[PORT_DEBUG] = &huart2, /**< 调试串口 */
[PORT_RS485] = &huart3, /**< 预留扩展 */
};
/**
@ -67,9 +78,9 @@ static UART_HandleTypeDef *const g_port_uart_map[PORT_COUNT] = {
* @note 用于调试日志输出,快速获取端口的可读名称
*/
static const char *const g_port_name_map[PORT_COUNT] = {
[PORT_UART1] = "UART1", /**< RF433无线模块 */
[PORT_UART2] = "UART2", /**< 调试串口 */
[PORT_UART3] = "UART3", /**< 预留扩展 */
[PORT_433] = "UART1", /**< RF433无线模块 */
[PORT_DEBUG] = "UART2", /**< 调试串口 */
[PORT_RS485] = "UART3", /**< 预留扩展 */
};
/*==============================================================================
@ -234,7 +245,23 @@ static void tx_kickoff(port_id_t port_id)
__disable_irq();
if (!ring->is_sending && ring->count > 0) {
/* 取出下一个待发送字节 */
if (port_id == PORT_433) {
if (ctx->csma_backoff_active) {
if ((int32_t)(HAL_GetTick() - ctx->csma_backoff_until) < 0) {
__enable_irq();
return;
}
ctx->csma_backoff_active = false;
}
if (HAL_GPIO_ReadPin(AUX_GPIO_Port, AUX_Pin) == GPIO_PIN_RESET) {
ctx->csma_backoff_active = true;
ctx->csma_backoff_until = HAL_GetTick() + (csma_rand(HAL_GetTick()) % 1000) + 1;
__enable_irq();
return;
}
}
byte = ring->buffer[ring->tail];
ring->tail = (ring->tail + 1) % UART_TX_BUFFER_SIZE;
ring->count--;
@ -287,6 +314,10 @@ void MultiUART_Init(void)
ctx->tx_count = 0;
ctx->error_count = 0;
ctx->initialized = true;
/* 初始化 CSMA/CA 随机退避状态 */
ctx->csma_backoff_active = false;
ctx->csma_backoff_until = 0;
}
DEBUG_LOG("Init OK, %d ports configured", PORT_COUNT);
@ -344,7 +375,7 @@ void MultiUART_FeedByte(port_id_t port_id, uint8_t byte)
* 接收处理由中断完成(MultiUART_FeedByte),此函数仅处理发送
*
* 端口跳过说明:
* - 跳过PORT_UART2(调试串口)由UART2_Print模块独立处理
* - 跳过PORT_DEBUG(调试串口)由UART2_Print模块独立处理
*
* 调用时机:
* 建议在主循环中周期性调用(如10ms定时)
@ -360,7 +391,7 @@ void MultiUART_Task(void)
}
/* 跳过调试串口(UART2) */
if (i == PORT_UART2) {
if (i == PORT_DEBUG) {
continue;
}
@ -379,7 +410,7 @@ void MultiUART_Task(void)
* @return 无
*
* 特殊处理:
* - PORT_UART2直接调用UART2_Print_Send由调试模块处理
* - PORT_DEBUG直接调用UART2_Print_Send由调试模块处理
* - 其他端口使用本模块的环形缓冲区机制
*
* 发送流程:
@ -400,7 +431,7 @@ void MultiUART_Send(port_id_t port_id, const uint8_t *data, uint16_t len)
* 调试串口(UART2)特殊处理
* 调试打印不走环形缓冲区,直接发送
*----------------------------------------------------------*/
if (port_id == PORT_UART2) {
if (port_id == PORT_DEBUG) {
UART2_Print_Send(data, len);
return;
}
@ -487,7 +518,7 @@ void MultiUART_SendFmt(port_id_t port_id, const char *fmt, ...)
* @return 无
*
* 特殊处理:
* - PORT_UART2调用UART2_Print_TxCpltCallback处理
* - PORT_DEBUG调用UART2_Print_TxCpltCallback处理
*
* 发送驱动逻辑:
* 1. 清除is_sending标志
@ -504,7 +535,7 @@ void MultiUART_TxCpltCallback(port_id_t port_id)
}
/* 调试串口(UART2)特殊处理 */
if (port_id == PORT_UART2) {
if (port_id == PORT_DEBUG) {
UART2_Print_TxCpltCallback();
return;
}
@ -660,3 +691,22 @@ uint32_t MultiUART_GetOverflowCount(port_id_t port_id)
return g_port_ctx[port_id].rx_ring.overflow_count +
g_port_ctx[port_id].tx_ring.overflow_count;
}
/**
* @brief 检查指定端口是否正忙于发送
* @param port_id: 端口ID
* @return bool: true=忙碌(有待发数据或硬件发送中), false=空闲
*/
bool MultiUART_IsBusy(uint8_t port_id)
{
if (port_id >= PORT_COUNT) return false;
// 调试串口特殊处理
if (port_id == PORT_DEBUG) {
// UART2_Print 使用单独的标志位,这里简单兼容
return false;
}
// 直接读取状态,不屏蔽中断,追求极致性能
return (g_port_ctx[port_id].tx_ring.count > 0 || g_port_ctx[port_id].tx_ring.is_sending);
}

View File

@ -462,7 +462,7 @@ int fputc(int ch, FILE *f)
{
(void)f;
UART2_Print_Send((uint8_t *)&ch, 1);
MultiUART_Send(PORT_UART3, (uint8_t *)&ch, 1); /* 增加:同时发给 UART3 */
// MultiUART_Send(PORT_RS485, (uint8_t *)&ch, 1); /* 增加:同时发给 UART3 */
return ch;
}
#endif
@ -471,7 +471,7 @@ int fputc(int ch, FILE *f)
int __io_putchar(int ch)
{
UART2_Print_Send((uint8_t *)&ch, 1);
MultiUART_Send(PORT_UART3, (uint8_t *)&ch, 1); /* 增加:同时发给 UART3 */
// MultiUART_Send(PORT_RS485, (uint8_t *)&ch, 1); /* 增加:同时发给 UART3 */
return ch;
}
@ -479,7 +479,7 @@ int _write(int file, char *ptr, int len)
{
(void)file;
UART2_Print_Send((uint8_t *)ptr, len);
MultiUART_Send(PORT_UART3, (uint8_t *)ptr, len); /* 增加:同时发给 UART3 */
// MultiUART_Send(PORT_RS485, (uint8_t *)ptr, len); /* 增加:同时发给 UART3 */
return len;
}
#endif

View File

@ -208,7 +208,7 @@ void Passthrough_Task(void)
}
uint8_t byte = node->data[node->offset++];
MultiUART_Send(PORT_UART1, &byte, 1);
MultiUART_Send(PORT_433, &byte, 1);
ctx->queue.pending_count--;
ctx->stats.total_bytes_sent++;
@ -232,7 +232,7 @@ void Passthrough_OnTxComplete(void)
*/
bool Passthrough_CanSend(void)
{
return (MultiUART_GetTxAvailable(PORT_UART1) > 0) &&
return (MultiUART_GetTxAvailable(PORT_433) > 0) &&
(g_passthrough_ctx.queue.pending_count > 0);
}

File diff suppressed because it is too large Load Diff

View File

@ -1,6 +1,7 @@
/*
* UVISION generated file: DO NOT EDIT!
* Generated by: uVision version 5.43.1.0
* Auto generated Run-Time-Environment Component Configuration File
* *** Do not modify ! ***
*
* Project: 'project'
* Target: 'project'
@ -16,5 +17,4 @@
#define CMSIS_device_header "stm32f10x.h"
#endif /* RTE_COMPONENTS_H */

File diff suppressed because one or more lines are too long

View File

@ -10,14 +10,14 @@
<TargetName>project</TargetName>
<ToolsetNumber>0x4</ToolsetNumber>
<ToolsetName>ARM-ADS</ToolsetName>
<pCCUsed>5060960::V5.06 update 7 (build 960)::.\ARMCC</pCCUsed>
<pCCUsed>5060750::V5.06 update 6 (build 750)::ARMCC</pCCUsed>
<uAC6>0</uAC6>
<TargetOption>
<TargetCommonOption>
<Device>STM32F103C8</Device>
<Vendor>STMicroelectronics</Vendor>
<PackID>Keil.STM32F1xx_DFP.2.4.1</PackID>
<PackURL>https://www.keil.com/pack/</PackURL>
<PackID>Keil.STM32F1xx_DFP.1.1.0</PackID>
<PackURL>http://www.keil.com/pack/</PackURL>
<Cpu>IRAM(0x20000000-0x20004FFF) IROM(0x8000000-0x800FFFF) CLOCK(8000000) CPUTYPE("Cortex-M3") TZ</Cpu>
<FlashUtilSpec></FlashUtilSpec>
<StartupFile></StartupFile>
@ -81,7 +81,7 @@
</BeforeMake>
<AfterMake>
<RunUserProg1>0</RunUserProg1>
<RunUserProg2>1</RunUserProg2>
<RunUserProg2>0</RunUserProg2>
<UserProg1Name></UserProg1Name>
<UserProg2Name></UserProg2Name>
<UserProg1Dos16Mode>0</UserProg1Dos16Mode>
@ -184,9 +184,6 @@
<hadXRAM>0</hadXRAM>
<uocXRam>0</uocXRam>
<RvdsVP>0</RvdsVP>
<RvdsMve>0</RvdsMve>
<RvdsCdeCp>0</RvdsCdeCp>
<nBranchProt>0</nBranchProt>
<hadIRAM2>0</hadIRAM2>
<hadIROM2>0</hadIROM2>
<StupSel>8</StupSel>
@ -353,7 +350,7 @@
<NoWarn>0</NoWarn>
<uSurpInc>0</uSurpInc>
<useXO>0</useXO>
<ClangAsOpt>1</ClangAsOpt>
<uClangAs>0</uClangAs>
<VariousControls>
<MiscControls></MiscControls>
<Define></Define>
@ -414,6 +411,11 @@
<FileType>1</FileType>
<FilePath>../Core/Src/main.c</FilePath>
</File>
<File>
<FileName>modbus_tcp_client.c</FileName>
<FileType>1</FileType>
<FilePath>../Core/Src/modbus_tcp_client.c</FilePath>
</File>
<File>
<FileName>gpio.c</FileName>
<FileType>1</FileType>
@ -783,14 +785,4 @@
<files/>
</RTE>
<LayerInfo>
<Layers>
<Layer>
<LayName>project</LayName>
<LayTarg>0</LayTarg>
<LayPrjMark>1</LayPrjMark>
</Layer>
</Layers>
</LayerInfo>
</Project>

View File

@ -4,6 +4,7 @@
"project\rf433_rx_app.o"
"project\rf433_tx_app.o"
"project\main.o"
"project\modbus_tcp_client.o"
"project\gpio.o"
"project\spi.o"
"project\usart.o"

View File

@ -7,7 +7,6 @@ LR_IROM1 0x08000000 0x00010000 { ; load region size_region
*.o (RESET, +First)
*(InRoot$$Sections)
.ANY (+RO)
.ANY (+XO)
}
RW_IRAM1 0x20000000 0x00005000 { ; RW data
.ANY (+RW +ZI)

View File

@ -0,0 +1,16 @@
; *************************************************************
; *** Scatter-Loading Description File generated by uVision ***
; *************************************************************
LR_IROM1 0x08000000 0x00010000 { ; load region size_region
ER_IROM1 0x08000000 0x00010000 { ; load address = execution address
*.o (RESET, +First)
*(InRoot$$Sections)
.ANY (+RO)
.ANY (+XO)
}
RW_IRAM1 0x20000000 0x00005000 { ; RW data
.ANY (+RW +ZI)
}
}

View File

@ -461,11 +461,11 @@ ARM Macro Assembler Page 8
Command Line: --debug --xref --diag_suppress=9931 --cpu=Cortex-M3 --apcs=interw
ork --depend=project\startup_stm32f103xb.d -oproject\startup_stm32f103xb.o -I.\
RTE\_project -IC:\Users\xtell\AppData\Local\Arm\Packs\ARM\CMSIS\6.2.0\CMSIS\Cor
e\Include -IC:\Users\xtell\AppData\Local\Arm\Packs\Keil\STM32F1xx_DFP\2.4.1\Dev
ice\Include --predefine="__MICROLIB SETA 1" --predefine="__UVISION_VERSION SETA
543" --predefine="STM32F10X_MD SETA 1" --predefine="_RTE_ SETA 1" --list=start
up_stm32f103xb.lst startup_stm32f103xb.s
RTE\_project -IC:\Keil_v5\ARM\PACK\ARM\CMSIS\5.4.0\CMSIS\Core\Include -IC:\Keil
_v5\ARM\PACK\Keil\STM32F1xx_DFP\1.1.0\Device\Include --predefine="__MICROLIB SE
TA 1" --predefine="__UVISION_VERSION SETA 525" --predefine="_RTE_ SETA 1" --pre
define="STM32F10X_MD SETA 1" --list=startup_stm32f103xb.lst startup_stm32f103xb
.s

View File

@ -245,22 +245,10 @@ int32_t loopback_udps(uint8_t sn, uint8_t *buf, uint16_t port)
}
size = (uint16_t)ret;
/* ========================================================== *
/* 🚀 核心修改:网络数据透传时,加上 [0xAA] 和设备 ID */
uint8_t tx_buf[2048];
// 1. 添加统一的空中协议头 (0xAA + ID)
tx_buf[0] = 0xAA;
tx_buf[1] = MY_DEVICE_ID;
// 2. 把网络标识 "[NET]" 写进数组,注意要从第 2 个字节开始写
int tag_len = sprintf((char*)&tx_buf[2], "[NET]");
// 3. 把网络收到的真实数据 (buf) 紧挨着拼接到后面
memcpy(&tx_buf[2 + tag_len], buf, size);
// 4. 把拼接好的整串数据 (头 + ID + [NET] + 数据) 发给 RF433
MultiUART_Send(PORT_UART1, tx_buf, 2 + tag_len + size);
/* ========================================================== *
* 🚀 核心修改:使用统一协议函数发送网络数据 (Type 0x55)
* ========================================================== */
RF433_SendPacket(PROTO_TYPE_NET, buf, size);
/* ========================================================== */
sentsize = 0;
while (sentsize != size)

View File

@ -4,6 +4,7 @@
#include "wizchip_conf.h"
#include "wiz_interface.h"
#include "loopback.h"
#include "main.h"
/*wizchip->STM32 Hardware Pin define*/
// wizchip_SCS ---> STM32_GPIOD7
@ -16,15 +17,19 @@
/* Define network information */
wiz_NetInfo default_net_info = {
.mac = {0x00, 0x08, 0xdc, 0x12, 0x22, 0x12},
.ip = {192, 168, 6, 212},
.gw = {192, 168, 6, 1},
#if TEST_A701
.ip = {192, 168, 0, 212},
.gw = {192, 168, 0, 1},
#else
.ip = {192, 168, 0, 5},
.gw = {192, 168, 0, 1},
#endif
.sn = {255, 255, 255, 0},
.dns = {8, 8, 8, 8},
.dhcp = NETINFO_STATIC
//.dhcp = NETINFO_STATIC //static ip
};
uint16_t local_port = 8000;
static uint8_t ethernet_buf[ETHERNET_BUF_MAX_SIZE] = {0};
uint8_t ethernet_buf[ETHERNET_BUF_MAX_SIZE] = {0};
/**
* @brief User Run Program
* @param none

View File

@ -2,6 +2,7 @@
#include "wiz_platform.h"
#include "wizchip_conf.h"
#include "dhcp.h"
#include "main.h"
#include <stdio.h>
#include <stdlib.h>
#include <string.h>
@ -93,57 +94,60 @@ void wiz_delete_timer(void (*func)(void))
}
/**
* @brief wiz timer event handler
* @brief wiz timer event handler (using HAL_GetTick)
*
* You must add this function to your 1ms timer interrupt
*
*/
void wiz_timer_handler(void)
{
static uint32_t last_tick = 0;
uint32_t current_tick = HAL_GetTick();
wiz_delay_ms_count++;
struct wiz_timer *temp = wiz_timer_head;
while (temp != NULL)
{
temp->count_time++;
if (temp->count_time >= temp->trigger_time)
if (current_tick != last_tick) {
last_tick = current_tick;
struct wiz_timer *temp = wiz_timer_head;
while (temp != NULL)
{
temp->count_time = 0;
temp->func();
temp->count_time++;
if (temp->count_time >= temp->trigger_time)
{
temp->count_time = 0;
temp->func();
}
temp = temp->next;
}
temp = temp->next;
}
}
/**
* @brief Delay function in milliseconds
* @brief Delay function in milliseconds (using HAL_GetTick)
* @param nms :Delay Time
*/
void wiz_user_delay_ms(uint32_t nms)
{
wiz_delay_ms_count = 0;
while (wiz_delay_ms_count < nms)
{
uint32_t start = HAL_GetTick();
while ((HAL_GetTick() - start) < nms) {
}
}
/**
* @brief Check the WIZCHIP version
* @brief Check the WIZCHIP version (with timeout)
*/
void wizchip_version_check(void)
{
uint8_t error_count = 0;
while (1)
uint32_t start_tick = HAL_GetTick();
while ((HAL_GetTick() - start_tick) < 5000)
{
wiz_user_delay_ms(1000);
wiz_user_delay_ms(100);
if (getVERSIONR() != W5500_VERSION)
{
error_count++;
if (error_count > 5)
{
printf("error, W5500 version is 0x%02x, but read W5500 version value = 0x%02x\r\n", W5500_VERSION, getVERSIONR());
while (1)
;
printf("WARN: W5500 version check failed, SPI may be disconnected\r\n");
break;
}
}
else
@ -165,25 +169,26 @@ void wiz_print_phy_info(void)
}
/**
* @brief Ethernet Link Detection
* @brief Ethernet Link Detection (with timeout)
*/
void wiz_phy_link_check(void)
{
uint8_t phy_link_status;
do
uint32_t start_tick = HAL_GetTick();
while ((HAL_GetTick() - start_tick) < 10000)
{
wiz_user_delay_ms(1000);
wiz_user_delay_ms(500);
ctlwizchip(CW_GET_PHYLINK, (void *)&phy_link_status);
if (phy_link_status == PHY_LINK_ON)
{
printf("PHY link\r\n");
wiz_print_phy_info();
return;
}
else
{
printf("PHY no link\r\n");
}
} while (phy_link_status == PHY_LINK_OFF);
}
printf("WARN: PHY link timeout, using static config\r\n");
}
/**

View File

@ -138,7 +138,7 @@
void HAL_UART_RxCpltCallback(UART_HandleTypeDef *huart)
{
if (huart->Instance == USART3) {
MultiUART_FeedByte(PORT_UART3, uart3_rx_byte);
MultiUART_FeedByte(PORT_RS485, uart3_rx_byte);
HAL_UART_Receive_IT(&huart3, &uart3_rx_byte, 1);
}
}
@ -149,7 +149,7 @@ void CmdRouter_Task(void)
// ... UART1/UART3处理 ...
for (port_id_t port_id = 0; port_id < PORT_COUNT; port_id++) {
if (port_id == PORT_UART2) continue; // UART2单独处理
if (port_id == PORT_DEBUG) continue; // UART2单独处理
uint8_t byte;
while (MultiUART_ReadByte(port_id, &byte) > 0) {
@ -380,7 +380,7 @@ void Passthrough_Task(void)
if (node->offset < node->length) {
// 发送一个字节
uint8_t byte = node->data[node->offset++];
MultiUART_Send(PORT_UART1, &byte, 1);
MultiUART_Send(PORT_433, &byte, 1);
}
// 检查节点是否发送完成
@ -659,7 +659,7 @@ void CmdRouter_Task_UART3_Enhanced(void)
// 1. 读取UART3接收缓冲区
uint8_t byte;
while (MultiUART_ReadByte(PORT_UART3, &byte) > 0) {
while (MultiUART_ReadByte(PORT_RS485, &byte) > 0) {
// 2. 协议识别
route_result_t route = UART3_Protocol_FeedByte(byte, current_tick);
@ -844,7 +844,7 @@ void Passthrough_Task(void)
// 发送一个字节
uint8_t byte = node->data[node->offset++];
MultiUART_Send(PORT_UART1, &byte, 1);
MultiUART_Send(PORT_433, &byte, 1);
ctx->queue.pending_count--;
ctx->stats.total_bytes_sent++;
@ -902,7 +902,7 @@ uint16_t Passthrough_PushBuffer(const uint8_t *data, uint16_t length)
bool Passthrough_CanSend(void)
{
// 检查UART1 TX是否忙
return (MultiUART_GetTxAvailable(PORT_UART1) > 0) &&
return (MultiUART_GetTxAvailable(PORT_433) > 0) &&
(g_passthrough_ctx.queue.pending_count > 0);
}
```
@ -934,8 +934,8 @@ void CmdRouter_Task(void)
#else
// 原有逻辑所有数据喂给CmdParser
uint8_t byte;
while (MultiUART_ReadByte(PORT_UART3, &byte) > 0) {
CmdParser_SetSourcePort(PORT_UART3);
while (MultiUART_ReadByte(PORT_RS485, &byte) > 0) {
CmdParser_SetSourcePort(PORT_RS485);
CmdParser_FeedByte(byte, current_tick);
}
#endif
@ -955,14 +955,14 @@ static void UART3_SmartRouter_Task(uint32_t current_tick)
uint8_t byte;
// 读取所有待处理的字节
while (MultiUART_ReadByte(PORT_UART3, &byte) > 0) {
while (MultiUART_ReadByte(PORT_RS485, &byte) > 0) {
// 协议识别
route_result_t route = UART3_Protocol_FeedByte(byte, current_tick);
switch (route) {
case ROUTE_CMD:
// 指令路径
CmdParser_SetSourcePort(PORT_UART3);
CmdParser_SetSourcePort(PORT_RS485);
CmdParser_FeedByte(byte, current_tick);
LOG_DEBUG("[UART3] CMD byte: 0x%02X", byte);
break;
@ -997,7 +997,7 @@ static void UART3_SmartRouter_Task(uint32_t current_tick)
#### 3.3.2 透传引擎发送接口
```c
// 复用现有的 MultiUART_Send(PORT_UART1, data, len)
// 复用现有的 MultiUART_Send(PORT_433, data, len)
// 透传引擎将数据写入UART1的发送缓冲区
// 由MultiUART_TxCpltCallback驱动后续发送
```

BIN
docs/temp.zip Normal file

Binary file not shown.

View File

@ -0,0 +1,2 @@
<?xml version="1.0" encoding="UTF-8" standalone="yes"?>
<Types xmlns="http://schemas.openxmlformats.org/package/2006/content-types"><Default Extension="rels" ContentType="application/vnd.openxmlformats-package.relationships+xml"/><Default Extension="xml" ContentType="application/xml"/><Override PartName="/docProps/app.xml" ContentType="application/vnd.openxmlformats-officedocument.extended-properties+xml"/><Override PartName="/docProps/core.xml" ContentType="application/vnd.openxmlformats-package.core-properties+xml"/><Override PartName="/docProps/custom.xml" ContentType="application/vnd.openxmlformats-officedocument.custom-properties+xml"/><Override PartName="/xl/customStorage/customStorage.xml" ContentType="application/vnd.wps-officedocument.customStorage+xml"/><Override PartName="/xl/sharedStrings.xml" ContentType="application/vnd.openxmlformats-officedocument.spreadsheetml.sharedStrings+xml"/><Override PartName="/xl/styles.xml" ContentType="application/vnd.openxmlformats-officedocument.spreadsheetml.styles+xml"/><Override PartName="/xl/theme/theme1.xml" ContentType="application/vnd.openxmlformats-officedocument.theme+xml"/><Override PartName="/xl/workbook.xml" ContentType="application/vnd.openxmlformats-officedocument.spreadsheetml.sheet.main+xml"/><Override PartName="/xl/worksheets/sheet1.xml" ContentType="application/vnd.openxmlformats-officedocument.spreadsheetml.worksheet+xml"/></Types>

View File

@ -0,0 +1,2 @@
<?xml version="1.0" encoding="UTF-8" standalone="yes"?>
<Relationships xmlns="http://schemas.openxmlformats.org/package/2006/relationships"><Relationship Id="rId1" Type="http://schemas.openxmlformats.org/officeDocument/2006/relationships/officeDocument" Target="xl/workbook.xml"/><Relationship Id="rId3" Type="http://schemas.openxmlformats.org/package/2006/relationships/metadata/core-properties" Target="docProps/core.xml"/><Relationship Id="rId2" Type="http://schemas.openxmlformats.org/officeDocument/2006/relationships/extended-properties" Target="docProps/app.xml"/><Relationship Id="rId4" Type="http://schemas.openxmlformats.org/officeDocument/2006/relationships/custom-properties" Target="docProps/custom.xml"/></Relationships>

View File

@ -0,0 +1,2 @@
<?xml version="1.0" encoding="UTF-8" standalone="yes"?>
<Properties xmlns="http://schemas.openxmlformats.org/officeDocument/2006/extended-properties" xmlns:vt="http://schemas.openxmlformats.org/officeDocument/2006/docPropsVTypes"><Application>Microsoft Excel</Application><HeadingPairs><vt:vector size="2" baseType="variant"><vt:variant><vt:lpstr>工作表</vt:lpstr></vt:variant><vt:variant><vt:i4>1</vt:i4></vt:variant></vt:vector></HeadingPairs><TitlesOfParts><vt:vector size="1" baseType="lpstr"><vt:lpstr>外部通讯协议</vt:lpstr></vt:vector></TitlesOfParts></Properties>

View File

@ -0,0 +1,2 @@
<?xml version="1.0" encoding="UTF-8" standalone="yes"?>
<cp:coreProperties xmlns:cp="http://schemas.openxmlformats.org/package/2006/metadata/core-properties" xmlns:dc="http://purl.org/dc/elements/1.1/" xmlns:dcterms="http://purl.org/dc/terms/" xmlns:dcmitype="http://purl.org/dc/dcmitype/" xmlns:xsi="http://www.w3.org/2001/XMLSchema-instance"><dc:creator>lkl</dc:creator><cp:lastModifiedBy>lkl</cp:lastModifiedBy><dcterms:created xsi:type="dcterms:W3CDTF">2015-06-05T18:19:00Z</dcterms:created><dcterms:modified xsi:type="dcterms:W3CDTF">2026-05-09T04:21:37Z</dcterms:modified></cp:coreProperties>

View File

@ -0,0 +1,2 @@
<?xml version="1.0" encoding="UTF-8" standalone="yes"?>
<Properties xmlns="http://schemas.openxmlformats.org/officeDocument/2006/custom-properties" xmlns:vt="http://schemas.openxmlformats.org/officeDocument/2006/docPropsVTypes"><property fmtid="{D5CDD505-2E9C-101B-9397-08002B2CF9AE}" pid="2" name="KSOProductBuildVer"><vt:lpwstr>2052-12.8.2.21549</vt:lpwstr></property><property fmtid="{D5CDD505-2E9C-101B-9397-08002B2CF9AE}" pid="3" name="ICV"><vt:lpwstr>32722E1FC28F465CAD8A47F6421DC308_13</vt:lpwstr></property></Properties>

View File

@ -0,0 +1,2 @@
<?xml version="1.0" encoding="UTF-8" standalone="yes"?>
<Relationships xmlns="http://schemas.openxmlformats.org/package/2006/relationships"><Relationship Id="rId5" Type="http://www.wps.cn/officeDocument/2023/relationships/customStorage" Target="customStorage/customStorage.xml"/><Relationship Id="rId4" Type="http://schemas.openxmlformats.org/officeDocument/2006/relationships/styles" Target="styles.xml"/><Relationship Id="rId3" Type="http://schemas.openxmlformats.org/officeDocument/2006/relationships/sharedStrings" Target="sharedStrings.xml"/><Relationship Id="rId2" Type="http://schemas.openxmlformats.org/officeDocument/2006/relationships/theme" Target="theme/theme1.xml"/><Relationship Id="rId1" Type="http://schemas.openxmlformats.org/officeDocument/2006/relationships/worksheet" Target="worksheets/sheet1.xml"/></Relationships>

View File

@ -0,0 +1,2 @@
<?xml version="1.0" encoding="UTF-8" standalone="yes"?>
<customStorage xmlns="https://web.wps.cn/et/2018/main"><book/><sheets/></customStorage>

View File

@ -0,0 +1,2 @@
<?xml version="1.0" encoding="UTF-8" standalone="yes"?>
<sst xmlns="http://schemas.openxmlformats.org/spreadsheetml/2006/main" count="419" uniqueCount="29"><si><t>Details</t></si><si><t>Address</t></si><si><t>Name</t></si><si><t>Bits</t></si><si><t>Write/Read</t></si><si><t>Definition</t></si><si><t>Type:Modbus TCP</t></si><si><t>备用</t></si><si><t>Write</t></si><si><t>IP Address:192.168.0.1</t></si><si><t>Port:502</t></si><si><t>Modbus ID:1</t></si><si><t>Modbus Offset:1</t></si><si><t>舵机舱浸水报警</t></si><si><t>Read</t></si><si><t>设备舱浸水报警</t></si><si><r><rPr><sz val="10.5"/><color theme="1"/><rFont val="宋体"/><charset val="134"/></rPr><t>机舱</t></r><r><rPr><sz val="10.5"/><color theme="1"/><rFont val="Calibri"/><charset val="134"/></rPr><t>1</t></r><r><rPr><sz val="10.5"/><color theme="1"/><rFont val="宋体"/><charset val="134"/></rPr><t>浸水报警</t></r></si><si><r><rPr><sz val="10.5"/><color theme="1"/><rFont val="宋体"/><charset val="134"/></rPr><t>机舱</t></r><r><rPr><sz val="10.5"/><color theme="1"/><rFont val="Calibri"/><charset val="134"/></rPr><t>2</t></r><r><rPr><sz val="10.5"/><color theme="1"/><rFont val="宋体"/><charset val="134"/></rPr><t>浸水报警</t></r></si><si><t>监控室浸水报警</t></si><si><t>电池舱浸水报警</t></si><si><t>船员舱浸水报警</t></si><si><r><rPr><sz val="10.5"/><color theme="1"/><rFont val="Calibri"/><charset val="134"/></rPr><t>2</t></r><r><rPr><sz val="10.5"/><color theme="1"/><rFont val="宋体"/><charset val="134"/></rPr><t>号通道浸水报警</t></r></si><si><t>艏侧推舱浸水报警</t></si><si><t>艏尖舱浸水报警</t></si><si><t>电池舱温度报警</t></si><si><t>电池舱可燃气体报警</t></si><si><t>机舱可燃气体报警</t></si><si><t>火灾报警</t></si><si><t>水密门报警</t></si></sst>

File diff suppressed because one or more lines are too long

File diff suppressed because one or more lines are too long

View File

@ -0,0 +1,2 @@
<?xml version="1.0" encoding="UTF-8" standalone="yes"?>
<workbook xmlns="http://schemas.openxmlformats.org/spreadsheetml/2006/main" xmlns:r="http://schemas.openxmlformats.org/officeDocument/2006/relationships" xmlns:dbsheet="http://web.wps.cn/et/2021/dbsheet"><fileVersion appName="xl" lastEdited="3" lowestEdited="5" rupBuild="9302"/><workbookPr/><bookViews><workbookView windowWidth="29870" windowHeight="15280"/></bookViews><sheets><sheet name="外部通讯协议" sheetId="2" r:id="rId1"/></sheets><definedNames><definedName name="_xlnm._FilterDatabase" localSheetId="0" hidden="1">外部通讯协议!#REF!</definedName></definedNames><calcPr calcId="191029"/><extLst><ext uri="{B58B0392-4F1F-4190-BB64-5DF3571DCE5F}" xmlns:xcalcf="http://schemas.microsoft.com/office/spreadsheetml/2018/calcfeatures"><xcalcf:calcFeatures><xcalcf:feature name="microsoft.com:RD"/><xcalcf:feature name="microsoft.com:Single"/><xcalcf:feature name="microsoft.com:FV"/><xcalcf:feature name="microsoft.com:CNMTM"/><xcalcf:feature name="microsoft.com:LET_WF"/><xcalcf:feature name="microsoft.com:LAMBDA_WF"/><xcalcf:feature name="microsoft.com:ARRAYTEXT_WF"/></xcalcf:calcFeatures></ext></extLst></workbook>

File diff suppressed because one or more lines are too long

343
docs/协议refer.md Normal file
View File

@ -0,0 +1,343 @@
# 蓝牙协议
```
/********************小程序 发数据到 BL**************************************/
===========================================================
BE BB 02 00 XX
----- -- -- --
| | | |
| | | 指定传感器进行初始化01--六轴02--地磁03--气压计
| | 进行传感器的初始化/校准
| 表示后面的数据长度
包头BE表示小程序BB表示BL表示小程序发数据到蓝牙板子
BE BB 02 01 XX
----- -- -- --
| | | |
| | | 01--左脚02--右脚
| | 设置传感器采集的是哪只脚
| 表示后面的数据长度
包头BE表示小程序BB表示BL表示小程序发数据到蓝牙板子
BE BB 02 02 XX
----- -- -- --
| | | |
| | | 01表示读六轴状态02表示读地磁状态03表示读气压计状态
| | 读取传感器的状态
| 表示后面的数据长度
包头BE表示小程序BB表示BL表示小程序发数据到蓝牙板子
BE BB 02 03 XX
----- -- -- --
| | | |
| | | 01--开始02--停止
| | 采集数据并计算开始与停止
| 表示后面的数据长度
包头BE表示小程序BB表示BL表示小程序发数据到蓝牙板子
BE BB 02 04 01
----- -- -- --
| | | |
| | | 获取电量
| | 获取电量
| 表示后面的数据长度
包头BE表示小程序BB表示BL表示小程序发数据到蓝牙板子
BE BB 02 05 XX
----- -- -- --
| | | |
| | | 01:100Hz02:200Hz03:400Hz
| | 设置传感器采集频率
| 表示后面的数据长度
包头BE表示小程序BB表示BL表示小程序发数据到蓝牙板子
BE BB 02 06 XX
----- -- -- --
| | | |
| | | 00:禁用地磁01:使能地磁
| | 地磁使能指令
| 表示后面的数据长度
包头BE表示小程序BB表示BL表示小程序发数据到蓝牙板子
BE BB 02 07 XX
----- -- -- --
| | | |
| | | 00:禁用气压计01:使能气压计
| | 气压计使能指令
| 表示后面的数据长度
包头BE表示小程序BB表示BL表示小程序发数据到蓝牙板子
BE BB 01 09
----- -- --
| | |
| | 开启地磁测试进程
| 表示后面的数据长度
包头BE表示小程序BB表示BL表示小程序发数据到蓝牙板子
BE BB 01 0A
----- -- --
| | |
| | 关闭地磁测试进程
| 表示后面的数据长度
包头BE表示小程序BB表示BL表示小程序发数据到蓝牙板子
BE BB 01 0B
----- -- --
| | |
| | 获取固件版本
| 表示后面的数据长度
包头BE表示小程序BB表示BL表示小程序发数据到蓝牙板子
BE BB 01 0C
----- -- --
| | |
| | 获取rfid/uid
| 表示后面的数据长度
包头BE表示小程序BB表示BL表示小程序发数据到蓝牙板子
BE BB 01 FF 扫描检测传感器
----- -- --
| | |
| | 扫描检测传感器
| 表示后面的数据长度
包头BE表示小程序BB表示BL表示小程序发数据到蓝牙板子
===============================================================
/********************BL 发数据到小程序**************************************/
============================================================
BB BE 02 00 XX
----- -- -- --
| | | |
| | | 10六轴未初始化11六轴初始化成功20地磁未初始化21地磁初始化成功30气压计未初始化31气压计初始化成功
| | 返回传感器的初始化状态
| 表示后面的数据长度
包头BE表示小程序BB表示BL表示蓝牙板子发数据到小程序
### 地磁校准流程
地磁传感器需要校准,发送 BLE 命令后进行"画八字"校准,校准数据会保存到 VM 中,掉电后再次上电会自动加载。
**发送命令:**
```
BE BB 02 00 02 // 启动地磁校准
```
**BLE 反馈消息:**
| 消息 | 含义 | 说明 |
|------|------|------|
| BB BE 02 00 20 | 地磁初始化失败 | 传感器通信异常 |
| BB BE 02 00 21 | 地磁初始化成功 | 传感器正常,即将进入校准状态 |
| BB BE 02 00 22 | 提示开始校准 | 用户可以开始画八字 |
| BB BE 02 00 23 | 校准中 | 循环发送,正在采集数据 |
| BB BE 02 00 24 | 校准错误 | 数据范围不足,需重新画八字 |
| BB BE 02 00 25 | 校准完成 | 校准成功,数据已保存到 VM |
**校准成功后的行为:**
- 校准数据offset_x, offset_y, offset_z保存到 VMCFG_MAG_CALIBRATION
- 再次上电自动从 VM 加载校准数据,无需重复校准
BB BE XX 00 XX.......
----- -- -- --
| | | |
| | | 16组传感器数据。每一组30字节
| | 数据包下标0-255
| 左/右脚数据
包头BE表示小程序BB表示BL表示蓝牙板子发数据到小程序
```
# 蓝牙助手设置
连接后要先将蓝牙的MTU设置为最大一般最大是512左右
![image-20251205204926475](image-20251205204926475.png)
![image-20251205204943926](image-20251205204943926.png)
![image-20251205205027729](image-20251205205027729.png)
右边的调试助手可以查看传输速率。
# 数据采集
先后发送:初始化三个传感器
- BE BB 02 00 01
- 六轴初始化
- 返回BB BE 02 00 11表示初始化成功
- BE BB 02 00 02
- 地磁初始化等到返回BB BE 02 00 21表示初始化成功
- BE BB 02 00 03
- 气压计初始化等到返回BB BE 02 00 31表示初始化成功
设定数据来源:
- 发送BE BB 02 01 XX
- 01左脚
- 02右脚
- 返回数据BB BE 06 05 XX
- 41 -- 已设置为左脚42 -- 已设置为右脚
开始采集,传感器通过蓝牙发送数据
- 发送BE BB 02 03 01
- 如果返回BB BE 02 00 00说明有传感器没初始化成功可以发BE BB 02 02 XX 查看传感器初始化状态
一次完整的数据接收类似如下:
```c
BE BB XX XX 后面每30字节为一组传感器数据,一个16
一次蓝牙发送共计484字节
第一个xx:左右脚标志,41左脚,42右脚
第二个xx:数据包下标,0-255,每到255就会重置为0
```
停止采集:
- BE BB 02 03 02
# 获取电量
发送BE BB 02 04 01
- 返回的是百分比的电量值,如:
- 0x57
- 转为十进制为87当前还剩87%的电量
# 开启地磁测试进程
发送BE BB 01 09
- 返回地磁三轴 X Y Z数据每轴4字节的float类型。
- BB BE 0D 09 XX XX XX XX XX XX XX XX XX XX XX XX
# 获取固件版本
发送BE BB 01 0B
返回: BB BE 03 0B XX XX
最后两字节就是版本号
# 获取设备ID/RFID
发送BE BB 01 0C
返回: BB BE 05 0C XX XX XX XX
最后四字节位就是RFID小端模式
# 扫描检测传感器
发送BE BB 01 FF
返回: 0xBB, 0xBE, 0x07, 0xFF, 0xXX, 0xXX, 0xXX, 0xXX, 0xXX, 0xXX
最后6字节位对应扫描到的6个传感器目前实际最多只有3个。
# 采集速率修改
设置为100Hz
- BE BB 02 05 01
设置200Hz
- BE BB 02 05 02
设置400Hz
- BE BB 02 05 03
# 数据解析
```c
//data蓝牙拿到的数据484字节长度
void data_log(uint8_t* data){
// 检查数据包头部
if (data[0] != 0xBE || data[1] != 0xBB) {
printf("Error: Invalid data packet header.\n");
return;
}
//左右脚
uint8_t package_foot = data[2];
// 解析包索引
uint8_t package_index = data[3];
printf("--- Parsing Data Packet Index: %d ---\n", package_index);
uint8_t* p = &data[4]; // 指向数据负载的起始位置
// 循环解析16组数据
for (int i = 0; i < MPU_FIFO_LEN; i++) {
// 1. 解析六轴传感器数据 (12 bytes)
int16_t imu_raw[6];
for (int j = 0; j < 6; j++) {
// 小端模式: 低字节在前, 高字节在后
imu_raw[j] = (int16_t)(((uint16_t)p[1] << 8) | (uint16_t)p[0]);
p += 2;
}
float acc_g[3];
float gyr_dps[3];
acc_g[0] = (float)imu_raw[0] / 2048.0f;
acc_g[1] = (float)imu_raw[1] / 2048.0f;
acc_g[2] = (float)imu_raw[2] / 2048.0f;
gyr_dps[0] = (float)imu_raw[3] * 0.061f;
gyr_dps[1] = (float)imu_raw[4] * 0.061f;
gyr_dps[2] = (float)imu_raw[5] * 0.061f;
// 2. 解析地磁传感器数据 (12 bytes)
int32_t mag_raw[3];
for (int j = 0; j < 3; j++) {
// 小端模式
mag_raw[j] = (int32_t)(((uint32_t)p[3] << 24) | ((uint32_t)p[2] << 16) | ((uint32_t)p[1] << 8) | (uint32_t)p[0]);
p += 4;
}
float mag_gauss[3];
mag_gauss[0] = (float)mag_raw[0] / 1000.0f;
mag_gauss[1] = (float)mag_raw[1] / 1000.0f;
mag_gauss[2] = (float)mag_raw[2] / 1000.0f;
// 3. 解析温度数据 (2 bytes)
int16_t temp_raw = (int16_t)(((uint16_t)p[1] << 8) | (uint16_t)p[0]);
p += 2;
float temperature = (float)temp_raw / 1000.0f;
// 4. 解析气压数据 (4 bytes)
uint32_t press_raw = (uint32_t)(((uint32_t)p[3] << 24) | ((uint32_t)p[2] << 16) | ((uint32_t)p[1] << 8) | (uint32_t)p[0]);
p += 4;
float pressure = (float)press_raw / 1000.0f;
// 打印解析后的数据
if(i % 8 == 0){
printf("Package[%d]:====================\n", i);
printf(" ACC(g): x=%.3f, y=%.3f, z=%.3f\n", acc_g[0], acc_g[1], acc_g[2]);
printf(" GYR(dps):x=%.3f, y=%.3f, z=%.3f\n", gyr_dps[0], gyr_dps[1], gyr_dps[2]);
printf(" MAG(Gs): x=%.3f, y=%.3f, z=%.3f\n", mag_gauss[0], mag_gauss[1], mag_gauss[2]);
printf(" TEMP(C): %.3f, PRESS(Pa): %.3f\n", temperature, pressure);
}
}
printf("--- End of Packet ---\n\n");
}
```

View File

@ -285,7 +285,7 @@ void CmdRouter_Init(void);
/**
* @brief 向指定端口的解析器喂入数据
* @note 由UART中断回调调用线程安全
* @param port_id: 端口ID (PORT_UART1/PORT_UART2/PORT_UART3)
* @param port_id: 端口ID (PORT_433/PORT_DEBUG/PORT_RS485)
* @param byte: 接收到的字节
* @param current_tick: 系统时间戳
* @retval 无
@ -325,9 +325,9 @@ void CmdRouter_SendResponseFmt(port_id_t port_id, const char *fmt, ...);
```c
/** 端口ID枚举 */
typedef enum {
PORT_UART1 = 0, /**< RF433模块 */
PORT_UART2 = 1, /**< 调试串口 */
PORT_UART3 = 2, /**< RS485模块 */
PORT_433 = 0, /**< RF433模块 */
PORT_DEBUG = 1, /**< 调试串口 */
PORT_RS485 = 2, /**< RS485模块 */
PORT_COUNT
} port_id_t;
@ -396,18 +396,18 @@ void CmdParser_SetResponseCallback(response_callback_t callback);
* @note 静态表根据port_id索引查找对应UART句柄
*/
static UART_HandleTypeDef* const g_port_uart_map[PORT_COUNT] = {
[PORT_UART1] = &huart1, // RF433
[PORT_UART2] = &huart2, // DEBUG
[PORT_UART3] = &huart3, // RS485
[PORT_433] = &huart1, // RF433
[PORT_DEBUG] = &huart2, // DEBUG
[PORT_RS485] = &huart3, // RS485
};
/**
* @brief 端口名称表(用于日志输出)
*/
static const char* const g_port_name_map[PORT_COUNT] = {
[PORT_UART1] = "UART1",
[PORT_UART2] = "UART2",
[PORT_UART3] = "UART3",
[PORT_433] = "UART1",
[PORT_DEBUG] = "UART2",
[PORT_RS485] = "UART3",
};
```
@ -650,9 +650,9 @@ void Configure_UART_Priorities(void)
#include "cmd_parser.h"
typedef enum {
PORT_UART1 = 0,
PORT_UART2 = 1,
PORT_UART3 = 2,
PORT_433 = 0,
PORT_DEBUG = 1,
PORT_RS485 = 2,
PORT_COUNT
} port_id_t;
@ -683,7 +683,7 @@ void MultiUART_SendString(port_id_t port_id, const char *str);
void HAL_UART_RxCpltCallback(UART_HandleTypeDef *huart)
{
if (huart->Instance == USART1) {
MultiUART_FeedByte(PORT_UART1, rf433_uart_rx_tmp, HAL_GetTick());
MultiUART_FeedByte(PORT_433, rf433_uart_rx_tmp, HAL_GetTick());
HAL_UART_Receive_IT(&huart1, &rf433_uart_rx_tmp, 1);
}
// ... 其他端口保持原样 ...

108
docs/报文.md Normal file
View File

@ -0,0 +1,108 @@
# BOAT DTU 无线通信协议 (RF433)
本文档采用直观图示方式定义 BOAT DTU 在 433MHz 无线频段的报文格式。
## 1. 通用报文结构图示
所有无线报文均遵循以下结构:
```text
AA TYPE LEN ID [PAYLOAD] SUM
-- ---- --- -- --------- ---
| | | | | |
| | | | | +-- 校验和:从 AA 到 PAYLOAD 结束的所有字节累加和 (取低8位)
| | | | +---------- 载荷数据:具体的业务数据内容
| | | +------------------ 设备 ID当前发送设备的唯一标识 (MY_DEVICE_ID)
| | +---------------------- 长度:指明后续 [ID + PAYLOAD + SUM] 的总字节数
| +--------------------------- 数据类型:区分数据来源 (10, 55, 48, AA)
+-------------------------------- 起始符:固定为 0xAA
```
---
## 2. 详细指令集定义
### 2.1 I/O 状态变化上报 (主动上报)
当板载 4 路数字输入 (DI) 电平发生变化时,立即发送此包。
```text
AA 10 03 ID XX SUM
-- -- -- -- -- ---
| | | | | |
| | | | | +-- 校验和
| | | | +------ I/O 状态位 (Bit0:DI1, Bit1:DI2, Bit2:DI3, Bit3:DI4)
| | | +---------- 本机设备 ID
| | +-------------- 长度固定为 0x03 (ID + 1字节状态 + SUM)
| +------------------ 类型标识0x10 (I/O Data)
+---------------------- 固定起始符
```
### 2.2 RS485 透传数据包
将 RS485 接口收到的原始串口数据封装后发出。
```text
AA 48 LEN ID [DATA] SUM
-- -- --- -- ------ ---
| | | | | |
| | | | | +-- 校验和
| | | | +--------- RS485 原始数据内容
| | | +--------------- 本机设备 ID
| | +------------------- 长度:(1 + 原始数据长度 + SUM)
| +----------------------- 类型标识0x48 (RS485 Data)
+--------------------------- 固定起始符
```
### 2.3 W5500 网络透传数据包
将以太网口收到的 UDP/TCP 原始数据封装后发出。
```text
AA 55 LEN ID [DATA] SUM
-- -- --- -- ------ ---
| | | | | |
| | | | | +-- 校验和
| | | | +--------- 网络原始数据内容
| | | +--------------- 本机设备 ID
| | +------------------- 长度:(1 + 原始数据长度 + SUM)
| +----------------------- 类型标识0x55 (Net Data)
+--------------------------- 固定起始符
```
### 2.4 系统心跳包 (30秒/次)
系统定时上报当前存活状态,包含当前的 I/O 状态、防丢包序列号、固件版本及 Modbus 寄存器值。
#### 2.4.1 标准心跳包 (8字节Payload)
```text
AA AA 09 [DEVICE_ID] [SEQ_H] [SEQ_L] [FW_H] [FW_L] [IO_STATUS] [MODBUS_H] [MODBUS_L] SUM
-- -- -- ----------- --------------- ------------- ----------- --------------------- ---
| | | | | | | | |
| | | | | | | | +-- 1字节 校验和
| | | | | | | +-------------------- 2字节 Modbus 寄存器值
| | | | | | +------------------------------------- 1字节 I/O 状态
| | | | | | Bit7: W5500 网线连接状态
| | | | | | Bit3-Bit0: 4路 DI 状态
| | | | | +--------------------------------------------------- 2字节序列号
| | | | +------------------------------------------------------------------ 2字节固件版本编码
| | | +----------------------------------------------------------------------------------- 1字节本机设备 ID
| | +--------------------------------------------------------------------------------------------- 长度 0x09后续的总字节数
| +------------------------------------------------------------------------------------------------- 类型 0xAA
+----------------------------------------------------------------------------------------------------- 固定起始符
```
**Payload 字段说明:**
| 字段 | 长度 | 说明 |
|------|------|------|
| SEQ_H, SEQ_L | 2 | 2字节序列号 (0-65535, 循环自增) |
| FW_H, FW_L | 2 | 2字节固件版本编码 (MAKE_XTELL_CODE 宏定义) |
| DEVICE_ID | 1 | 本机设备 ID (MY_DEVICE_ID) |
| IO_STATUS | 1 | 1字节 I/O 状态 |
| MODBUS_H, MODBUS_L | 2 | 2字节 Modbus 寄存器值 (最新读取值) |
---
## 3. 示例说明 (假设 Device ID = 0x01)
* **心跳包示例**`AA AA 08 01 00 05 06 41 01 0F 01 2C 5A`
* 表示ID为1的设备序列号5固件版本 0x0641 (2026年5月10日第1次编译)本机ID=1I/O全高Modbus=0x012C (300)8字节payload
* **485透传示例**`AA 48 05 01 41 42 43 44 4D`
* 表示ID为1的设备转发了 485 数据 "ABCD" (长度 4+1=5)。

View File

@ -0,0 +1,62 @@
import socket
import struct
import time
# 配置信息
SERVER_IP = '127.0.0.1' # 模拟本地回路
PORT = 502
UNIT_ID = 1
REG_ADDR = 30 # 逻辑 40031
def poll_register():
# 1. 构造 Modbus TCP 请求 (Function Code 03)
tid = 0x0001
pid = 0x0000
length = 6 # 后续字节长度 (UnitID 1 + PDU 5)
uid = UNIT_ID
fc = 0x03
addr = REG_ADDR
qty = 1
# [MBAP Header] + [PDU]
request = struct.pack('>HHHB', tid, pid, length, uid) + \
struct.pack('>BHH', fc, addr, qty)
try:
with socket.socket(socket.AF_INET, socket.SOCK_STREAM) as s:
s.settimeout(2.0)
s.connect((SERVER_IP, PORT))
print(f"[TX] 发送请求: {request.hex(' ')}")
s.sendall(request)
# 2. 接收响应
response = s.recv(1024)
if not response:
print("[!] 服务器关闭了连接")
return
print(f"[RX] 收到响应: {response.hex(' ')}")
if len(response) >= 9: # MBAP(7) + FC(1) + ByteCount(1)
# 解析响应
header = response[:7]
pdu = response[7:]
res_tid, res_pid, res_len, res_uid = struct.unpack('>HHHB', header)
res_fc = pdu[0]
byte_count = pdu[1]
reg_value = struct.unpack('>H', pdu[2:4])[0]
print(f"[+] 解析成功!")
print(f" - 事务ID: {res_tid}")
print(f" - 寄存器 {REG_ADDR} 的值: {hex(reg_value)} ({reg_value})")
else:
print("[!] 响应长度不足")
except Exception as e:
print(f"[!] 连接错误: {e}")
if __name__ == "__main__":
print("[*] Python Modbus TCP 客户端模拟启动...")
poll_register()

View File

@ -0,0 +1,122 @@
import socket
import struct
import sys
import msvcrt
import datetime
# 配置信息
HOST = '0.0.0.0' # 监听所有接口
PORT = 502 # Modbus TCP 标准端口
UNIT_ID = 1 # 目标 Unit ID
# 模拟寄存器存储 (30号地址 -> 40031逻辑地址)
registers = {
30: 0xABCD # 初始模拟值
}
def get_time():
"""获取当前格式化时间"""
return datetime.datetime.now().strftime("%Y-%m-%d %H:%M:%S.%f")[:-3]
def handle_client(conn, addr):
print(f"[{get_time()}] [*] 客户端已连接: {addr}")
conn.settimeout(1.0)
while True:
try:
data = conn.recv(1024)
if not data:
break
# 记录接收到的原始报文
print(f"[{get_time()}] [RAW] 收到原始报文: {data.hex(' ')}")
if len(data) < 7:
print(f"[{get_time()}] [!] 报文长度不足 7 字节")
continue
tid, pid, length, uid = struct.unpack('>HHHB', data[:7])
pdu = data[7:]
if len(pdu) < 5:
print(f"[{get_time()}] [!] PDU 长度不足")
continue
func_code = pdu[0]
if func_code == 0x03:
start_addr, qty = struct.unpack('>HH', pdu[1:5])
print(f"[{get_time()}] [REQ] 读取保持寄存器: 起始地址={start_addr}, 数量={qty}, UnitID={uid}")
payload = b''
for i in range(qty):
val = registers.get(start_addr + i, 0)
payload += struct.pack('>H', val)
resp_pdu = struct.pack('B', func_code) + struct.pack('B', len(payload)) + payload
resp_length = len(resp_pdu) + 1
resp_header = struct.pack('>HHHB', tid, pid, resp_length, uid)
conn.sendall(resp_header + resp_pdu)
print(f"[{get_time()}] [RES] 已发送响应: {payload.hex(' ')}")
else:
print(f"[{get_time()}] [!] 不支持的功能码: {func_code}")
except socket.timeout:
# 检查是否有退出按键
if msvcrt.kbhit():
if msvcrt.getch().decode('utf-8', errors='ignore').lower() == 'q':
return True
continue
except Exception as e:
print(f"[{get_time()}] [!] 错误: {e}")
break
conn.close()
print(f"[{get_time()}] [*] 客户端连接已断开: {addr}")
return False
def main():
# 从命令行参数获取寄存器 30 的初始值
if len(sys.argv) > 1:
try:
val_str = sys.argv[1]
if val_str.startswith('0x'):
registers[30] = int(val_str, 16)
else:
registers[30] = int(val_str)
except ValueError:
print(f"[!] 警告: 无效的参数 '{sys.argv[1]}',使用默认值 {hex(registers[30])}")
with socket.socket(socket.AF_INET, socket.SOCK_STREAM) as s:
s.setsockopt(socket.SOL_SOCKET, socket.SO_REUSEADDR, 1)
s.settimeout(1.0)
try:
s.bind((HOST, PORT))
except PermissionError:
print(f"[!] 错误: 无法绑定 {PORT} 端口。请尝试使用管理员权限运行。")
return
s.listen()
print(f"[{get_time()}] [*] Modbus TCP 模拟服务端启动,监听 {PORT} 端口...")
print(f"[{get_time()}] [*] 寄存器 30 (40031) 当前值: {hex(registers[30])}")
print("[*] 提示: 随时按下 'q' 键退出程序")
should_exit = False
while not should_exit:
if msvcrt.kbhit():
if msvcrt.getch().decode('utf-8', errors='ignore').lower() == 'q':
print("\n[*] 检测到 'q' 键,正在退出...")
break
try:
conn, addr = s.accept()
should_exit = handle_client(conn, addr)
except socket.timeout:
continue
except KeyboardInterrupt:
print("\n[*] 正在停止服务端...")
break
s.close()
if __name__ == "__main__":
main()