R-VoxelMap is a voxel mapping method that improves localization accuracy in online LiDAR odometry by using a geometry-driven recursive plane fitting strategy. Our code is based on VoxelMap and primarily addresses the issues where VoxelMap and its variants typically fit and check planes using all points in a voxel, leading to parameter deviation due to outliers, over-segmentation of large planes, and incorrect merging across different physical planes. The main changes are as follows:
-
R-VoxelMap performs an outlier detect-and-reuse pipeline in each recursive iteration, effectively suppressing outlier influence, improving map accuracy, and reducing plane over-segmentation.
-
R-VoxelMap uses a point distribution-based plane validity check strategy, projecting and clustering point clouds on the RANSAC-fitted plane to prevent incorrect merging of different physical planes.
Related paper available on arxiv and IEEE RAL 2026.
The required dependencies are same as VoxelMap.
PCL>= 1.8, Eigen>= 3.3.4
Follow livox_ros_driver Installation.
Clone the repository and catkin_make:
cd ~/$A_ROS_DIR$/src
git clone https://github.com/NKU-MobFly-Robotics/R-VoxelMap.git
cd ..
catkin_make
source devel/setup.bash
- Remember to source the livox_ros_driver before build (follow 1.2 livox_ros_driver).
KITTI odometry dataset for example. The KITTI rosbag we used can be downloaded from Baidu Netdisk.
cd ~/$R_VOXEL_MAP_ROS_DIR$
source devel/setup.bash
roslaunch rvoxelmap kitti.launch
rosbag play kitti_00.bag --delay 1
- Make sure the topics match the rostopics you are using before running.
- Make sure log file path is modified to a suitable path.
- It is not recommended to enable the visualization option for R-VoxelMap plane features, as it may affect efficiency. If visualization is needed, you can use rosservice
/rvoxelmap/publish_allfor one-time visualization. --delay 1is used to ensure rosbag's first frame data can be captured by the algorithm.
We provide programs for testing the construction and update of R-VoxelMap.
cd ~/$R_VOXEL_MAP_ROS_DIR$
source devel/setup.bash
roslaunch rvoxelmap test.launch
- Make sure
test.launch'spcd_fileparameter points to your own PCD file.
cd ~/$R_VOXEL_MAP_ROS_DIR$
source devel/setup.bash
roslaunch rvoxelmap test_update.launch
rosbag play test.bag
- You need to prepare a test bag file containing point cloud data in PointCloud2 format.
- Make sure
test_update.launchinput point cloud topic remap to the correct topic. - It is also not recommended to enable the visualization option for R-VoxelMap plane features, as it may affect efficiency. If visualization is needed, you can use rosservice
/publish_againor/publish_allfor one-time visualization.
Our code is built on top of VoxelMap. We would like to acknowledge the contributions of the VoxelMap team for providing such a valuable framework.

