Skip to content
/ PALoc Public
forked from JokerJohn/PALoc

[TMECH'2024] Official codes of ”PALoc: Advancing SLAM Benchmarking with Prior-Assisted 6-DoF Trajectory Generation and Uncertainty Estimation“

Notifications You must be signed in to change notification settings

baidu31/PALoc

 
 

Folders and files

NameName
Last commit message
Last commit date

Latest commit

 
 
 
 
 
 
 
 
 
 
 

Repository files navigation

PALoc: Advancing SLAM Benchmarking with Prior-Assisted 6-DoF Trajectory Generation and Uncertainty Estimation

PALoc Overview

Paper PDF YoutubevideoPRs-WelcomeGitHub Stars FORK GitHub IssuesLicense

Introduction

PALoc presents a novel approach for generating high-fidelity, dense 6-DoF ground truth (GT) trajectories, enhancing the evaluation of Simultaneous Localization and Mapping (SLAM) under diverse environmental conditions. This framework leverages prior maps to improve the accuracy of indoor and outdoor SLAM datasets. Key features include:

  • Robustness in Degenerate Conditions: Exceptionally handles scenarios frequently encountered in SLAM datasets.
  • Advanced Uncertainty Analysis: Detailed covariance derivation within factor graphs, enabling precise uncertainty propagation and pose analysis.
  • Open-Source Toolbox: An open-source toolbox is provided for map evaluation, indirectly assessing trajectory precision.

Pipeline

News

  • 2025/01/22: Add new data bag redbird_03 in MS-Dataset.
  • 2025/01/16: A real-time map-based localization system with new features is on the way, see this repo LTLoc!
  • 2024/12/26: Formally Published by IEEE/ASME TMECH.
  • 2024/12/06: Adapt for real-time map-based localization, see fp_os128_corridor_loc.launch and instructions.
  • 2024/11/15: Docker support!
  • 2024/08/15: Support newer college dataset!
  • 2024/08/15: Support FusionPortable dataset and MS-dataset
  • 2024/08/14: Release codes and data.
  • 2024/03/26: Early access by IEEE/ASME TMECH.
  • 2024/02/01: Preparing codes for release.
  • 2024/01/29: Accepted by 2024 IEEE/ASME TMECH.
  • 2023/12/08: Resubmitted.
  • 2023/08/22: Reject and resubmitted.
  • 2023/05/13: Submitted to IEEE/ASME TRANSACTIONS ON MECHATRONICS (TMECH).
  • 2023/05/08: Accepted by ICRA 2023 Workshop on Future of Construction.

Dataset

This data was provided by Zhiqiang Chen and Prof.Yuhua Qi from SYSU and HKU.

Stairs scenes with different types of lidar and glass noise. This is very challenging due to narrow stairs , you need to tune some parameters of ICP. The prior map and raw map can be downloaded.

Prior map without glass noise Raw prior map
Sensor setup Download link
Velodyne16+ xsense IMU http://gofile.me/4jm56/yCBxjdEXA
Ouster64 + xsense IMU http://gofile.me/4jm56/2EoKPDfKi
image-20240813195354720 image-20240812181454491

Our algorithms were tested on the Fusion Portable Dataset.

Sequence GT Map Scene
20220216_corridor_day corridor with x degeneracy. corridor_day_gif
20220216_canteen_day The prior map only covers a portion of the scene. canteen_day_gif
20220219_MCR_normal_01 Performance on a quadruped robot platform. normal-01-gif
20220216_escalator_day Performance in an open stairwell scenario. escaltor_day_gif
20220216_garden_day Smaller scenario, similar to an indoor environment. garden_day_gif
20220225_building_day Three loops of indoor hallway scanning with a handheld device, taking a relatively long time. building-day-gif

This dataset include 2 different maps: parkland and math-institute.

Parkland Math-institute
image-20240816230105207 image-20240816232236054

Self-collected Dataset

Getting Started

Docker Support

It is recommended to run the code in the container while visualize it in the host machine, e.g.:

Pull the Docker image:

docker pull ulterzlw/paloc

Run the container with host network access:

docker run -it --network host ulterzlw/paloc bash

launch the application (inside the container):

roslaunch paloc geode_beta_os64.launch

Start RViz (on the host machine):

rviz -d ${PATH_TO_PALOC}/config/rviz/ouster_indoors.rviz

Install

Recommend to use system eigen when install GTSAM.

cmake -DGTSAM_USE_SYSTEM_EIGEN=ON -DGTSAM_BUILD_UNSTABLE:OPTION=ON -DCMAKE_BUILD_TYPE=Release ..

if you have already installed other version of GTSAM

# install this version of GTSAM to a fixed path 
cmake -DGTSAM_USE_SYSTEM_EIGEN=ON -DGTSAM_BUILD_UNSTABLE:OPTION=ON -DCMAKE_BUILD_TYPE=Release -DCMAKE_INSTALL_PREFIX=/home/xchu/cmake_project ..

make install

# modity your cmakelist.txt to search for the specific version
find_package(GTSAM 4.0.3 REQUIRED PATHS /home/xchu/cmake_project NO_DEFAULT_PATH)
include_directories(
  /home/xchu/cmake_project/include  # 确保优先使用自定义路径
)
link_directories(/home/xchu/cmake_project/lib)
target_link_libraries(xx_node
  ${catkin_LIBRARIES}
  ${PCL_LIBRARIES}
  yaml-cpp
  /home/xchu/cmake_project/lib/libgtsam.so  # 直接指定库文件
)

Additionally, there is no need to install the livox_ros_driver required by FAST-LIO2, as we have directly integrated the necessary message headers into the code.

Quickly Run

download the demo rosbag and prior map, set the file path in geode_beta_os64.launch.

#ouster64 : GEODE dataset
roslaunch paloc geode_beta_os64.launch

#velodyne16: GEODE dataset
roslaunch paloc geode_alpha_vlp16.launch

#ouster128 fusionportable-corridor
roslaunch paloc fp_os128_corridor.launch

#pandar xt32: MS-dataset
roslaunch paloc ms_sbg_pandar32.launch

#ouster128: newer_colleage dataset
roslaunch paloc newer_colleage_os128.launch 

then play rosbag:

# ouster64
rosbag play stairs_bob.bag

#velodyne16
rosbag play stairs_alpha.bag

#ouster128 fusionportable-corridor
rosbag play 20220216_corridor_day_ref.bag

#pandar xt32
rosbag play Parkinglot-2023-10-28-18-59-01.bag 

#ouster128
rosbag play parkland0.bag

You can save data.

rosservice call /save_map

image-20240813173140476

For your own dataset

Set Parameters

Set your file path in geode_beta_os64.launch. Put your prior map file in prior_map_directory, the map name must be set as the sequence. The map file size is recommend to down-sampled less than 2Gb.

<param name="save_directory" type="string" value="/home/xchu/data/paloc_result/"/>
<param name="prior_map_directory" type="string" value="/home/xchu/data/prior_map/paloc_map_file/"/>

<arg name="sequence" default="stairs_bob"/>

image-20240813184225320

Adapt for FAST-LIO2

Set parameters in geode_beta_os64.yaml. Adapt for the FAST-LIO2 first.

common:
  lid_topic: "/ouster/points"
  imu_topic: "/imu/data"

  acc_cov: 1.1118983704388789e-01                     # acc noise and bias
  b_acc_cov: 1.5961182793700285e-03
  gyr_cov: 9.6134865171113148e-02                     # gyro noise and bias
  b_gyr_cov: 7.9993782046705285e-04

  extrinsic_T: [ -0.027172, -0.034873, 0.062643 ]     # from lidar to imu
  extrinsic_R: [ 0.998638, 0.052001, -0.004278,
                 -0.051937, 0.998554, 0.013900,
                 0.004994, -0.013659, 0.999894 ]
lio:
  lidar_type: 8      # 1 for Livox serials LiDAR, 2 for Velodyne LiDAR, 3 for ouster LiDAR,
  scan_line: 64
  scan_rate: 10      # only need to be set for velodyne, unit: Hz,
  timestamp_unit: 3  # 0-second, 1-milisecond, 2-microsecond, 3-nanosecond.
  blind: 0.5         # remove the nearest point cloud

Get Initial pose using CloudCompare

then set the initial pose. When you run the launch command, the first point cloud will be saved in save_directory, you can align it with the prior map using CloudCompare to get the initial pose.

common:
    initial_pose: [ -0.519301, 0.850557, 0.082936 ,-11.347226,
                  -0.852164, -0.522691, 0.024698, 3.002144,
                  0.064357, -0.057849, 0.996249, -0.715776,
                  0.000000, 0.000000, 0.000000, 1.000000 ]

image-20240813185337470

image-20240807094808981

Evaluation with MapEval

We can evaluate the map accuracy of PAloc as follows. Note that when you use the Cloud Map Evaluation library, the map of PALoc or ICP do not need to set initial pose since they are already in the same coordinate. But evaluate the map from FAST-LIO2 must to set it.

Raw Error Map Entropy Map
image-20240813190359418 image-20240813190440224

Evaluation results example can be downloaded here.

TODO

  • The covariance of map factor should be described on SE3, not SO3 * R3
  • support for LIO-SAM
  • gravity factor

Results

Trajectory Evaluation

Trajectory Evaluation

Map Evaluation

Map Evaluation 1 image-20240323141038974

Degeneracy Analysis

X Degenerate (Translation) Yaw Degenerate (Rotation)
X Translation Degeneracy Yaw Rotation Degeneracy

Degeneracy Analysis

Time Analysis

To plot the results, you can follow this scripts.

Time Analysis 1
Time Analysis 2

Important Issue

How do we calculate covariance of odom factor in GTSAM?

We follow the assumption of pose Independence as barfoot does(TRO 2014) as equation (13), there is no correlated cov between this two poses. Left-hand convention means a small increments on world frame.

image-20240408203918682

Since GTSAM follow the right-hand convention on SE(3) , we need to use the adjoint representation as equation (14). Please note that there is an error in Equation 14. The paper has not yet been updated. The adjoint matrix of the inverse relative pose should be used, not the adjoint of the relative pose.

image-20240408204125990

Code Implement in degenercy detection

some people may curious about why i use the max eigenvalues as the rotation part, then caculate the condtion number of the rotation. This is not a right way, since the eigenvalues will lose its order after SVD/EVD. reader can refer to my new paper DCReg to find the reasons and real-world example.

Citations

For referencing our work in PALoc, please use:

@ARTICLE{hu2024paloc,
  author={Hu, Xiangcheng and Zheng, Linwei and Wu, Jin and Geng, Ruoyu and Yu, Yang and Wei, Hexiang and Tang, Xiaoyu and Wang, Lujia and Jiao, Jianhao and Liu, Ming},
  journal={IEEE/ASME Transactions on Mechatronics}, 
  title={PALoc: Advancing SLAM Benchmarking With Prior-Assisted 6-DoF Trajectory Generation and Uncertainty Estimation}, 
  year={2024},
  volume={29},
  number={6},
  pages={4297-4308},
  doi={10.1109/TMECH.2024.3362902}}

The map evaluation metrics of this work follow MapEval. Please cite:

@misc{hu2024mapeval,
      title={MapEval: Towards Unified, Robust and Efficient SLAM Map Evaluation Framework}, 
      author={Xiangcheng Hu and Jin Wu and Mingkai Jia and Hongyu Yan and Yi Jiang and Binqian Jiang and Wei Zhang and Wei He and Ping Tan},
      year={2025},
      volume={10},
      number={5},
      pages={4228-4235},
  	  doi={10.1109/LRA.2025.3548441}
}

Acknowledgment

The code in this project is adapted from the following projects:

  • The odometry method is adapted from FAST-LIO2 and LIO-SAM.
  • The basic framework for pose graph optimization (PGO) is adapted from SC-A-LOAM.
  • The Point-to-Plane registration is adapted from LOAM.

Contributors

About

[TMECH'2024] Official codes of ”PALoc: Advancing SLAM Benchmarking with Prior-Assisted 6-DoF Trajectory Generation and Uncertainty Estimation“

Resources

Stars

Watchers

Forks

Releases

No releases published

Packages

No packages published

Languages

  • C++ 99.2%
  • Other 0.8%