zhangxy0517 / 3D-Registration-with-Maximal-Cliques

Source code of CVPR 2023 paper
MIT License
463 stars 55 forks source link

Problems with reproduction of registration results FPFH+MAC from the paper #45

Closed BorSch90 closed 8 months ago

BorSch90 commented 8 months ago

Dear Mr. Zhang, Thank you for the excellent paper, the very interesting approach and the fact that you have open sourced your implementation!

I am struggling to reproduce the results on KITTI with FPFH features that you have reported in the paper and hope you can help me find the parameters you have used. In the paper, you mention that FPFH+MAC has a recall of 99.46%. You do not further discuss whether you have done finegrain matching, so I will presume that you did not. As of today, I only manage to obtain a recall rate of ~76% so I think I must be doing something wrong. To begin with, I am running this on Linux and am certain that I have the correct versions of the dependencies (PCL = 1.10.1, igraph = 0.9.9).

As you have already discussed in the following issue , I have adapted the registration code in the following manner:

// in my own calling class
PointCloudPtr src_cloud(new pcl::PointCloud<pcl::PointXYZ>);
PointCloudPtr des_cloud(new pcl::PointCloud<pcl::PointXYZ>);
PointCloudPtr new_src_cloud(new pcl::PointCloud<pcl::PointXYZ>);
PointCloudPtr new_des_cloud(new pcl::PointCloud<pcl::PointXYZ>);

// populate pointcloud ...
float src_resolution = MeshResolution_mr_compute(src_cloud);
float des_resolution = MeshResolution_mr_compute(des_cloud);
float resolution = (src_resolution + des_resolution) / 2;

double downsample = 0.3;
Voxel_grid_downsample(src_cloud, new_src_cloud, downsample);
Voxel_grid_downsample(des_cloud, new_des_cloud, downsample);

std::vector<std::vector<float>> src_feature, des_feature;
FPFH_descriptor(new_src_cloud, downsample * 5, src_feature);
FPFH_descriptor(new_des_cloud, downsample * 5, des_feature);

std::vector<Corre_3DMatch> raw_correspondence, correspondence;
feature_matching(new_src_cloud, new_des_cloud, src_feature, des_feature, raw_correspondence);

// randomly downsample correspondences
vector<int>rand_idx;
boost_rand(5000, 0, (int)raw_correspondence.size() - 1, 5000, rand_idx);
for(int i = 0; i< 5000; i++){       
    correspondence.push_back(raw_correspondence[rand_idx[i]]);
}

registration(src_cloud, des_cloud, correspondence, ov_lable, folderPath, resolution, 0.95); 
// adapt the code to return the transform and compare with ground truth

I have searched all mentions of KITTI in the code and set the values in the registration() function used by the demo code similarly:

line 1041

string descriptor = "fpfh";
string name = "KITTI";

line 1240

igraph_maximal_cliques(&g, &cliques, 4, 0);

line 1280

inlier_thresh = 0.6;

As a concrete example of log output on failure, I want to show the result of KITTI run 08, registration pair 168 - 177:

5000 correspondences, took 721 ms
graph construction: 2.26546
coefficient computation: 0.212927
0.912101->min(0.912101 1.43598 2.47595)
clique computation: 0.248005
clique selection: 0.0180683
hypothesis generation & evaluation: 0.111791
3890 : 130873
total time 4130.55 (ms)
TE: 10.8942, RE: 0.954748

Thanks a lot for your help, I look forward to hearing from you! Robert

zhangxy0517 commented 8 months ago

1、The last parameter in the registration function should be set larger (e.g., 0.999) 2、In experiments on dataset KITTI, we reference https://github.com/ZhiChen902/SC2-PCR to save the correspondence data generated by FPFH, which is then input to MAC for testing. I suggest you follow the same approach. Here is the code used for saving data. get_correapondence_KITTI.zip The main.cpp file provides testing code for the KITTI dataset.

BorSch90 commented 8 months ago

Thank you for your swift answer! Sorry for missing that important information in the paper, I will check again :).