SLAM:
- ikd-Tree: A state-of-art dynamic KD-Tree for 3D kNN search.
- R2LIVE: A high-precision LiDAR-inertial-Vision fusion work using FAST-LIO as LiDAR-inertial front-end.
- LI_Init: A robust, real-time LiDAR-IMU extrinsic initialization and synchronization package..
- FAST-LIO-LOCALIZATION: The integration of FAST-LIO with Re-localization function module.
Control and Plan:
- IKFOM: A Toolbox for fast and high-precision on-manifold Kalman filter.
- UAV Avoiding Dynamic Obstacles: One of the implementation of FAST-LIO in robot's planning.
- UGV Demo: Model Predictive Control for Trajectory Tracking on Differentiable Manifolds.
- Bubble Planner: Planning High-speed Smooth Quadrotor Trajectories using Receding Corridors.
FAST-LIO (Fast LiDAR-Inertial Odometry) is a computationally efficient and robust LiDAR-inertial odometry package. It fuses LiDAR feature points with IMU data using a tightly-coupled iterated extended Kalman filter to allow robust navigation in fast-motion, noisy or cluttered environments where degeneration occurs. Our package address many key issues:
- Fast iterated Kalman filter for odometry optimization;
- Automaticaly initialized at most steady environments;
- Parallel KD-Tree Search to decrease the computation;
Related video: FAST-LIO2, FAST-LIO1
Pipeline:
New Features:
- Incremental mapping using ikd-Tree, achieve faster speed and over 100Hz LiDAR rate.
- Direct odometry (scan to map) on Raw LiDAR points (feature extraction can be disabled), achieving better accuracy.
- Since no requirements for feature extraction, FAST-LIO2 can support many types of LiDAR including spinning (Velodyne, Ouster) and solid-state (Livox Avia, Horizon, MID-70) LiDARs, and can be easily extended to support more LiDARs.
- Support external IMU.
- Support ARM-based platforms including Khadas VIM3, Nivida TX2, Raspberry Pi 4B(8G RAM).
Related papers:
FAST-LIO2: Fast Direct LiDAR-inertial Odometry
FAST-LIO: A Fast, Robust LiDAR-inertial Odometry Package by Tightly-Coupled Iterated Kalman Filter
Contributors
Wei Xu 徐威,Yixi Cai 蔡逸熙,Dongjiao He 贺东娇,Fangcheng Zhu 朱方程,Jiarong Lin 林家荣,Zheng Liu 刘政, Borong Yuan
Ubuntu >= 20.04
The default from apt PCL and Eigen is enough for FAST-LIO to work normally.
ROS >= Foxy (Recommend to use ROS-Humble). ROS Installation
PCL >= 1.8, Follow PCL Installation.
Eigen >= 3.3.4, Follow Eigen Installation.
Follow livox_ros2_driver Installation.
Remarks:
- Since the FAST-LIO must support Livox serials LiDAR firstly, so the livox_ros2_driver must be installed and sourced before run any FAST-LIO launch file.
- How to source? The easiest way is add the line
source $livox_ros2_driver_dir$/install/setup.sh
to the end of file~/.bashrc
, where$livox_ros2_driver_dir$
is the directory of the livox ros2 driver workspace (should be thews_livox
directory if you completely followed the livox official document).
Clone the repository and colcon build:
cd <ros2_ws>/src # cd into a ros2 workspace folder
git clone https://github.com/ivvi333/FAST_LIO.git --recursive
cd ..
rosdep install --from-paths src --ignore-src -y --os=ubuntu:jammy
colcon build --symlink-install
. ./install/setup.bash # use setup.zsh if use zsh
- Remember to source the livox_ros2_driver before build
- If you want to use a custom build of PCL, add the following line to ~/.bashrc
export PCL_ROOT={CUSTOM_PCL_PATH}
Noted:
A. Please make sure the IMU and LiDAR are Synchronized, that's important.
B. The warning message "Failed to find match for field 'time'." means the timestamps of each LiDAR points are missed in the rosbag file. That is important for the forward propagation and backwark propagation.
C. We recommend to set the extrinsic_est_en to false if the extrinsic is give. As for the extrinsic initiallization, please refer to our recent work: Robust Real-time LiDAR-inertial Initialization.
Connect to your PC to Livox LiDAR by following Livox-ros2-driver installation, then
cd <ros2_ws>
. install/setup.bash # use setup.zsh if use zsh
ros2 launch fast_lio mapping.launch.py config_file:=avia.yaml
Change config_file
parameter to other yaml file under config directory as you need.
Launch livox ros driver.
ros2 launch livox_ros2_driver livox_lidar_msg_launch.py
- For livox serials, FAST-LIO only support the data collected by the
livox_lidar_msg_launch.py
since only itslivox_ros2_driver/CustomMsg
data structure produces the timestamp of each LiDAR point which is very important for the motion undistortion.livox_lidar_launch.py
can not produce it right now. - If you want to change the frame rate, please modify the publish_freq parameter in the livox_lidar_msg_launch.py of Livox-ros2-driver before make the livox_ros2_driver pakage.
pcl_viewer scans.pcd
can visualize the point clouds.
Tips for pcl_viewer:
- change what to visualize/color by pressing keyboard 1,2,3,4,5 when pcl_viewer is running.
1 is all random
2 is X values
3 is Y values
4 is Z values
5 is intensity
Files: Can be downloaded from google drive!!!This ros1 bag should be convert to ros2!!!
Run:
ros2 launch fast_lio mapping.launch.py config_path:=<path_to_your_config_file>
ros2 bag play <your_bag_dir>
NCLT Dataset: Original bin file can be found here.
We produce Rosbag Files and a python script to generate Rosbag files: python3 sensordata_to_rosbag_fastlio.py bin_file_dir bag_name.bag
!!!This ros1 bag should be convert to ros2!!! To convert ros1 bag to ros2 bag, please follow the documentation Convert rosbag versions
Run:
roslaunch fast_lio mapping_velodyne.launch
rosbag play YOUR_DOWNLOADED.bag
In order to validate the robustness and computational efficiency of FAST-LIO in actual mobile robots, we build a small-scale quadrotor which can carry a Livox Avia LiDAR with 70 degree FoV and a DJI Manifold 2-C onboard computer with a 1.8 GHz Intel i7-8550U CPU and 8 G RAM, as shown in below.
The main structure of this UAV is 3d printed (Aluminum or PLA), the .stl file will be open-sourced in the future.
Thanks for LOAM(J. Zhang and S. Singh. LOAM: Lidar Odometry and Mapping in Real-time), Livox_Mapping, LINS and Loam_Livox.