Use FAST-LIO2
1 Overview
This document provides a detailed introduction on how to use the Hesai ROS driver to run the FAST-LIO2 algorithm on Hesai JT16 / JT128.
2 Prerequisites
- Ubuntu + ROS, with ROS Melodic or Noetic recommended.
- HesaiLidar_ROS_2.0 built successfully.
- FAST-LIO2 algorithm adaptation code from hesai_slam built successfully.
- The lidar, host network interface, and driver configuration are on the same subnet.
FAST-LIO2 algorithm reads these topics by default:
| Data | Default topic |
|---|---|
| Point cloud | /lidar_points |
| IMU | /lidar_imu |
The point cloud must use sensor_msgs/PointCloud2 and include these fields:
x, y, z, intensity, ring, timestamp
3 Application Method
3.1 Start Hesai ROS Driver
Launch the driver in the Hesai ROS driver workspace:
cd ~/hesai_ros_ws
source devel/setup.bash
roslaunch hesai_ros_driver start.launch
For a live lidar connection, enable live input and ROS topic output in the driver configuration:
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
Update device_ip_address, udp_port, and ptc_port according to your network.
After the driver starts, check that point cloud and IMU topics are publishing:
rostopic hz /lidar_points
rostopic hz /lidar_imu
rostopic echo -n 1 /lidar_points/fields
Confirm that /lidar_points/fields contains ring and timestamp before starting FAST-LIO2.
3.2 Start FAST-LIO2
Build and source 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
For JT16:
roslaunch fast_lio mapping_jt16.launch
For JT128:
roslaunch fast_lio mapping_jt128.launch
To start without RViz:
roslaunch fast_lio mapping_jt128.launch rviz:=false
For JT16, replace the launch file with mapping_jt16.launch.
4 Example Result
The following images show point cloud mapping results generated by running FAST-LIO2 with Hesai JT-series lidar.
5 Common Parameters
| Parameter | Description | JT16 default | JT128 default |
|---|---|---|---|
common/lid_topic | Point cloud topic | /lidar_points | /lidar_points |
common/imu_topic | IMU topic | /lidar_imu | /lidar_imu |
common/imu_gyr_unit | IMU angular velocity unit. Supports rad / deg | deg | rad |
preprocess/lidar_type | lidar type. 5 means JT16, 6 means JT128 | 5 | 6 |
preprocess/scan_line | Number of scan lines | 16 | 128 |
preprocess/timestamp_unit | Per-point timestamp unit. 0 seconds, 1 milliseconds, 2 microseconds, 3 nanoseconds | 0 | 0 |
preprocess/blind | Near-field blind-zone filtering distance, in meters | 1.0 | 0.5 |
If the driver publishes different topic names, update common/lid_topic and common/imu_topic in the FAST-LIO2 configuration.
6 Use a Rosbag
If the rosbag already contains /lidar_points and /lidar_imu, play the rosbag first and then start FAST-LIO2:
rosbag play your_data.bag
If the rosbag stores Hesai raw packets, use the Hesai ROS driver to parse and publish /lidar_points and /lidar_imu before starting FAST-LIO2.
7 FAQ
7.1 No FAST-LIO2 Output
Check that the topics exist and are publishing continuously:
rostopic list
rostopic hz /lidar_points
rostopic hz /lidar_imu
Also confirm that the topic names in the FAST-LIO2 configuration match the topics published by the driver.
7.2 Trajectory Diverges or Shakes Heavily
Check these items first:
- Whether lidar and IMU time are synchronized.
- Whether
common/imu_gyr_unitmatches the actual IMU driver output. - Whether
mapping/extrinsic_T/mapping/extrinsic_Rare correct. - Whether
preprocess/timestamp_unitmatches the unit of the point cloudtimestamp.
7.3 Extrinsic Configuration
Extrinsics are defined as the lidar pose in the IMU coordinate frame. If accurate extrinsics are available, disable online extrinsic estimation:
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]
Find it useful?