实现 IMU 数据发布 + CRC
This commit is contained in:
@@ -1,4 +1,3 @@
|
|||||||
|
|
||||||
cmake_minimum_required(VERSION 3.8)
|
cmake_minimum_required(VERSION 3.8)
|
||||||
project(amadeus_26)
|
project(amadeus_26)
|
||||||
|
|
||||||
@@ -13,6 +12,7 @@ set(CMAKE_EXPORT_COMPILE_COMMANDS ON)
|
|||||||
find_package(ament_cmake REQUIRED)
|
find_package(ament_cmake REQUIRED)
|
||||||
find_package(rclcpp REQUIRED)
|
find_package(rclcpp REQUIRED)
|
||||||
find_package(std_msgs REQUIRED)
|
find_package(std_msgs REQUIRED)
|
||||||
|
find_package(geometry_msgs REQUIRED)
|
||||||
|
|
||||||
# 添加 SDK 库路径
|
# 添加 SDK 库路径
|
||||||
set(TRANSMITTER_SDK_PATH ${CMAKE_CURRENT_SOURCE_DIR}/lib/transmitter_sdk)
|
set(TRANSMITTER_SDK_PATH ${CMAKE_CURRENT_SOURCE_DIR}/lib/transmitter_sdk)
|
||||||
@@ -32,9 +32,19 @@ ament_target_dependencies(uart_transmitter_node
|
|||||||
std_msgs
|
std_msgs
|
||||||
)
|
)
|
||||||
|
|
||||||
|
# ==================== IMU 节点 ====================
|
||||||
|
add_executable(imu_receiver_node src/imu_receiver_node.cpp)
|
||||||
|
|
||||||
|
ament_target_dependencies(imu_receiver_node
|
||||||
|
rclcpp
|
||||||
|
std_msgs
|
||||||
|
geometry_msgs
|
||||||
|
)
|
||||||
|
|
||||||
# ==================== 安装目标 ====================
|
# ==================== 安装目标 ====================
|
||||||
install(TARGETS
|
install(TARGETS
|
||||||
uart_transmitter_node
|
uart_transmitter_node
|
||||||
|
imu_receiver_node
|
||||||
DESTINATION lib/${PROJECT_NAME}
|
DESTINATION lib/${PROJECT_NAME}
|
||||||
)
|
)
|
||||||
|
|
||||||
|
|||||||
@@ -36,7 +36,7 @@ ROS2 基本架构为节点。以每个节点的发布、解析、接收数据为
|
|||||||
- 发布:描述该节点使用 ROS 发布的数据
|
- 发布:描述该节点使用 ROS 发布的数据
|
||||||
- 发送:描述该节点使用直连硬件发送的数据
|
- 发送:描述该节点使用直连硬件发送的数据
|
||||||
|
|
||||||
### 收发节点
|
### UART 收发节点
|
||||||
|
|
||||||
- 功能:主机对外通信的封装节点。物理上读取收发模块
|
- 功能:主机对外通信的封装节点。物理上读取收发模块
|
||||||
- 连接:CH340,协商 UART 通信速率 115200,`/dev/ttyUSB0`
|
- 连接:CH340,协商 UART 通信速率 115200,`/dev/ttyUSB0`
|
||||||
@@ -48,6 +48,10 @@ ROS2 基本架构为节点。以每个节点的发布、解析、接收数据为
|
|||||||
裁判系统数据(血量、比赛当前状态)
|
裁判系统数据(血量、比赛当前状态)
|
||||||
CH340 、IMU 连接 OK 标志
|
CH340 、IMU 连接 OK 标志
|
||||||
|
|
||||||
|
### IMU 收发节点
|
||||||
|
|
||||||
|
- 功能:IMU 与
|
||||||
|
|
||||||
### 中央节点
|
### 中央节点
|
||||||
|
|
||||||
- 功能:综合各类信息判断状态与转移,是控制指令发送的唯一来源
|
- 功能:综合各类信息判断状态与转移,是控制指令发送的唯一来源
|
||||||
|
|||||||
19
docs/IMU/packet/MSG_NED_VEL.md
Normal file
19
docs/IMU/packet/MSG_NED_VEL.md
Normal file
@@ -0,0 +1,19 @@
|
|||||||
|
# MSG_NED_VEL | FDISYSTEMS支持中心
|
||||||
|
|
||||||
|
该数据包用于描述:卡尔曼滤波融合的北东地速度
|
||||||
|
|
||||||
|
## 基本信息
|
||||||
|
|
||||||
|
| 属性 | 值 |
|
||||||
|
|------|-----|
|
||||||
|
| **Packet ID** | 0x5F |
|
||||||
|
| **Length** | 12 |
|
||||||
|
| **Read / Write** | Read |
|
||||||
|
|
||||||
|
## 数据字段
|
||||||
|
|
||||||
|
| Offset | Size | Format | Field | Unit | Description |
|
||||||
|
|--------|------|--------|-------|------|-------------|
|
||||||
|
| 0 | 4 | float32_t | Velocity_north | m/s | 滤波修正的北向速度 |
|
||||||
|
| 4 | 4 | float32_t | Velocity_east | m/s 7 | 滤波修正的东向速度 |
|
||||||
|
| 8 | 4 | float32_t | Velocity_down | m/s | 滤波修正的地向速度 |
|
||||||
@@ -11,6 +11,7 @@
|
|||||||
|
|
||||||
<depend>rclcpp</depend>
|
<depend>rclcpp</depend>
|
||||||
<depend>std_msgs</depend>
|
<depend>std_msgs</depend>
|
||||||
|
<depend>geometry_msgs</depend>
|
||||||
|
|
||||||
<export>
|
<export>
|
||||||
<build_type>ament_cmake</build_type>
|
<build_type>ament_cmake</build_type>
|
||||||
|
|||||||
495
src/imu_receiver_node.cpp
Normal file
495
src/imu_receiver_node.cpp
Normal file
@@ -0,0 +1,495 @@
|
|||||||
|
/**
|
||||||
|
* @file imu_receiver_node.cpp
|
||||||
|
* @brief IMU NED 速度接收节点 (FDI DETA10) - 高实时性版本
|
||||||
|
*
|
||||||
|
* 通过串口读取 FDI DETA10 IMU 模块的北东地速度数据
|
||||||
|
* 用于二维惯性导航
|
||||||
|
* 波特率:921600
|
||||||
|
* 协议:FDILink
|
||||||
|
*
|
||||||
|
* 数据包:MSG_NED_VEL (0x5F)
|
||||||
|
* - Velocity_north: 北向速度 (m/s)
|
||||||
|
* - Velocity_east: 东向速度 (m/s)
|
||||||
|
* - Velocity_down: 地向速度 (m/s)
|
||||||
|
*/
|
||||||
|
|
||||||
|
#include <atomic>
|
||||||
|
#include <cstring>
|
||||||
|
#include <errno.h>
|
||||||
|
#include <fcntl.h>
|
||||||
|
#include <geometry_msgs/msg/twist.hpp>
|
||||||
|
#include <rclcpp/rclcpp.hpp>
|
||||||
|
#include <std_msgs/msg/bool.hpp>
|
||||||
|
#include <std_msgs/msg/float32.hpp>
|
||||||
|
#include <termios.h>
|
||||||
|
#include <thread>
|
||||||
|
#include <unistd.h>
|
||||||
|
#include <vector>
|
||||||
|
|
||||||
|
// FDI Link 帧定义
|
||||||
|
constexpr uint8_t FRAME_START = 0xFC;
|
||||||
|
constexpr uint8_t FRAME_END = 0xFD;
|
||||||
|
|
||||||
|
// 数据包 ID - 只保留 NED 速度
|
||||||
|
constexpr uint8_t MSG_NED_VEL = 0x5F; // 卡尔曼滤波融合的北东地速度
|
||||||
|
|
||||||
|
// 默认串口设备
|
||||||
|
constexpr const char *DEFAULT_SERIAL_PORT = "/dev/ttyUSB1";
|
||||||
|
constexpr int DEFAULT_BAUDRATE = 921600;
|
||||||
|
|
||||||
|
// 串口读取缓冲区大小 (921600bps ≈ 115KB/s, 缓冲区需要足够大)
|
||||||
|
constexpr size_t SERIAL_READ_BUF_SIZE = 4096;
|
||||||
|
constexpr size_t MAX_FRAME_SIZE = 256;
|
||||||
|
|
||||||
|
// CRC8 查找表
|
||||||
|
static const uint8_t CRC8Table[] = {
|
||||||
|
0, 94, 188, 226, 97, 63, 221, 131, 194, 156, 126, 32, 163, 253, 31,
|
||||||
|
65, 157, 195, 33, 127, 252, 162, 64, 30, 95, 1, 227, 189, 62, 96,
|
||||||
|
130, 220, 35, 125, 159, 193, 66, 28, 254, 160, 225, 191, 93, 3, 128,
|
||||||
|
222, 60, 98, 190, 224, 2, 92, 223, 129, 99, 61, 124, 34, 192, 158,
|
||||||
|
29, 67, 161, 255, 70, 24, 250, 164, 39, 121, 155, 197, 132, 218, 56,
|
||||||
|
102, 229, 187, 89, 7, 219, 133, 103, 57, 186, 228, 6, 88, 25, 71,
|
||||||
|
165, 251, 120, 38, 196, 154, 101, 59, 217, 135, 4, 90, 184, 230, 167,
|
||||||
|
249, 27, 69, 198, 152, 122, 36, 248, 166, 68, 26, 153, 199, 37, 123,
|
||||||
|
58, 100, 134, 216, 91, 5, 231, 185, 140, 210, 48, 110, 237, 179, 81,
|
||||||
|
15, 78, 16, 242, 172, 47, 113, 147, 205, 17, 79, 173, 243, 112, 46,
|
||||||
|
204, 146, 211, 141, 111, 49, 178, 236, 14, 80, 175, 241, 19, 77, 206,
|
||||||
|
144, 114, 44, 109, 51, 209, 143, 12, 82, 176, 238, 50, 108, 142, 208,
|
||||||
|
83, 13, 239, 177, 240, 174, 76, 18, 145, 207, 45, 115, 202, 148, 118,
|
||||||
|
40, 171, 245, 23, 73, 8, 86, 180, 234, 105, 55, 213, 139, 87, 9,
|
||||||
|
235, 181, 54, 104, 138, 212, 149, 203, 41, 119, 244, 170, 72, 22, 233,
|
||||||
|
183, 85, 11, 136, 214, 52, 106, 43, 117, 151, 201, 74, 20, 246, 168,
|
||||||
|
116, 42, 200, 150, 21, 75, 169, 247, 182, 232, 10, 84, 215, 137, 107,
|
||||||
|
53};
|
||||||
|
|
||||||
|
// CRC16 查找表
|
||||||
|
static const uint16_t CRC16Table[256] = {
|
||||||
|
0x0000, 0x1021, 0x2042, 0x3063, 0x4084, 0x50A5, 0x60C6, 0x70E7, 0x8108,
|
||||||
|
0x9129, 0xA14A, 0xB16B, 0xC18C, 0xD1AD, 0xE1CE, 0xF1EF, 0x1231, 0x0210,
|
||||||
|
0x3273, 0x2252, 0x52B5, 0x4294, 0x72F7, 0x62D6, 0x9339, 0x8318, 0xB37B,
|
||||||
|
0xA35A, 0xD3BD, 0xC39C, 0xF3FF, 0xE3DE, 0x2462, 0x3443, 0x0420, 0x1401,
|
||||||
|
0x64E6, 0x74C7, 0x44A4, 0x5485, 0xA56A, 0xB54B, 0x8528, 0x9509, 0xE5EE,
|
||||||
|
0xF5CF, 0xC5AC, 0xD58D, 0x3653, 0x2672, 0x1611, 0x0630, 0x76D7, 0x66F6,
|
||||||
|
0x5695, 0x46B4, 0xB75B, 0xA77A, 0x9719, 0x8738, 0xF7DF, 0xE7FE, 0xD79D,
|
||||||
|
0xC7BC, 0x48C4, 0x58E5, 0x6886, 0x78A7, 0x0840, 0x1861, 0x2802, 0x3823,
|
||||||
|
0xC9CC, 0xD9ED, 0xE98E, 0xF9AF, 0x8948, 0x9969, 0xA90A, 0xB92B, 0x5AF5,
|
||||||
|
0x4AD4, 0x7AB7, 0x6A96, 0x1A71, 0x0A50, 0x3A33, 0x2A12, 0xDBFD, 0xCBDC,
|
||||||
|
0xFBBF, 0xEB9E, 0x9B79, 0x8B58, 0xBB3B, 0xAB1A, 0x6CA6, 0x7C87, 0x4CE4,
|
||||||
|
0x5CC5, 0x2C22, 0x3C03, 0x0C60, 0x1C41, 0xEDAE, 0xFD8F, 0xCDEC, 0xDDCD,
|
||||||
|
0xAD2A, 0xBD0B, 0x8D68, 0x9D49, 0x7E97, 0x6EB6, 0x5ED5, 0x4EF4, 0x3E13,
|
||||||
|
0x2E32, 0x1E51, 0x0E70, 0xFF9F, 0xEFBE, 0xDFDD, 0xCFFC, 0xBF1B, 0xAF3A,
|
||||||
|
0x9F59, 0x8F78, 0x9188, 0x81A9, 0xB1CA, 0xA1EB, 0xD10C, 0xC12D, 0xF14E,
|
||||||
|
0xE16F, 0x1080, 0x00A1, 0x30C2, 0x20E3, 0x5004, 0x4025, 0x7046, 0x6067,
|
||||||
|
0x83B9, 0x9398, 0xA3FB, 0xB3DA, 0xC33D, 0xD31C, 0xE37F, 0xF35E, 0x02B1,
|
||||||
|
0x1290, 0x22F3, 0x32D2, 0x4235, 0x5214, 0x6277, 0x7256, 0xB5EA, 0xA5CB,
|
||||||
|
0x95A8, 0x8589, 0xF56E, 0xE54F, 0xD52C, 0xC50D, 0x34E2, 0x24C3, 0x14A0,
|
||||||
|
0x0481, 0x7466, 0x6447, 0x5424, 0x4405, 0xA7DB, 0xB7FA, 0x8799, 0x97B8,
|
||||||
|
0xE75F, 0xF77E, 0xC71D, 0xD73C, 0x26D3, 0x36F2, 0x0691, 0x16B0, 0x6657,
|
||||||
|
0x7676, 0x4615, 0x5634, 0xD94C, 0xC96D, 0xF90E, 0xE92F, 0x99C8, 0x89E9,
|
||||||
|
0xB98A, 0xA9AB, 0x5844, 0x4865, 0x7806, 0x6827, 0x18C0, 0x08E1, 0x3882,
|
||||||
|
0x28A3, 0xCB7D, 0xDB5C, 0xEB3F, 0xFB1E, 0x8BF9, 0x9BD8, 0xABBB, 0xBB9A,
|
||||||
|
0x4A75, 0x5A54, 0x6A37, 0x7A16, 0x0AF1, 0x1AD0, 0x2AB3, 0x3A92, 0xFD2E,
|
||||||
|
0xED0F, 0xDD6C, 0xCD4D, 0xBDAA, 0xAD8B, 0x9DE8, 0x8DC9, 0x7C26, 0x6C07,
|
||||||
|
0x5C64, 0x4C45, 0x3CA2, 0x2C83, 0x1CE0, 0x0CC1, 0xEF1F, 0xFF3E, 0xCF5D,
|
||||||
|
0xDF7C, 0xAF9B, 0xBFBA, 0x8FD9, 0x9FF8, 0x6E17, 0x7E36, 0x4E55, 0x5E74,
|
||||||
|
0x2E93, 0x3EB2, 0x0ED1, 0x1EF0};
|
||||||
|
|
||||||
|
class ImuReceiverNode : public rclcpp::Node {
|
||||||
|
public:
|
||||||
|
ImuReceiverNode() : Node("imu_receiver_node") {
|
||||||
|
// 声明参数
|
||||||
|
this->declare_parameter("serial_port", DEFAULT_SERIAL_PORT);
|
||||||
|
this->declare_parameter("baudrate", DEFAULT_BAUDRATE);
|
||||||
|
this->declare_parameter("verbose", true); // 是否输出详细日志
|
||||||
|
this->declare_parameter("enable_crc", false); // 是否启用CRC校验(默认关闭)
|
||||||
|
|
||||||
|
// 获取参数
|
||||||
|
serial_port_ = this->get_parameter("serial_port").as_string();
|
||||||
|
baudrate_ = this->get_parameter("baudrate").as_int();
|
||||||
|
enable_crc_ = this->get_parameter("enable_crc").as_bool();
|
||||||
|
|
||||||
|
RCLCPP_INFO(this->get_logger(), "=================================");
|
||||||
|
RCLCPP_INFO(this->get_logger(), "IMU NED 速度接收节点启动 (高实时性版本)");
|
||||||
|
RCLCPP_INFO(this->get_logger(), "串口: %s", serial_port_.c_str());
|
||||||
|
RCLCPP_INFO(this->get_logger(), "波特率: %d", baudrate_);
|
||||||
|
RCLCPP_INFO(this->get_logger(), "CRC校验: %s",
|
||||||
|
enable_crc_ ? "启用" : "禁用");
|
||||||
|
RCLCPP_INFO(this->get_logger(), "=================================");
|
||||||
|
|
||||||
|
// 创建发布者
|
||||||
|
ned_vel_pub_ = this->create_publisher<geometry_msgs::msg::Twist>(
|
||||||
|
"imu/ned_velocity", 10);
|
||||||
|
vel_north_pub_ = this->create_publisher<std_msgs::msg::Float32>(
|
||||||
|
"imu/velocity_north", 10);
|
||||||
|
vel_east_pub_ =
|
||||||
|
this->create_publisher<std_msgs::msg::Float32>("imu/velocity_east", 10);
|
||||||
|
connection_status_pub_ = this->create_publisher<std_msgs::msg::Bool>(
|
||||||
|
"imu/connection_status", 10);
|
||||||
|
|
||||||
|
// 初始化串口
|
||||||
|
if (!initSerial()) {
|
||||||
|
RCLCPP_ERROR(this->get_logger(), "串口初始化失败,节点退出");
|
||||||
|
rclcpp::shutdown();
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
|
// 创建接收线程
|
||||||
|
receive_thread_ = std::thread(&ImuReceiverNode::receiveLoop, this);
|
||||||
|
|
||||||
|
// 创建状态发布定时器
|
||||||
|
status_timer_ = this->create_wall_timer(
|
||||||
|
std::chrono::seconds(1),
|
||||||
|
std::bind(&ImuReceiverNode::publishStatus, this));
|
||||||
|
|
||||||
|
RCLCPP_INFO(this->get_logger(), "IMU 节点初始化完成");
|
||||||
|
}
|
||||||
|
|
||||||
|
~ImuReceiverNode() {
|
||||||
|
running_ = false;
|
||||||
|
if (receive_thread_.joinable()) {
|
||||||
|
receive_thread_.join();
|
||||||
|
}
|
||||||
|
if (serial_fd_ >= 0) {
|
||||||
|
close(serial_fd_);
|
||||||
|
}
|
||||||
|
RCLCPP_INFO(this->get_logger(), "IMU 串口已关闭");
|
||||||
|
}
|
||||||
|
|
||||||
|
private:
|
||||||
|
bool initSerial() {
|
||||||
|
RCLCPP_INFO(this->get_logger(), "正在打开 IMU 串口 %s...",
|
||||||
|
serial_port_.c_str());
|
||||||
|
|
||||||
|
serial_fd_ = open(serial_port_.c_str(), O_RDWR | O_NOCTTY | O_NDELAY);
|
||||||
|
if (serial_fd_ < 0) {
|
||||||
|
RCLCPP_ERROR(this->get_logger(), "无法打开串口 %s: %s",
|
||||||
|
serial_port_.c_str(), strerror(errno));
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
struct termios tty;
|
||||||
|
memset(&tty, 0, sizeof(tty));
|
||||||
|
|
||||||
|
if (tcgetattr(serial_fd_, &tty) != 0) {
|
||||||
|
RCLCPP_ERROR(this->get_logger(), "tcgetattr 错误: %s", strerror(errno));
|
||||||
|
close(serial_fd_);
|
||||||
|
serial_fd_ = -1;
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
speed_t baud = convertBaudrate(baudrate_);
|
||||||
|
cfsetospeed(&tty, baud);
|
||||||
|
cfsetispeed(&tty, baud);
|
||||||
|
|
||||||
|
tty.c_cflag &= ~PARENB;
|
||||||
|
tty.c_cflag &= ~CSTOPB;
|
||||||
|
tty.c_cflag &= ~CSIZE;
|
||||||
|
tty.c_cflag |= CS8;
|
||||||
|
tty.c_cflag |= CREAD | CLOCAL;
|
||||||
|
tty.c_cflag &= ~CRTSCTS;
|
||||||
|
|
||||||
|
tty.c_lflag &= ~(ICANON | ECHO | ECHOE | ISIG);
|
||||||
|
tty.c_iflag &= ~(IXON | IXOFF | IXANY);
|
||||||
|
tty.c_oflag &= ~OPOST;
|
||||||
|
|
||||||
|
// 非阻塞读取,最小读取0字节,超时0
|
||||||
|
tty.c_cc[VMIN] = 0;
|
||||||
|
tty.c_cc[VTIME] = 0;
|
||||||
|
|
||||||
|
if (tcsetattr(serial_fd_, TCSANOW, &tty) != 0) {
|
||||||
|
RCLCPP_ERROR(this->get_logger(), "tcsetattr 错误: %s", strerror(errno));
|
||||||
|
close(serial_fd_);
|
||||||
|
serial_fd_ = -1;
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
tcflush(serial_fd_, TCIOFLUSH);
|
||||||
|
|
||||||
|
RCLCPP_INFO(this->get_logger(), "IMU 串口打开成功");
|
||||||
|
is_connected_ = true;
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
|
speed_t convertBaudrate(int baudrate) {
|
||||||
|
switch (baudrate) {
|
||||||
|
case 9600:
|
||||||
|
return B9600;
|
||||||
|
case 19200:
|
||||||
|
return B19200;
|
||||||
|
case 38400:
|
||||||
|
return B38400;
|
||||||
|
case 57600:
|
||||||
|
return B57600;
|
||||||
|
case 115200:
|
||||||
|
return B115200;
|
||||||
|
case 230400:
|
||||||
|
return B230400;
|
||||||
|
case 460800:
|
||||||
|
return B460800;
|
||||||
|
case 921600:
|
||||||
|
return B921600;
|
||||||
|
default:
|
||||||
|
return B921600;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
uint8_t calculateCRC8(const uint8_t *data, uint8_t len) {
|
||||||
|
uint8_t crc8 = 0;
|
||||||
|
for (uint8_t i = 0; i < len; i++) {
|
||||||
|
crc8 = CRC8Table[crc8 ^ data[i]];
|
||||||
|
}
|
||||||
|
return crc8;
|
||||||
|
}
|
||||||
|
|
||||||
|
uint16_t calculateCRC16(const uint8_t *data, uint8_t len) {
|
||||||
|
uint16_t crc16 = 0;
|
||||||
|
for (uint8_t i = 0; i < len; i++) {
|
||||||
|
crc16 = CRC16Table[((crc16 >> 8) ^ data[i]) & 0xFF] ^ (crc16 << 8);
|
||||||
|
}
|
||||||
|
return crc16;
|
||||||
|
}
|
||||||
|
|
||||||
|
// 接收循环
|
||||||
|
void receiveLoop() {
|
||||||
|
// 使用双缓冲区策略:一个用于接收,一个用于处理
|
||||||
|
std::vector<uint8_t> rx_buffer;
|
||||||
|
rx_buffer.reserve(SERIAL_READ_BUF_SIZE * 2);
|
||||||
|
|
||||||
|
// 临时读取缓冲区
|
||||||
|
uint8_t read_buf[SERIAL_READ_BUF_SIZE];
|
||||||
|
|
||||||
|
// 帧解析状态
|
||||||
|
bool in_frame = false;
|
||||||
|
std::vector<uint8_t> current_frame;
|
||||||
|
current_frame.reserve(MAX_FRAME_SIZE);
|
||||||
|
|
||||||
|
while (running_ && rclcpp::ok()) {
|
||||||
|
// 批量读串口数据
|
||||||
|
ssize_t n = read(serial_fd_, read_buf, sizeof(read_buf));
|
||||||
|
|
||||||
|
if (n > 0) {
|
||||||
|
// 将新数据追加到缓冲区
|
||||||
|
rx_buffer.insert(rx_buffer.end(), read_buf, read_buf + n);
|
||||||
|
|
||||||
|
// 处理缓冲区中的数据
|
||||||
|
size_t i = 0;
|
||||||
|
while (i < rx_buffer.size()) {
|
||||||
|
uint8_t byte = rx_buffer[i];
|
||||||
|
|
||||||
|
if (!in_frame) {
|
||||||
|
// 查找帧头
|
||||||
|
if (byte == FRAME_START) {
|
||||||
|
// 检查是否有足够的字节来读取帧头信息
|
||||||
|
if (i + 5 <= rx_buffer.size()) {
|
||||||
|
// 读取帧头信息
|
||||||
|
uint8_t msg_id = rx_buffer[i + 1];
|
||||||
|
uint8_t data_len = rx_buffer[i + 2];
|
||||||
|
uint8_t seq = rx_buffer[i + 3];
|
||||||
|
uint8_t header_crc = rx_buffer[i + 4];
|
||||||
|
|
||||||
|
// 可选的CRC校验
|
||||||
|
bool header_valid = true;
|
||||||
|
if (enable_crc_) {
|
||||||
|
uint8_t header[4] = {FRAME_START, msg_id, data_len, seq};
|
||||||
|
header_valid = (calculateCRC8(header, 4) == header_crc);
|
||||||
|
}
|
||||||
|
|
||||||
|
if (header_valid) {
|
||||||
|
// 开始收集帧数据
|
||||||
|
in_frame = true;
|
||||||
|
current_frame.clear();
|
||||||
|
current_frame.push_back(FRAME_START);
|
||||||
|
current_frame.push_back(msg_id);
|
||||||
|
current_frame.push_back(data_len);
|
||||||
|
current_frame.push_back(seq);
|
||||||
|
current_frame.push_back(header_crc);
|
||||||
|
|
||||||
|
// 计算还需要读取多少字节
|
||||||
|
size_t total_frame_len =
|
||||||
|
5 + 2 + data_len + 1; // 头+CRC16+数据+尾
|
||||||
|
size_t remaining = total_frame_len - 5; // 已经读取了5字节
|
||||||
|
|
||||||
|
// 检查缓冲区中是否有足够的数据
|
||||||
|
if (i + 5 + remaining <= rx_buffer.size()) {
|
||||||
|
// 数据足够,直接复制剩余部分
|
||||||
|
current_frame.insert(current_frame.end(),
|
||||||
|
rx_buffer.begin() + i + 5,
|
||||||
|
rx_buffer.begin() + i + 5 + remaining);
|
||||||
|
|
||||||
|
// 检查帧尾
|
||||||
|
if (current_frame.back() == FRAME_END) {
|
||||||
|
// 解析帧
|
||||||
|
processFrame(current_frame);
|
||||||
|
}
|
||||||
|
// 无论是否有帧尾,都结束当前帧处理
|
||||||
|
in_frame = false;
|
||||||
|
i += total_frame_len;
|
||||||
|
continue;
|
||||||
|
} else {
|
||||||
|
// 数据不够,需要等待更多数据
|
||||||
|
// 删除已处理的部分,保留当前帧的后续数据
|
||||||
|
rx_buffer.erase(rx_buffer.begin(), rx_buffer.begin() + i);
|
||||||
|
i = 5; // 保留当前帧头
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
i++;
|
||||||
|
} else {
|
||||||
|
// 已经在帧中,继续收集数据
|
||||||
|
current_frame.push_back(byte);
|
||||||
|
|
||||||
|
// 检查是否到达帧尾
|
||||||
|
if (byte == FRAME_END) {
|
||||||
|
// 解析帧
|
||||||
|
processFrame(current_frame);
|
||||||
|
in_frame = false;
|
||||||
|
i++;
|
||||||
|
} else if (current_frame.size() >= MAX_FRAME_SIZE) {
|
||||||
|
// 帧太长,丢弃
|
||||||
|
in_frame = false;
|
||||||
|
i++;
|
||||||
|
} else {
|
||||||
|
i++;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
// 如果不在帧中且缓冲区太大,清理旧数据
|
||||||
|
if (!in_frame && rx_buffer.size() > SERIAL_READ_BUF_SIZE) {
|
||||||
|
// 保留最后一部分数据,可能包含不完整的帧头
|
||||||
|
if (rx_buffer.size() > 100) {
|
||||||
|
rx_buffer.erase(rx_buffer.begin(), rx_buffer.end() - 100);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
} else if (n < 0 && errno != EAGAIN && errno != EWOULDBLOCK) {
|
||||||
|
// 读取错误
|
||||||
|
RCLCPP_ERROR(this->get_logger(), "串口读取错误: %s", strerror(errno));
|
||||||
|
}
|
||||||
|
// n == 0 或 EAGAIN: 没有数据可读,继续循环(无sleep,保证实时性)
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
// 处理完整的一帧数据
|
||||||
|
void processFrame(const std::vector<uint8_t> &frame) {
|
||||||
|
// 最小帧长度检查:头(5) + CRC16(2) + 尾(1) = 8
|
||||||
|
if (frame.size() < 8)
|
||||||
|
return;
|
||||||
|
|
||||||
|
// 检查帧尾
|
||||||
|
if (frame.back() != FRAME_END)
|
||||||
|
return;
|
||||||
|
|
||||||
|
uint8_t msg_id = frame[1];
|
||||||
|
uint8_t data_len = frame[2];
|
||||||
|
|
||||||
|
// 验证数据长度
|
||||||
|
size_t expected_len = 5 + 2 + data_len + 1;
|
||||||
|
if (frame.size() != expected_len)
|
||||||
|
return;
|
||||||
|
|
||||||
|
// 可选的数据CRC校验
|
||||||
|
if (enable_crc_) {
|
||||||
|
uint16_t data_crc = (frame[5] << 8) | frame[6];
|
||||||
|
uint16_t calc_crc = calculateCRC16(frame.data() + 7, data_len);
|
||||||
|
if (data_crc != calc_crc)
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
|
// 解析数据包
|
||||||
|
parsePacket(msg_id, frame.data() + 7, data_len);
|
||||||
|
}
|
||||||
|
|
||||||
|
void parsePacket(uint8_t msg_id, const uint8_t *data, uint8_t len) {
|
||||||
|
if (msg_id == MSG_NED_VEL) {
|
||||||
|
parseNEDVelocity(data, len);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
// 解析 NED 速度数据
|
||||||
|
void parseNEDVelocity(const uint8_t *data, uint8_t len) {
|
||||||
|
if (len < 12)
|
||||||
|
return;
|
||||||
|
|
||||||
|
float vel_north = *reinterpret_cast<const float *>(data);
|
||||||
|
float vel_east = *reinterpret_cast<const float *>(data + 4);
|
||||||
|
float vel_down = *reinterpret_cast<const float *>(data + 8);
|
||||||
|
|
||||||
|
// 发布 Twist 消息
|
||||||
|
geometry_msgs::msg::Twist twist_msg;
|
||||||
|
twist_msg.linear.x = vel_north; // 北向速度
|
||||||
|
twist_msg.linear.y = vel_east; // 东向速度
|
||||||
|
twist_msg.linear.z = vel_down; // 地向速度
|
||||||
|
|
||||||
|
ned_vel_pub_->publish(twist_msg);
|
||||||
|
|
||||||
|
// 单独发布北向和东向速度(方便二维导航使用)
|
||||||
|
std_msgs::msg::Float32 north_msg;
|
||||||
|
north_msg.data = vel_north;
|
||||||
|
vel_north_pub_->publish(north_msg);
|
||||||
|
|
||||||
|
std_msgs::msg::Float32 east_msg;
|
||||||
|
east_msg.data = vel_east;
|
||||||
|
vel_east_pub_->publish(east_msg);
|
||||||
|
|
||||||
|
// 增加接收计数
|
||||||
|
ned_vel_received_count_++;
|
||||||
|
|
||||||
|
// 根据 verbose 参数输出日志
|
||||||
|
bool verbose = this->get_parameter("verbose").as_bool();
|
||||||
|
if (verbose) {
|
||||||
|
RCLCPP_INFO(this->get_logger(),
|
||||||
|
"NED速度 - 北向: %.3f, 东向: %.3f, 地向: %.3f m/s", vel_north,
|
||||||
|
vel_east, vel_down);
|
||||||
|
} else {
|
||||||
|
RCLCPP_DEBUG(this->get_logger(),
|
||||||
|
"NED速度 - 北向: %.3f, 东向: %.3f, 地向: %.3f m/s",
|
||||||
|
vel_north, vel_east, vel_down);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
void publishStatus() {
|
||||||
|
auto msg = std_msgs::msg::Bool();
|
||||||
|
msg.data = is_connected_ && (serial_fd_ >= 0);
|
||||||
|
connection_status_pub_->publish(msg);
|
||||||
|
|
||||||
|
if (is_connected_) {
|
||||||
|
RCLCPP_INFO_THROTTLE(this->get_logger(), *this->get_clock(), 5000,
|
||||||
|
"IMU NED 速度接收正常 - 累计接收数据包: %zu",
|
||||||
|
ned_vel_received_count_.load());
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
// 成员变量
|
||||||
|
std::string serial_port_;
|
||||||
|
int baudrate_;
|
||||||
|
bool enable_crc_ = true; // CRC校验开关
|
||||||
|
|
||||||
|
int serial_fd_ = -1;
|
||||||
|
bool is_connected_ = false;
|
||||||
|
std::atomic<bool> running_{true};
|
||||||
|
std::thread receive_thread_;
|
||||||
|
|
||||||
|
// 统计信息
|
||||||
|
std::atomic<size_t> ned_vel_received_count_;
|
||||||
|
|
||||||
|
rclcpp::Publisher<geometry_msgs::msg::Twist>::SharedPtr ned_vel_pub_;
|
||||||
|
rclcpp::Publisher<std_msgs::msg::Float32>::SharedPtr vel_north_pub_;
|
||||||
|
rclcpp::Publisher<std_msgs::msg::Float32>::SharedPtr vel_east_pub_;
|
||||||
|
rclcpp::Publisher<std_msgs::msg::Bool>::SharedPtr connection_status_pub_;
|
||||||
|
rclcpp::TimerBase::SharedPtr status_timer_;
|
||||||
|
};
|
||||||
|
|
||||||
|
int main(int argc, char *argv[]) {
|
||||||
|
rclcpp::init(argc, argv);
|
||||||
|
|
||||||
|
auto node = std::make_shared<ImuReceiverNode>();
|
||||||
|
|
||||||
|
if (rclcpp::ok()) {
|
||||||
|
rclcpp::spin(node);
|
||||||
|
}
|
||||||
|
|
||||||
|
rclcpp::shutdown();
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
Reference in New Issue
Block a user