跳到主要内容

使用 FAST-LIO2 算法

1 概述

本文详细介绍了如何使用 Hesai ROS 驱动在禾赛 JT16 / JT128 激光雷达上运行 FAST-LIO2 算法。

2 准备工作

  • Ubuntu + ROS,建议 ROS Melodic 或 Noetic。
  • 已编译 HesaiLidar_ROS_2.0
  • 已获取并编译 hesai_slam 中的 FAST-LIO2 算法适配代码。
  • 雷达、主机网卡和驱动配置处于同一网段。

FAST-LIO2 算法默认读取以下 Topic:

数据默认 Topic
点云/lidar_points
IMU/lidar_imu

点云消息需为 sensor_msgs/PointCloud2,并包含以下字段:

x, y, z, intensity, ring, timestamp

3 使用方法

3.1 启动 Hesai ROS 驱动

在 Hesai ROS 驱动工作空间中启动驱动:

cd ~/hesai_ros_ws
source devel/setup.bash
roslaunch hesai_ros_driver start.launch

实时连接雷达时,驱动配置中需启用实时数据源和 ROS Topic 输出:

lidar:
- driver:
source_type: 1
lidar_udp_type:
device_ip_address: 192.168.1.201
udp_port: 2368
ptc_port: 9347
ros:
ros_send_point_cloud_topic: /lidar_points
ros_send_imu_topic: /lidar_imu
send_point_cloud_ros: true
send_imu_ros: true

根据实际网络修改 device_ip_addressudp_portptc_port

启动后检查点云和 IMU 是否正常发布:

rostopic hz /lidar_points
rostopic hz /lidar_imu
rostopic echo -n 1 /lidar_points/fields

确认 /lidar_points/fields 中包含 ringtimestamp 后,再启动 FAST-LIO2。

3.2 启动 FAST-LIO2 算法

编译并加载 FAST-LIO2 环境:

cd ~/catkin_ws/src
git clone https://github.com/HesaiTechnology-Spatial-Perception/hesai_slam.git
cd hesai_slam
git submodule update --init --recursive

cd ~/catkin_ws
catkin_make
source devel/setup.bash

JT16 使用:

roslaunch fast_lio mapping_jt16.launch

JT128 使用:

roslaunch fast_lio mapping_jt128.launch

如果不需要打开 RViz:

roslaunch fast_lio mapping_jt128.launch rviz:=false

JT16 同理,将 launch 文件替换为 mapping_jt16.launch

4 运行效果

下图为使用 Hesai JT 系列雷达运行 FAST-LIO2 后生成的点云建图效果。

FAST-LIO2 Hesai JT 点云建图俯视效果 FAST-LIO2 Hesai JT 点云建图斜视效果

5 常用参数

参数说明JT16 默认值JT128 默认值
common/lid_topic点云 Topic/lidar_points/lidar_points
common/imu_topicIMU Topic/lidar_imu/lidar_imu
common/imu_gyr_unitIMU 角速度单位,支持 rad / degdegrad
preprocess/lidar_type雷达类型,5 为 JT16,6 为 JT12856
preprocess/scan_line雷达线数16128
preprocess/timestamp_unit点级时间戳单位,0 秒、1 毫秒、2 微秒、3 纳秒00
preprocess/blind近距离盲区过滤距离,单位为米1.00.5

如驱动发布的 Topic 名称不同,需要同步修改 FAST-LIO2 配置中的 common/lid_topiccommon/imu_topic

6 使用 rosbag

如果 rosbag 中已经包含 /lidar_points/lidar_imu,可以先播放 rosbag,再启动 FAST-LIO2:

rosbag play your_data.bag

如果 rosbag 中保存的是 Hesai 原始 packet,需要先通过 Hesai ROS 驱动解析并发布 /lidar_points/lidar_imu,再启动 FAST-LIO2。

7 常见问题

7.1 FAST-LIO2 没有输出

检查 Topic 是否存在且持续发布:

rostopic list
rostopic hz /lidar_points
rostopic hz /lidar_imu

同时确认 FAST-LIO2 配置中的 Topic 名称与驱动实际发布的 Topic 一致。

7.2 轨迹发散或抖动明显

优先检查:

  • Lidar 与 IMU 时间是否同步。
  • common/imu_gyr_unit 是否与 IMU 驱动实际输出一致。
  • mapping/extrinsic_T / mapping/extrinsic_R 是否正确。
  • preprocess/timestamp_unit 是否与点云 timestamp 单位一致。

7.3 外参配置

外参定义为 Lidar 在 IMU 坐标系下的位姿。已有准确外参时,建议关闭在线外参估计:

mapping:
extrinsic_est_en: false
extrinsic_T: [0.0, 0.0, 0.0]
extrinsic_R: [1.0, 0.0, 0.0,
0.0, 1.0, 0.0,
0.0, 0.0, 1.0]

此文档对您有帮助吗?