Awesome
LinK3D is develped for the real-time 3D feature extraction and matching of LiDAR point cloud, which generates accurate point-to-point matching results in real time. The LinK3D paper "LinK3D: Linear Keypoints Representation for 3D LiDAR Point Cloud" (PDF) has been accepted by IEEE Robotics and Automation Letters (RA-L). The core idea of LinK3D is derived from a very simple principle: representing the current keypoint with its neighboring keypoints. The LinK3D descriptor is represented by a 180-dimensional vector. It can be potentially extended to 3D registration and LiDAR odometry tasks. We also proposed the real-time place recognition algorithm BoW3D based on LinK3D. For more details about BoW3D, please refer to our paper "BoW3D: Bag of Words for Real-Time Loop Closing in 3D LiDAR SLAM" in IEEE Robotics and Automation Letters (RA-L) (PDF).
<div align=center><img width="1800" height="340" src="fig/coreIdea.png"/></div>1. Publication
If you use the code in an academic work, please cite:
@ARTICLE{10400838,
author={Cui, Yunge and Zhang, Yinlong and Dong, Jiahua and Sun, Haibo and Chen, Xieyuanli and Zhu, Feng},
journal={IEEE Robotics and Automation Letters},
title={LinK3D: Linear Keypoints Representation for 3D LiDAR Point Cloud},
year={2024},
volume={9},
number={3},
pages={2128-2135},
keywords={Laser radar;Feature extraction;Three-dimensional displays;Point cloud compression;Task analysis;Histograms;Simultaneous localization and mapping;3D LiDAR point cloud;feature extraction and matching;real-time;LiDAR SLAM},
doi={10.1109/LRA.2024.3354550}}
@ARTICLE{9944848,
author={Cui, Yunge and Chen, Xieyuanli and Zhang, Yinlong and Dong, Jiahua and Wu, Qingxiao and Zhu, Feng},
journal={IEEE Robotics and Automation Letters},
title={BoW3D: Bag of Words for Real-Time Loop Closing in 3D LiDAR SLAM},
year={2023},
volume={8},
number={5},
pages={2828-2835},
doi={10.1109/LRA.2022.3221336}}
2. Prerequisites
We have tested the library in Ubuntu 16.04 and 20.04. A computer with an Intel Core i7 will ensure the real-time performance and provide stable and accurate results.
- ROS Kinetic for Ubuntu 16.04 and ROS Noetic for Ubuntu 20.04.
- PCL(>=1.7)
- OpenCV
- Eigen 3
3. Build LinK3D
Clone the repository and catkin_make:
cd ~/catkin_ws/src
git clone https://github.com/YungeCui/LinK3D/
cd ..
catkin_make -j8
source devel/setup.bash
If the compilation is not successful, perhaps you should adjust the CMAKE_CXX_STANDARD in the CMakeList.txt to match the C++ version on your computer.
4. KITTI Example (Velodyne HDL-64)
Download KITTI Odometry dataset to YOUR_DATASET_FOLDER. The program supports reading the point clouds in the form of .bin in the KITTI dataset. Change the "dataset_path" and "scan_line"(default:64) params in the run_bin.launch file, and save the changes. Then execute the command:
roslaunch LinK3D run_bin.launch
5. Rosbag Example
1). The program also supports receiving the Rosbag messages. The M2DGR dataset is collected by a Velodyne VLP-32C LiDAR. The Stevens-VLP16-Dataset is collected by a Velodyne VLP-16 LiDAR. The two datasets provide the point cloud in the form of ".bag" format. To run the M2DGR dataset, you should change the "scan_line" param to 32 in the run_rosbag.launch file, and save the change. To run the Stevens dataset, you should change the "scan_line" param to 16 in the run_rosbag.launch file, and save the change. Then, execute the command:
roslaunch LinK3D run_rosbag.launch
2). Play the bag file corresponding to the "scan_line" param:
rosbag play *.bag