The official implementation of C-LOAM (A Compact LiDAR Odometry and Mapping with Dynamic Removal), an accurate LiDAR odometry approach targeted for dynamic environments. C-LOAM achieve dynamic removal, ground extraction, and point cloud segmentation throught range image, showiing its compactedness. Additionally, we use ground points to estimate ground normal to impose ground contraints and feature submap to conduct loop closure detection. This work is accepted by IEEE ICUS 2024.
Welcome to our website for more details.
If you think our work useful for your research, please cite:
@misc{c-loam,
title={A Compact LiDAR Odometry and Mapping with Dynamic Removal},
author={Meifeng Zhang, Yanpeng Jia, Shiliang Shao and Shiyi Wang},
booktitle={2024 IEEE International Conference on Unmanned Systems (ICUS)},
year = {2024}
}
- Oct. 19. 2024: ⭐ Commit the codes!
- Aug. 20. 2024: ✌️ Paper is accepted by ICUS 2024!
Our system has been tested extensively on Ubuntu 20.04 Focal with ROS Noetic, although other versions may work. The following configuration with required dependencies has been verified to be compatible:
- Ubuntu 20.04
- ROS Noetic (roscpp, std_msgs, sensor_msgs, geometry_msgs, pcl_ros, jsk_recognition_msgs)
- C++ 14
- CMake >= 3.22.3
- Point Cloud Library >= 1.10.0
- Eigen >= 3.3.7
- Ceres 1.14.0
- GTSAM 4.0.3
If you cannot compile successfully, you can uncomment the line 61 of CMakeList.txt
, and replace it with your GTSAM 4.0.3
installation path, such as:
set(GTSAM_DIR "/home/jyp/3rdparty/gtsam-4.0.3/build") #4.0.3
You can use the following command to build the project:
#!/bin/bash
source "/opt/ros/${ROS_DISTRO}/setup.bash"
mkdir -p ~/catkin_ws/src
cd ~/catkin_ws/src
git clone [email protected]:Yaepiii/C-LOAM.git
cd ..
catkin_make
According to the dataset you want to test, you can modify the parameter values of pointCloudTopic
in util.h
. If an IMU is used, modify the parameter values of imuTopic
in util.h
.
After sourcing the workspace, launch the C-LOAM ROS nodes via:
#!/bin/bash
# run C-LOAM node
roslaunch c_loam run.launch
# play your bag
rosbag play your_test.bag --clock
You can modify the pose file save path in line 232 of mapOptmization.cpp
to save pose estimation results as TUM format, such that:
f_save_pose_evo.open("/home/jyp/3D_LiDAR_SLAM/pose_evo.txt", std::fstream::out);
For more results, please refer to our paper
We thank the authors of the LeGO-LOAM and SC-LeGO-LOAM open-source packages:
-
. Shan and B. Englot, "LeGO-LOAM: Lightweight and Ground-Optimized Lidar Odometry and Mapping on Variable Terrain," 2018 IEEE/RSJ International Conference on Intelligent Robots and Systems (IROS), Madrid, Spain, 2018, pp. 4758-4765
-
G. Kim and A. Kim, "Scan Context: Egocentric Spatial Descriptor for Place Recognition Within 3D Point Cloud Map," 2018 IEEE/RSJ International Conference on Intelligent Robots and Systems (IROS), Madrid, Spain, 2018, pp. 4802-4809
This work is licensed under a Creative Commons Attribution-ShareAlike 4.0 International License.