From b64dc0740f11e9060cfb1c38015b07a50d54485f Mon Sep 17 00:00:00 2001 From: Robofish <1683502971@qq.com> Date: Wed, 4 Mar 2026 17:54:59 +0800 Subject: [PATCH] =?UTF-8?q?=E6=95=B4=E7=90=86?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- .../examples/mcu_example_new_protocol.ino | 337 ------------------ src/rm_serial_driver/tools/debug_serial.py | 161 --------- 2 files changed, 498 deletions(-) delete mode 100644 src/rm_serial_driver/examples/mcu_example_new_protocol.ino delete mode 100755 src/rm_serial_driver/tools/debug_serial.py diff --git a/src/rm_serial_driver/examples/mcu_example_new_protocol.ino b/src/rm_serial_driver/examples/mcu_example_new_protocol.ino deleted file mode 100644 index bc19039..0000000 --- a/src/rm_serial_driver/examples/mcu_example_new_protocol.ino +++ /dev/null @@ -1,337 +0,0 @@ -/* - * RM Serial Driver - 单片机端示例代码(新协议) - * 适用于 Arduino/STM32 - * - * 协议格式: - * - 帧头: 'M' 'R' (0x4D 0x52) - * - 数据: 根据不同数据类型 - * - CRC16: CRC16-CCITT (初始值 0xFFFF) - */ - -#include -#include - -// ==================== 协议定义 ==================== - -#define FRAME_HEADER_0 'M' // 0x4D -#define FRAME_HEADER_1 'R' // 0x52 -#define CRC16_INIT 0xFFFF - -// MCU 发送给上位机的数据 -typedef struct __attribute__((packed)) -{ - uint8_t head[2]; // 帧头 'M' 'R' - uint8_t mode; // 0: 空闲, 1: 自瞄, 2: 小符, 3: 大符 - float q[4]; // 四元数 wxyz 顺序 - float yaw; // 偏航角 - float yaw_vel; // 偏航角速度 - float pitch; // 俯仰角 - float pitch_vel; // 俯仰角速度 - float bullet_speed; // 弹速 - uint16_t bullet_count; // 子弹累计发送次数 -} DataMCU_t; - -typedef struct __attribute__((packed)) -{ - DataMCU_t data; - uint16_t crc16; -} PackageMCU_t; - -// 上位机发送给 MCU 的控制命令 -typedef struct __attribute__((packed)) -{ - uint8_t head[2]; // 帧头 'M' 'R' - uint8_t mode; // 0: 不控制, 1: 控制云台但不开火, 2: 控制云台且开火 - float yaw; // 目标偏航角 - float yaw_vel; // 偏航角速度 - float yaw_acc; // 偏航角加速度 - float pitch; // 目标俯仰角 - float pitch_vel; // 俯仰角速度 - float pitch_acc; // 俯仰角加速度 - float vx; // X 方向速度 - float vy; // Y 方向速度 - float wz; // Z 方向角速度 - uint8_t reserved; // 预留字段 -} DataAI_t; - -typedef struct __attribute__((packed)) -{ - DataAI_t data; - uint16_t crc16; -} PackageAI_t; - -// ==================== CRC16 计算 ==================== - -static const uint16_t crc16_tab[256] = { - 0x0000, 0x1189, 0x2312, 0x329b, 0x4624, 0x57ad, 0x6536, 0x74bf, - 0x8c48, 0x9dc1, 0xaf5a, 0xbed3, 0xca6c, 0xdbe5, 0xe97e, 0xf8f7, - 0x1081, 0x0108, 0x3393, 0x221a, 0x56a5, 0x472c, 0x75b7, 0x643e, - 0x9cc9, 0x8d40, 0xbfdb, 0xae52, 0xdaed, 0xcb64, 0xf9ff, 0xe876, - 0x2102, 0x308b, 0x0210, 0x1399, 0x6726, 0x76af, 0x4434, 0x55bd, - 0xad4a, 0xbcc3, 0x8e58, 0x9fd1, 0xeb6e, 0xfae7, 0xc87c, 0xd9f5, - 0x3183, 0x200a, 0x1291, 0x0318, 0x77a7, 0x662e, 0x54b5, 0x453c, - 0xbdcb, 0xac42, 0x9ed9, 0x8f50, 0xfbef, 0xea66, 0xd8fd, 0xc974, - 0x4204, 0x538d, 0x6116, 0x709f, 0x0420, 0x15a9, 0x2732, 0x36bb, - 0xce4c, 0xdfc5, 0xed5e, 0xfcd7, 0x8868, 0x99e1, 0xab7a, 0xbaf3, - 0x5285, 0x430c, 0x7197, 0x601e, 0x14a1, 0x0528, 0x37b3, 0x263a, - 0xdecd, 0xcf44, 0xfddf, 0xec56, 0x98e9, 0x8960, 0xbbfb, 0xaa72, - 0x6306, 0x728f, 0x4014, 0x519d, 0x2522, 0x34ab, 0x0630, 0x17b9, - 0xef4e, 0xfec7, 0xcc5c, 0xddd5, 0xa96a, 0xb8e3, 0x8a78, 0x9bf1, - 0x7387, 0x620e, 0x5095, 0x411c, 0x35a3, 0x242a, 0x16b1, 0x0738, - 0xffcf, 0xee46, 0xdcdd, 0xcd54, 0xb9eb, 0xa862, 0x9af9, 0x8b70, - 0x8408, 0x9581, 0xa71a, 0xb693, 0xc22c, 0xd3a5, 0xe13e, 0xf0b7, - 0x0840, 0x19c9, 0x2b52, 0x3adb, 0x4e64, 0x5fed, 0x6d76, 0x7cff, - 0x9489, 0x8500, 0xb79b, 0xa612, 0xd2ad, 0xc324, 0xf1bf, 0xe036, - 0x18c1, 0x0948, 0x3bd3, 0x2a5a, 0x5ee5, 0x4f6c, 0x7df7, 0x6c7e, - 0xa50a, 0xb483, 0x8618, 0x9791, 0xe32e, 0xf2a7, 0xc03c, 0xd1b5, - 0x2942, 0x38cb, 0x0a50, 0x1bd9, 0x6f66, 0x7eef, 0x4c74, 0x5dfd, - 0xb58b, 0xa402, 0x9699, 0x8710, 0xf3af, 0xe226, 0xd0bd, 0xc134, - 0x39c3, 0x284a, 0x1ad1, 0x0b58, 0x7fe7, 0x6e6e, 0x5cf5, 0x4d7c, - 0xc60c, 0xd785, 0xe51e, 0xf497, 0x8028, 0x91a1, 0xa33a, 0xb2b3, - 0x4a44, 0x5bcd, 0x6956, 0x78df, 0x0c60, 0x1de9, 0x2f72, 0x3efb, - 0xd68d, 0xc704, 0xf59f, 0xe416, 0x90a9, 0x8120, 0xb3bb, 0xa232, - 0x5ac5, 0x4b4c, 0x79d7, 0x685e, 0x1ce1, 0x0d68, 0x3ff3, 0x2e7a, - 0xe70e, 0xf687, 0xc41c, 0xd595, 0xa12a, 0xb0a3, 0x8238, 0x93b1, - 0x6b46, 0x7acf, 0x4854, 0x59dd, 0x2d62, 0x3ceb, 0x0e70, 0x1ff9, - 0xf78f, 0xe606, 0xd49d, 0xc514, 0xb1ab, 0xa022, 0x92b9, 0x8330, - 0x7bc7, 0x6a4e, 0x58d5, 0x495c, 0x3de3, 0x2c6a, 0x1ef1, 0x0f78 -}; - -uint16_t CRC16_Calc(const uint8_t *buf, size_t len, uint16_t crc) -{ - while (len--) - { - crc = (crc >> 8) ^ crc16_tab[(crc ^ (*buf++)) & 0xFF]; - } - return crc; -} - -bool CRC16_Verify(const uint8_t *buf, size_t len) -{ - if (len < 2) - return false; - - uint16_t expected = CRC16_Calc(buf, len - 2, CRC16_INIT); - uint16_t received = buf[len - 2] | (buf[len - 1] << 8); - - return expected == received; -} - -// ==================== 发送 MCU 数据 ==================== - -void send_mcu_data(uint8_t mode, float q[4], float yaw, float yaw_vel, - float pitch, float pitch_vel, float bullet_speed, uint16_t bullet_count) -{ - PackageMCU_t package; - - // 设置帧头 - package.data.head[0] = FRAME_HEADER_0; // 'M' - package.data.head[1] = FRAME_HEADER_1; // 'R' - - // 填充数据 - package.data.mode = mode; - memcpy(package.data.q, q, sizeof(float) * 4); - package.data.yaw = yaw; - package.data.yaw_vel = yaw_vel; - package.data.pitch = pitch; - package.data.pitch_vel = pitch_vel; - package.data.bullet_speed = bullet_speed; - package.data.bullet_count = bullet_count; - - // 计算 CRC(从帧头开始) - package.crc16 = CRC16_Calc((uint8_t*)&package.data, sizeof(DataMCU_t), CRC16_INIT); - - // 发送 - Serial.write((uint8_t*)&package, sizeof(PackageMCU_t)); -} - -// ==================== 接收 AI 控制命令 ==================== - -uint8_t rx_buffer[256]; -uint16_t rx_index = 0; - -void receive_ai_command() -{ - while (Serial.available()) - { - uint8_t byte = Serial.read(); - - // 查找帧头 'M' - if (rx_index == 0 && byte != FRAME_HEADER_0) - { - continue; - } - - rx_buffer[rx_index++] = byte; - - // 防止缓冲区溢出 - if (rx_index >= sizeof(rx_buffer)) - { - rx_index = 0; - continue; - } - - // 检查是否接收到完整的包头 - if (rx_index >= 2) - { - // 验证第二个字节是否为 'R' - if (rx_buffer[1] != FRAME_HEADER_1) - { - // 帧头不完整,重新开始 - rx_index = 0; - continue; - } - } - - // 检查是否接收完整 - if (rx_index >= sizeof(PackageAI_t)) - { - // 验证 CRC - if (CRC16_Verify(rx_buffer, sizeof(PackageAI_t))) - { - // CRC 校验通过,处理数据包 - PackageAI_t *package = (PackageAI_t*)rx_buffer; - process_ai_command(&package->data); - } - else - { - // CRC 校验失败 - Serial.println("CRC Error!"); - } - - // 重置接收缓冲区 - rx_index = 0; - } - } -} - -void process_ai_command(DataAI_t *data) -{ - // 处理 AI 控制命令 - switch (data->mode) - { - case 0: // 不控制 - // 停止控制 - break; - - case 1: // 控制云台但不开火 - // 控制云台到目标位置 - control_gimbal(data->yaw, data->pitch, data->yaw_vel, data->pitch_vel); - break; - - case 2: // 控制云台且开火 - // 控制云台并开火 - control_gimbal(data->yaw, data->pitch, data->yaw_vel, data->pitch_vel); - fire(); - break; - } - - // 控制底盘 - control_chassis(data->vx, data->vy, data->wz); -} - -// ==================== Arduino 主程序 ==================== - -void setup() -{ - Serial.begin(115200); - while (!Serial) { - delay(10); - } - - Serial.println("RM Serial Driver - MCU Ready!"); -} - -void loop() -{ - // 接收 AI 控制命令 - receive_ai_command(); - - // 定时发送 MCU 数据(每 10ms) - static unsigned long last_send = 0; - if (millis() - last_send >= 10) - { - // 读取传感器数据 - uint8_t mode = get_current_mode(); - float q[4] = {1.0f, 0.0f, 0.0f, 0.0f}; // 四元数 - get_quaternion(q); - float yaw = get_yaw(); - float yaw_vel = get_yaw_velocity(); - float pitch = get_pitch(); - float pitch_vel = get_pitch_velocity(); - float bullet_speed = get_bullet_speed(); - uint16_t bullet_count = get_bullet_count(); - - // 发送数据 - send_mcu_data(mode, q, yaw, yaw_vel, pitch, pitch_vel, bullet_speed, bullet_count); - - last_send = millis(); - } -} - -// ==================== 辅助函数(需要根据实际硬件实现)==================== - -uint8_t get_current_mode() -{ - // 返回当前模式:0=空闲, 1=自瞄, 2=小符, 3=大符 - return 1; // 示例:自瞄模式 -} - -void get_quaternion(float q[4]) -{ - // 从 IMU 读取四元数 - // q[0] = w, q[1] = x, q[2] = y, q[3] = z -} - -float get_yaw() -{ - // 读取偏航角 - return 0.0f; -} - -float get_yaw_velocity() -{ - // 读取偏航角速度 - return 0.0f; -} - -float get_pitch() -{ - // 读取俯仰角 - return 0.0f; -} - -float get_pitch_velocity() -{ - // 读取俯仰角速度 - return 0.0f; -} - -float get_bullet_speed() -{ - // 读取弹速 - return 15.0f; -} - -uint16_t get_bullet_count() -{ - // 返回子弹累计发送次数 - static uint16_t count = 0; - return count++; -} - -void control_gimbal(float yaw, float pitch, float yaw_vel, float pitch_vel) -{ - // 控制云台到目标位置 - // 实现 PID 控制等 -} - -void control_chassis(float vx, float vy, float wz) -{ - // 控制底盘运动 -} - -void fire() -{ - // 开火 -} diff --git a/src/rm_serial_driver/tools/debug_serial.py b/src/rm_serial_driver/tools/debug_serial.py deleted file mode 100755 index f7f9175..0000000 --- a/src/rm_serial_driver/tools/debug_serial.py +++ /dev/null @@ -1,161 +0,0 @@ -#!/usr/bin/env python3 -""" -串口数据调试工具 -用于查看原始串口数据,帮助排查 CRC 校验失败问题 -""" - -import serial -import sys - -def bytes_to_hex(data): - """将字节转换为十六进制字符串""" - return ' '.join(f'{b:02X}' for b in data) - -def main(): - if len(sys.argv) < 2: - print("用法: python3 debug_serial.py <串口设备> [波特率]") - print("示例: python3 debug_serial.py /dev/ttyUSB0 115200") - sys.exit(1) - - device = sys.argv[1] - baudrate = int(sys.argv[2]) if len(sys.argv) > 2 else 115200 - - print(f"打开串口: {device} @ {baudrate}") - print("按 Ctrl+C 退出\n") - - try: - ser = serial.Serial(device, baudrate, timeout=1) - - buffer = bytearray() - packet_count = 0 - - while True: - if ser.in_waiting > 0: - data = ser.read(ser.in_waiting) - buffer.extend(data) - - print(f"接收 {len(data)} 字节: {bytes_to_hex(data)}") - - # 查找帧头 (0xC4 或 0xA8) - while len(buffer) > 0: - # 查找 MCU 帧头 (0xC4) - if 0xC4 in buffer: - idx = buffer.index(0xC4) - if idx > 0: - print(f" 丢弃 {idx} 字节垃圾数据: {bytes_to_hex(buffer[:idx])}") - buffer = buffer[idx:] - - # MCU 数据包大小: 1(ID) + 28(Data) + 2(CRC) = 31 字节 - if len(buffer) >= 31: - packet = buffer[:31] - buffer = buffer[31:] - - packet_count += 1 - print(f"\n[数据包 #{packet_count}] MCU (0xC4) - 31 字节:") - print(f" 完整数据: {bytes_to_hex(packet)}") - print(f" ID: 0x{packet[0]:02X}") - print(f" 数据: {bytes_to_hex(packet[1:29])}") - print(f" CRC: 0x{packet[29]:02X}{packet[30]:02X}") - - # 计算 CRC - crc = calculate_crc16(packet[1:29]) - received_crc = packet[29] | (packet[30] << 8) - - if crc == received_crc: - print(f" ✓ CRC 校验通过") - else: - print(f" ✗ CRC 校验失败: 计算值=0x{crc:04X}, 接收值=0x{received_crc:04X}") - print() - else: - break - - # 查找裁判系统帧头 (0xA8) - elif 0xA8 in buffer: - idx = buffer.index(0xA8) - if idx > 0: - print(f" 丢弃 {idx} 字节垃圾数据: {bytes_to_hex(buffer[:idx])}") - buffer = buffer[idx:] - - # 裁判系统数据包大小: 1(ID) + 5(Data) + 2(CRC) = 8 字节 - if len(buffer) >= 8: - packet = buffer[:8] - buffer = buffer[8:] - - packet_count += 1 - print(f"\n[数据包 #{packet_count}] 裁判系统 (0xA8) - 8 字节:") - print(f" 完整数据: {bytes_to_hex(packet)}") - print(f" ID: 0x{packet[0]:02X}") - print(f" 数据: {bytes_to_hex(packet[1:6])}") - print(f" CRC: 0x{packet[6]:02X}{packet[7]:02X}") - - # 计算 CRC - crc = calculate_crc16(packet[1:6]) - received_crc = packet[6] | (packet[7] << 8) - - if crc == received_crc: - print(f" ✓ CRC 校验通过") - else: - print(f" ✗ CRC 校验失败: 计算值=0x{crc:04X}, 接收值=0x{received_crc:04X}") - print() - else: - break - else: - # 没有找到帧头,清空缓冲区 - if len(buffer) > 0: - print(f" 未找到帧头,丢弃 {len(buffer)} 字节: {bytes_to_hex(buffer)}") - buffer.clear() - break - - except KeyboardInterrupt: - print("\n\n程序退出") - except Exception as e: - print(f"错误: {e}") - finally: - if 'ser' in locals() and ser.is_open: - ser.close() - -def calculate_crc16(data): - """计算 CRC16-CCITT""" - crc16_tab = [ - 0x0000, 0x1189, 0x2312, 0x329b, 0x4624, 0x57ad, 0x6536, 0x74bf, - 0x8c48, 0x9dc1, 0xaf5a, 0xbed3, 0xca6c, 0xdbe5, 0xe97e, 0xf8f7, - 0x1081, 0x0108, 0x3393, 0x221a, 0x56a5, 0x472c, 0x75b7, 0x643e, - 0x9cc9, 0x8d40, 0xbfdb, 0xae52, 0xdaed, 0xcb64, 0xf9ff, 0xe876, - 0x2102, 0x308b, 0x0210, 0x1399, 0x6726, 0x76af, 0x4434, 0x55bd, - 0xad4a, 0xbcc3, 0x8e58, 0x9fd1, 0xeb6e, 0xfae7, 0xc87c, 0xd9f5, - 0x3183, 0x200a, 0x1291, 0x0318, 0x77a7, 0x662e, 0x54b5, 0x453c, - 0xbdcb, 0xac42, 0x9ed9, 0x8f50, 0xfbef, 0xea66, 0xd8fd, 0xc974, - 0x4204, 0x538d, 0x6116, 0x709f, 0x0420, 0x15a9, 0x2732, 0x36bb, - 0xce4c, 0xdfc5, 0xed5e, 0xfcd7, 0x8868, 0x99e1, 0xab7a, 0xbaf3, - 0x5285, 0x430c, 0x7197, 0x601e, 0x14a1, 0x0528, 0x37b3, 0x263a, - 0xdecd, 0xcf44, 0xfddf, 0xec56, 0x98e9, 0x8960, 0xbbfb, 0xaa72, - 0x6306, 0x728f, 0x4014, 0x519d, 0x2522, 0x34ab, 0x0630, 0x17b9, - 0xef4e, 0xfec7, 0xcc5c, 0xddd5, 0xa96a, 0xb8e3, 0x8a78, 0x9bf1, - 0x7387, 0x620e, 0x5095, 0x411c, 0x35a3, 0x242a, 0x16b1, 0x0738, - 0xffcf, 0xee46, 0xdcdd, 0xcd54, 0xb9eb, 0xa862, 0x9af9, 0x8b70, - 0x8408, 0x9581, 0xa71a, 0xb693, 0xc22c, 0xd3a5, 0xe13e, 0xf0b7, - 0x0840, 0x19c9, 0x2b52, 0x3adb, 0x4e64, 0x5fed, 0x6d76, 0x7cff, - 0x9489, 0x8500, 0xb79b, 0xa612, 0xd2ad, 0xc324, 0xf1bf, 0xe036, - 0x18c1, 0x0948, 0x3bd3, 0x2a5a, 0x5ee5, 0x4f6c, 0x7df7, 0x6c7e, - 0xa50a, 0xb483, 0x8618, 0x9791, 0xe32e, 0xf2a7, 0xc03c, 0xd1b5, - 0x2942, 0x38cb, 0x0a50, 0x1bd9, 0x6f66, 0x7eef, 0x4c74, 0x5dfd, - b58b, 0xa402, 0x9699, 0x8710, 0xf3af, 0xe226, 0xd0bd, 0xc134, - 0x39c3, 0x284a, 0x1ad1, 0x0b58, 0x7fe7, 0x6e6e, 0x5cf5, 0x4d7c, - 0xc60c, 0xd785, 0xe51e, 0xf497, 0x8028, 0x91a1, 0xa33a, 0xb2b3, - 0x4a44, 0x5bcd, 0x6956, 0x78df, 0x0c60, 0x1de9, 0x2f72, 0x3efb, - 0xd68d, 0xc704, 0xf59f, 0xe416, 0x90a9, 0x8120, 0xb3bb, 0xa232, - 0x5ac5, 0x4b4c, 0x79d7, 0x685e, 0x1ce1, 0x0d68, 0x3ff3, 0x2e7a, - 0xe70e, 0xf687, 0xc41c, 0xd595, 0xa12a, 0xb0a3, 0x8238, 0x93b1, - 0x6b46, 0x7acf, 0x4854, 0x59dd, 0x2d62, 0x3ceb, 0x0e70, 0x1ff9, - 0xf78f, 0xe606, 0xd49d, 0xc514, 0xb1ab, 0xa022, 0x92b9, 0x8330, - 0x7bc7, 0x6a4e, 0x58d5, 0x495c, 0x3de3, 0x2c6a, 0x1ef1, 0x0f78 - ] - - crc = 0xFFFF - for byte in data: - crc = (crc >> 8) ^ crc16_tab[(crc ^ byte) & 0xFF] - - return crc - -if __name__ == '__main__': - main()