Livox Mid-360双雷达ROS驱动深度改造:独立话题发布与盲区过滤实战指南
当两个Livox Mid-360雷达同时工作时,原始驱动会将所有数据混入同一话题,导致坐标系混乱和数据处理困难。本文将带您深入驱动源码,实现双雷达数据的完全独立发布,并增加实用的点云盲区过滤功能。
1. 双雷达系统架构与问题分析
典型的双Mid-360部署方案中,两个雷达通过交换机连接到同一主机,IP地址分别为192.168.123.170和192.168.123.171。原始驱动存在三个关键问题:
- 话题冲突:两个雷达的点云、IMU数据都发布到相同话题
- 坐标系混乱:无法为每个雷达单独设置坐标系
- 无效点云干扰:雷达支架和车体附近的点云影响算法精度
提示:盲区过滤的物理原理是基于球坐标距离计算,过滤掉原点附近半径内的点云数据
2. 驱动改造核心技术方案
2.1 配置文件修改
首先修改MID360_config.json,明确指定两个雷达的IP和初始参数:
"lidar_configs": [ { "ip": "192.168.123.170", "pcl_data_type": 1, "pattern_mode": 0, "extrinsic_parameter": { "roll": 0.0, "pitch": 0.0, "yaw": 0.0, "x": 0, "y": 0, "z": 0 } }, { "ip": "192.168.123.171", "pcl_data_type": 1, "pattern_mode": 0, "extrinsic_parameter": { "roll": 0.0, "pitch": 0.0, "yaw": 0.0, "x": 0, "y": 0, "z": 0 } } ]2.2 Launch文件参数调整
在msg_MID360.launch中添加关键参数:
<arg name="multi_topic" default="1"/> <arg name="blind" default="1"/> <!-- 盲区过滤半径(m) --> <param name="blind" type="double" value="$(arg blind)"/>3. 核心代码改造详解
3.1 点云数据处理改造
在lddc.cpp中修改点云发布逻辑,主要改动包括:
- 盲区过滤实现:
int point_size_used = 0; for (size_t i = 0; i < pkg.points.size(); i++) { auto &point = pkg.points[i]; if(point.x * point.x + point.y * point.y + point.z * point.z >= blind_) { point_size_used++; } } pkg.points_num = point_size_used;- 独立坐标系设置:
std::string ip_string = IpNumToString(lds_->lidars_[index].handle); ip_string = ReplacePeriodByUnderline(ip_string); cloud.header.frame_id = "livox_frame_" + ip_string;3.2 IMU数据处理改造
修改InitImuMsg函数实现IMU数据的独立发布:
void Lddc::InitImuMsg(ImuData& imu_data, ImuMsg& imu_msg, uint64_t& timestamp, const uint8_t index) { std::string ip_string = IpNumToString(lds_->lidars_[index].handle); ip_string = ReplacePeriodByUnderline(ip_string); imu_msg.header.frame_id = "livox_frame_" + ip_string; }3.3 新增发布器函数
添加专门的点云发布器获取函数:
PublisherPtr Lddc::GetPclPublisher(uint8_t index) { ros::Publisher **pub = nullptr; uint32_t queue_size = kMinEthPacketQueueSize; if (use_multi_topic_) { pub = &private_pub_[index+2]; queue_size = queue_size / 8; } else { pub = &global_pub_; queue_size = queue_size * 8; } if (*pub == nullptr) { char name_str[48]; memset(name_str, 0, sizeof(name_str)); if (use_multi_topic_) { std::string ip_string = IpNumToString(lds_->lidars_[index].handle); snprintf(name_str, sizeof(name_str), "livox/pcl/lidar_%s", ReplacePeriodByUnderline(ip_string).c_str()); } else { snprintf(name_str, sizeof(name_str), "livox/pcl/lidar"); } *pub = new ros::Publisher; **pub = cur_node_->GetNode().advertise<PointCloud>(name_str, queue_size); } return *pub; }4. 编译与验证
完成代码修改后,执行编译命令:
source /opt/ros/noetic/setup.sh ./build.sh ROS1启动驱动并检查话题列表:
roslaunch livox_ros_driver2 msg_MID360.launch rostopic list正常输出应包含独立的话题:
/livox/imu_192_168_123_170 /livox/imu_192_168_123_171 /livox/lidar_192_168_123_170 /livox/lidar_192_168_123_171 /livox/pcl/lidar_192_168_123_170 /livox/pcl/lidar_192_168_123_1715. 实际应用效果对比
| 功能指标 | 原始驱动 | 改造后驱动 |
|---|---|---|
| 话题独立性 | 混合发布 | 完全独立 |
| 坐标系管理 | 全局统一 | 按雷达区分 |
| 无效点云 | 全部保留 | 可配置过滤 |
| SLAM适配性 | 需要额外处理 | 直接可用 |
在LIO-SAM和FAST-LIO2等SLAM算法中测试,改造后的驱动显著提升了建图质量。特别是盲区过滤功能,消除了车体附近的噪点,使场景重建更加清晰。