IMM-LIO (Interaction Multiple Models LiDAR-Inertial Odometry) is a reliable and effective LiDAR-inertial odometry package that supports multiple filters for estimation. It mitigates LiDAR motion distortion by leveraging high-rate IMU data through a tightly-coupled approach using the IMM filter. Three models—constant velocity, acceleration, and turning rate—are employed in this work.
The framework has been tested with ROS Noetic and Ubuntu 20.04. The following configuration, along with the required dependencies, has been verified for compatibility:
- Ubuntu 20.04
- ROS Noetic (
roscpp
,std_msgs
,sensor_msgs
,geometry_msgs
) - C++ 14
- PCL >= 1.8
- Eigen >= 3.3.4
- ZED SDK >= 3.5
- CUDA (Recommend to use CUDA toolkit >= 11 for Ubuntu 20.04)
- Velodyne PUCK Lite (360 HFOV, +15 degree VFOV, 100m range, 10Hz)
- Zedm camera
- Handheld device
- Ground Rover Robot
All the variables are described in detail in the paper
We have designed a system that supports multiple filters, making it suitable for real-time applications. This package introduces several new features:- Support external for 9-axis, and internal 6-axis IMU.
- The 'State Prediction' module produces multiple estimations, thanks to the use of multiple models. This ensures consistent performance even if one model degrades.
- The 'Model Probability' module calculates the likelihood of LiDAR measurements with respect to the laser points estimated by each model in IMM. This module contributes to the final estimation and reduces computational complexity compared to direct non-linear filters.
Use the following commands to download and build the package: (The code is implemented in ROS1)
mkdir catkin_ws
cd ~/caktin_ws/src // caktin_ws or your ROS Dir
git clone https://github.com/aralab-unr/IMM_LIO.git
cd IMM_LIO
cd ../..
source devel/setup.bash
catkin_make
Requires an input LiDAR point cloud of type sensor_msgs::PointCloud2
and IMU input of type sensor_msgs::IMU
- Setup LiDAR and IMU before run. To achieve optimal performance, it is essential to calibrate and synchronize both the LiDAR and IMU.
- Edit the file
config/velodyne.yaml
to set the parameters. - Set the LiDAR and IMU topic at:
lid_topic
,imu_topic
- Change the LiDAR, and IMU extrinsic calibration parameters:
extrinsic_R
, andextrinsic_T
. - Set the IMU as base frame.
For Velodyne type
- Run the launch file:
roslaunch imm_lio velodyne.launch
2. Play existing bag files:
rosbag play your-file.bag
- Download sample dataset which are collected in UNR campuse to test the package. In these dataset, the point cloud topic is
"/velodyne_points"
, and the imu topic need to be set to"zed/zed_nodelet/imu/data"
- Download Urban Hong Kong dataset medium-urban deep-urban. Set the imu topic to
"/imu/data"
.
Depending on the number of models and their characteristics, the users can modify the transition matrix of the IMM model (p_ij) in the 'IMM_lio.cpp' file. The default values used in this work are [0.9, 0.01, 0.09; 0.025, 0.75, 0.225; 0.075, 0.175, 0.75]. Ensure that the sum of each row equals 1
We thank the authors of Fast-LIO2 and LiDAR-IMU calibration for providing open-source packages:
-
Xu, W., Cai, Y., He, D., Lin, J., & Zhang, F. (2022). Fast-lio2: Fast direct lidar-inertial odometry. IEEE Transactions on Robotics, 38(4), 2053-2073.
-
F. Zhu, Y. Ren and F. Zhang, "Robust Real-time LiDAR-inertial Initialization," 2022 IEEE/RSJ International Conference on Intelligent Robots and Systems (IROS), Kyoto, Japan, 2022, pp. 3948-3955, doi: 10.1109/IROS47612.2022.9982225.