Skip to content

MapEval: Towards Unified, Robust and Efficient SLAM Map Evaluation Framework

Notifications You must be signed in to change notification settings

JokerJohn/Cloud_Map_Evaluation

Folders and files

NameName
Last commit message
Last commit date

Latest commit

 

History

40 Commits
 
 
 
 
 
 

Repository files navigation

MapEval: Towards Unified, Robust and Efficient SLAM Map Evaluation Framework

Xiangcheng Hu1 · Jin Wu1 · Mingkai Jia1· Hongyu Yan1· Yi Jiang2· Binqian Jiang1
Wei Zhang1 · Wei He3 · Ping Tan1*†

1HKUST   2CityU   3USTB

†project lead *corresponding author

Paper PDFPRs-WelcomeGitHub Stars FORK GitHub IssuesLicense

image-20241127080805642

MapEval is a comprehensive framework for evaluating point cloud maps in SLAM systems, addressing two fundamentally distinct aspects of map quality assessment:

  1. Global Geometric Accuracy: Measures the absolute geometric fidelity of the reconstructed map compared to ground truth. This aspect is crucial as SLAM systems often accumulate drift over long trajectories, leading to global deformation.
  2. Local Structural Consistency: Evaluates the preservation of local geometric features and structural relationships, which is essential for tasks like obstacle avoidance and local planning, even when global accuracy may be compromised.

These complementary aspects require different evaluation approaches, as global drift may exist despite excellent local reconstruction, or conversely, good global alignment might mask local inconsistencies. Our framework provides a unified solution through both traditional metrics and novel evaluation methods based on optimal transport theory.

Key Features

Traditional Metrics Implementation:

  • Accuracy (AC): Point-level geometric error assessment
  • Completeness (COM): Map coverage evaluation
  • Chamfer Distance (CD): Bidirectional point cloud difference
  • Mean Map Entropy (MME): Information-theoretic local consistency metric

Novel Proposed Metrics:

  • Average Wasserstein Distance (AWD): Robust global geometric accuracy assessment
  • Spatial Consistency Score (SCS): Enhanced local consistency evaluation

image-20241129091604653

News

  • 2024/11/26: Submitted to a Journal. When the paper accepted, the new version of codes will release!

Results

Simulated experiments

Noise Sensitivity Outlier Robustness
image-20241129091823199 image-20241129091845196

image-20241127083707943

Real-world experiments

Map Evaluation via Localization Accuracy Map Evaluation in Diverse Environments
image-20241127083813797 image-20241127083801691
image-20241129092052634
image-20241129092017261

Computational Efficiency

image-20241129091927786

Parameter Sensitivity Analysis

image-20241127084154114

Datasets

image-20241129091746334

Quickly Run

Dependencies

Test Data(password: 1)

sequence Test PCD GT PCD
MCR_slow map.pcd map_gt.pcd
FusionPortable Dataset

Usage

  1. install open3d. (maybe a higer version of CMake is needed)
git clone https://github.com/isl-org/Open3D.git
cd Open3D && mkdir build && cd build   
cmake ..
make install
  1. install cloud_map_eval
git clone https://github.com/JokerJohn/Cloud_Map_Evaluation.git
cd Cloud_Map_Evaluation/cloud_map_eval && mkdir build
cmake ..
make
./cloud_map_eval
  1. set some params
double icp_max_distance = 0.5;             // max correspondence pairs distance for  knn search in icp
int method = 2;                            // 0:point-to-point icp 1:point-to-plane icp 
Vector5d accuacy_level = Vector5d::Zero();   // set evaluatation accucay level, eg. 20cm/10cm/5cm/2cm/1cm
accuacy_level << 0.2, 0.1, 0.05, 0.02, 0.01;  //  do not recommand to change this

Eigen::Matrix4d initial_matrix = Eigen::Matrix4d::Identity();   // initial pose for your map

// the path dir must end with '/'
std::string est_path, gt_path, results_path, sequence_name;
std::string est_folder = "/home/xchu/my_git/Cloud_Map_Evaluation/cloud_map_evaluation/dataset/";
sequence_name = "MCR_slow";
est_path = est_folder + sequence_name + "/";
gt_path = est_folder + sequence_name + "/" + sequence_name + "_gt.pcd";
results_path = est_folder + sequence_name + "/";

// in  you want to evaluate mme
bool evaluate_mme = true;
bool evaluate_gt_mme = true;  // for gt map, we do not use it
  1. get the final results

we have a point cloud map generated by a pose-slam system, and we have a ground truth point cloud map. Then we caculate related metrics.

image-20240127212931498

We can also get a rendered raw distance-error map(10cm) and inlier distance-error map(2cm) in this process, the color R->G->B represent for the distance error at a level of 0-10cm.

image (4)

if we do not have gt map, we can evaluate the Mean Map Entropy (MME), smaller means better consistency.

image (5)

we can also get a simpe mesh reconstructed from point cloud map.

image-20230101200651976

  1. we got the result flies.

image-20240127213557574

Important Parameters

bool eva_mesh = false;  // if we construct a simple meth.
bool eva_mme = true; // if we evaluate mme without gt map.

// Downsampling for efficiency
map_3d_ = map_3d_->VoxelDownSample(0.03);
gt_3d_ = gt_3d_->VoxelDownSample(0.03);

double radius = 0.5;  // we choose a nearest distance of 0.5m to caculate the point cov for mme caculation.
mme_est = ComputeMeanMapEntropy(map_3d_, est_entropies, radius);
mme_gt = ComputeMeanMapEntropy(gt_3d_, gt_entropies, radius);


// rendering distance map
// when render the inlier distance map and raw distance map, we choose a thresohold of trunc_dist_[0] (20cm).
map_3d_render_inlier = renderDistanceOnPointCloud(corresponding_cloud_gt, corresponding_cloud_est, param_.trunc_dist_[0]);
map_3d_render_raw = enderDistanceOnPointCloud(gt_3d_, map_3d_, param_.trunc_dist_[0]);

Issues

How do you get your initial pose?

we can use CloudCompare to align LIO map to Gt map .

  • Roughly translate and rotate the LIO point cloud map to the GT map。

  • Manually register the moved LIO map (aligned) to the GT map (reference), and get the output of the terminal transfrom T2, then the initial pose matrix is the terminal output transform T.

image-20230106135937336

image-20230106140017020

What's the difference between raw rendered map and inlier rendered map?

The primary function of the raw rendered map (left) is to color-code the error of all points in the map estimated by the algorithm. For each point in the estimated map that does not find a corresponding point in the ground truth (gt) map, it is defaulted to the maximum error (20cm), represented as red. On the other hand, the inlier rendered map (right) excludes the non-overlapping regions of the point cloud and colors only the error of the inlier points after point cloud matching. This map therefore contains only a portion of the points from the original estimated map.

image (6)

Publications

We kindly recommend to cite our paper if you find this library useful:

@misc{hu2024mapevalunifiedrobustefficient,
      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={2024},
      eprint={2411.17928},
      archivePrefix={arXiv},
      primaryClass={cs.RO},
      url={https://arxiv.org/abs/2411.17928}, 
}


@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={},
  number={},
  pages={1-12},
  doi={10.1109/TMECH.2024.3362902}
  }

Contributors