A simple localization framework that can re-localize in built maps based on POINT-LIO and works with ROS Noetic.
~~- 2024-08-29: small_gicp by kenji koide implemented for robust, fast, threaded scan-to-map matching (By Jason Kim)
~~- 2024-08-28: FAST-LIO altered with POINT-LIO, now running extensively robust to drift (By Jason Kim)
~~- 2023: Add Open3D 0.13 support. (By Jason Kim)
~~- 2021-08-11: Add Open3D 0.7 support.
~~- 2021-08-09: Migrate to Open3D for better performance.
- Realtime 3D global localization in a pre-built point cloud map. By fusing low-frequency global localization (about 0.5~0.2Hz), and high-frequency, drift-robust odometry from POINT-LIO, the entire system is computationally efficient.
- Eliminate the accumulative error of the odometry.
- The initial localization can be provided either by rough manual estimation from RVIZ, or pose from another sensor/algorithm.
- Using Small_GICP, the registration now accepts more tolerence in rough initial pose input, subsequently robust to unstructured and dynamic query input.
Technically, if you have built and run POINT-LIO before, you may skip section 2.1.
This part of dependency is consistent with POINT-LIO, please refer to the documentation POINT-LIO prequisites
-
python 2.7python 3.8
sudo apt install ros-$ROS_DISTRO-ros-numpy
pip install numpy==1.21
pip install open3d==0.9
pip install open3d==0.13
Notice that, there may be issue when installing Open3D directly using pip in Python2.7:
you may firstly install pyrsistent:
Then
pip install open3d==0.9
Just pip install open3d==0.13 (or later version)
Clone the repository and catkin_make:
cd ~/$A_ROS_DIR$/src
git clone https://github.com/U-AMC/POINT_LIO_LOCALIZATION
cd POINT_LIO_LOCALIZATION
git submodule update --init
cd ../..
catkin_make
source devel/setup.bash
- Remember to source the livox_ros_driver before build (follow livox_ros_driver)
- If you want to use a custom build of PCL, add the following line to ~/.bashrc
export PCL_ROOT={CUSTOM_PCL_PATH}
Demo rosbag in a large underground garage: Google Drive | Baidu Pan (Code: ne8d);
Corresponding map: Google Drive | Baidu Pan (Code: kw6f)
The map can be built using LIO-SAM or FAST-LIO-SLAM.
-
First, please make sure you're using the Python
2.73.8 environment; -
Run localization, here we take Livox AVIA as an example:
roslaunch point_lio_localization localization_avia.launch map:=/path/to/your/map.pcd
Please modify /path/to/your/map.pcd
to your own map point cloud file path.
Wait for 3~5 seconds until the map cloud shows up in RVIZ;
- If you are testing with the sample rosbag data:
rosbag play localization_test_scene_1.bag
Or if you are running realtime
roslaunch livox_ros_driver livox_lidar_msg.launch
Please set the publish_freq in livox_lidar_rviz.launch to 10Hz, to ensure there are enough points for global localization in a single scan. Support for higher frequency is coming soon.
- Provide initial pose
rosrun point_lio_localization publish_initial_pose.py 14.5 -7.5 0 -0.25 0 0
The numerical value 14.5 -7.5 0 -0.25 0 0 denotes 6D pose x y z yaw pitch roll in map frame, which is a rough initial guess for localization_test_scene_1.bag.
The initial guess can also be provided by the '2D Pose Estimate' Tool in RVIZ.
Note that, during the initialization stage, it's better to keep the robot still. Or if you play bags, fistly play the bag for about 0.5s, and then pause the bag until the initialization succeed.
- POINT-LIO: A computationally efficient and robust LiDAR-inertial odometry (LIO) package
- ikd-Tree: A state-of-art dynamic KD-Tree for 3D kNN search.
- FAST-LIO-SLAM: The integration of FAST-LIO with Scan-Context loop closure module.
- LIO-SAM_based_relocalization: A simple system that can relocalize a robot on a built map based on LIO-SAM.
Thanks for the authors of POINT-LIO and LIO-SAM_based_relocalization.
- Go over the timestamp issue of the published odometry and tf;
- Using integrated points for global localization;
- Fuse global localization with the state estimation of
FAST-LIOPOINT-LIO, and smooth the localization trajectory; - Updating...