第一次接触Livox雷达和ROS2时,我花了两天时间才把环境配通。现在回想起来,其实只要抓住几个关键步骤就能避开大部分坑。建议使用Ubuntu 22.04 LTS系统,这是ROS2 Humble的官方支持版本。安装ROS2桌面版时,记得勾选ros-humble-desktop-full而不是基础版,否则会缺少RViz等关键工具:
bash复制sudo apt update
sudo apt install -y ros-humble-desktop-full
装完基础环境后,需要配置一个专用工作空间。我习惯在~/livox_ws目录下操作,结构清晰便于管理。创建工作空间的命令看起来简单,但有个细节容易忽略——必须确保colcon工具链完整:
bash复制mkdir -p ~/livox_ws/src
cd ~/livox_ws
sudo apt install -y python3-colcon-common-extensions
Livox驱动依赖的Livox-SDK2需要手动编译安装。这里最容易出问题的是权限配置,建议全程用普通用户操作,只在最后make install时临时提权。编译时如果遇到libpcap报错,需要先安装libpcap-dev:
bash复制git clone https://github.com/Livox-SDK/Livox-SDK2.git
cd Livox-SDK2
sudo apt install -y libpcap-dev
mkdir build && cd build
cmake .. -DCMAKE_BUILD_TYPE=Release
make -j$(nproc)
sudo make install
验证环境是否就绪有个小技巧:在终端输入ros2 doctor,它会检查所有依赖项并给出修复建议。我第一次用MID360时就靠这个命令发现少了ros-humble-tf2模块。
拿到MID360和HAP两款雷达时,最头疼的就是它们的混合配置。Livox ROS2驱动采用设备类型码区分不同雷达,MID360对应类型码8,HAP则是6。在config目录下需要为每个雷达创建独立配置文件,我建议直接复制驱动包里的模板:
bash复制cd ~/livox_ws/src/livox_ros_driver2
cp config/MID360_config.json config/HAP_config.json
网络配置是调试时最容易出错的部分。两个雷达必须设置在不同IP段,比如MID360用192.168.1.129,HAP用192.168.1.130。主机的IP要配置在host_net_info段,这里有个隐藏坑点——cmd_data_ip和point_data_ip必须相同,否则会导致数据流中断:
json复制{
"lidar_configs": [{
"ip": "192.168.1.129",
"pcl_data_type": 1,
"extrinsic_parameter": {
"roll": 0.0, "pitch": 0.0, "yaw": 0.0,
"x": 0, "y": 0, "z": 0
}
}],
"MID360": {
"lidar_net_info": {
"cmd_data_port": 56100,
"point_data_port": 56300
},
"host_net_info": {
"cmd_data_ip": "192.168.1.50",
"point_data_ip": "192.168.1.50"
}
}
}
编译驱动时推荐使用项目自带的build.sh脚本,它比colcon更了解Livox的特殊需求。如果遇到ament_index报错,先执行source /opt/ros/humble/setup.bash再重试:
bash复制cd ~/livox_ws
./src/livox_ros_driver2/build.sh humble
官方提供的启动文件需要根据实际场景调整。对于双雷达系统,我创建了自定义启动文件dual_lidar_launch.py,关键点在于设置不同的frame_id和话题命名空间:
python复制def generate_launch_description():
mid360_node = Node(
package='livox_ros_driver2',
executable='livox_ros_driver2_node',
namespace='mid360',
parameters=[{
'config_path': '/path/to/MID360_config.json',
'frame_id': 'mid360_frame'
}]
)
hap_node = Node(
package='livox_ros_driver2',
executable='livox_ros_driver2_node',
namespace='hap',
parameters=[{
'config_path': '/path/to/HAP_config.json',
'frame_id': 'hap_frame'
}]
)
return LaunchDescription([mid360_node, hap_node])
参数调优直接影响点云质量。实测发现publish_freq超过15Hz会导致HAP雷达丢包,而xfer_format设为1(自定义格式)比0(标准格式)节省30%带宽。如果启用multi_topic模式,记得每个雷达要有独立的话题前缀:
python复制parameters=[{
'publish_freq': 10.0,
'xfer_format': 1,
'multi_topic': 1,
'topic_namespace': 'custom_topic'
}]
启动时建议分步验证:先单独启动每个雷达查看原始数据,再启用融合。这个命令能同时启动双雷达和RViz:
bash复制ros2 launch livox_ros_driver2 dual_lidar_launch.py use_rviz:=true
多雷达融合的核心在于外参标定。我习惯先用棋盘格手动测量粗略外参,再用ICP算法精细调整。在配置文件中,外参顺序必须是roll→pitch→yaw,单位是弧度:
json复制"extrinsic_parameter": {
"roll": 0.785, // 45度
"pitch": 0.0,
"yaw": 1.571, // 90度
"x": 0.5, // 单位:米
"y": 0.2,
"z": 0.1
}
TF树配置不当会导致点云错位。建议创建静态TF广播节点,把两个雷达坐标系关联到统一的base_link。这个Python脚本可以添加到启动文件中:
python复制static_tf = Node(
package='tf2_ros',
executable='static_transform_publisher',
arguments=['0.5', '0', '0.1', '0', '0', '0', 'base_link', 'mid360_frame']
)
点云融合推荐使用point_cloud_assembler节点。配置max_clouds参数时要考虑雷达频率,双10Hz雷达建议设为2。我在实际项目中发现开启use_inf选项能显著提升远距离点云质量:
xml复制<node pkg="point_cloud_assembler" type="point_cloud_assembler" name="assembler">
<param name="max_clouds" value="2" />
<param name="fixed_frame" value="base_link" />
<param name="use_inf" value="true" />
</node>
在RViz中验证时,记得把Global Options→Fixed Frame设为base_link,并添加两个PointCloud2显示项,分别订阅/mid360/livox/lidar和/hap/livox/lidar话题。
网络带宽常常成为性能瓶颈。通过ifconfig查看网卡丢包率,如果超过1%就需要优化。我总结的三招很管用:1) 使用CAT6网线 2) 关闭IPv6 3) 调整内核网络缓冲区:
bash复制sudo sysctl -w net.core.rmem_max=2097152
sudo sysctl -w net.core.wmem_max=2097152
驱动日志是排查问题的金钥匙。启动节点时加上--ros-args --log-level debug参数,能看到详细的通信状态。常见错误码中,0x0001表示网络中断,0x0002代表数据校验失败。
当遇到点云断裂时,检查以下三项:
top查看实时负载)对于时间同步问题,可以启用PTP协议。在配置文件中添加:
json复制"timesync": {
"enable_ptp": true,
"ptp_profile": "1588v2"
}
记得在系统服务中启动ptpd守护进程:
bash复制sudo apt install ptpd
sudo ptpd -i eth0 -M
Livox的自定义消息格式比标准PointCloud2多出反射率和标签字段。要使用这些数据,需要在CMakeLists.txt中添加消息依赖:
cmake复制find_package(livox_ros_driver2 REQUIRED)
ament_target_dependencies(your_node
rclcpp
livox_ros_driver2_interfaces
)
处理自定义消息时,注意时间戳存储在timebase字段,单位是纳秒。这个Python代码片段演示如何解析点云:
python复制from livox_ros_driver2.msg import CustomMsg
def callback(msg):
for point in msg.points:
x = point.x # 米
reflectivity = point.reflectivity # 0-255
timestamp = msg.timebase + point.offset_time # 纳秒
我习惯编写自动化启动脚本来简化操作。这个脚本会自动检测雷达连接状态,只有两个雷达都就绪时才启动驱动:
bash复制#!/bin/bash
while ! ping -c1 192.168.1.129 &>/dev/null; do
echo "等待MID360连接..."
sleep 1
done
while ! ping -c1 192.168.1.130 &>/dev/null; do
echo "等待HAP连接..."
sleep 1
done
ros2 launch livox_ros_driver2 dual_lidar_launch.py
对于长期运行的机器人,建议添加看门狗机制。这个Python脚本会监控点云频率,异常时自动重启节点:
python复制import rclpy
from rclpy.node import Node
from livox_ros_driver2.msg import CustomMsg
class Watchdog(Node):
def __init__(self):
super().__init__('watchdog')
self.sub = self.create_subscription(
CustomMsg, '/livox/lidar', self.callback, 10)
self.last_time = self.get_clock().now()
def callback(self, msg):
now = self.get_clock().now()
if (now - self.last_time).nanoseconds > 1e9: # 1秒无数据
os.system('ros2 lifecycle set /livox_lidar_publisher shutdown')
os.system('ros2 launch livox_ros_driver2 msg_MID360_launch.py &')
self.last_time = now