Comments (6)
To test KITTI data by running ./MAC --demo
command, you should modify the demo function in main.cpp
:
float downsample = 0.3; //larger value for sparse pointcloud
Voxel_grid_downsample(src_cloud, new_src_cloud, downsample);
Voxel_grid_downsample(des_cloud, new_des_cloud, downsample);
vector<vector<float>> src_feature, des_feature;
FPFH_descriptor(new_src_cloud, downsample*5, src_feature);
FPFH_descriptor(new_des_cloud, downsample*5, des_feature);
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); //FPFH 0.95 or 0.9
from 3d-registration-with-maximal-cliques.
Thanks for your reply. I tyied fix code like you suggested, and it is really useful for sparse lidar pointcoud. While it can not cover all of frame to frame registration.
And I can not get correct result when I tried to use it for frame to map registration. Is it not applicable for that?
Some bad results like this
from 3d-registration-with-maximal-cliques.
It seems that the frame point cloud is too sparse for FPFH to extract discriminative features. I think you may try some deep-learned methods mentioned in our paper to generate correspondences first, then feed the correspondences to MAC.
from 3d-registration-with-maximal-cliques.
Hello, may I ask how to modify the parameters according to the above operation and test two frames of 16 line LiDAR point clouds? One frame of point cloud has about 50000 points, but the calculation time is very long. Can you give some suggestions on how to modify the parameters。
The following are the results of terminal operation:
./MAC --demo
Start registration.
graph construction: 29.6819
coefficient computation: 368.68
340.93->min(340.93 1127.72 576.63)
clique computation: 5.57187
clique selection: 32.3755
hypothesis generation & evaluation: 0.216686
14 : 1206
1133 1220.67
from 3d-registration-with-maximal-cliques.
To test KITTI data by running
./MAC --demo
command, you should modify the demo function inmain.cpp
:float downsample = 0.3; //larger value for sparse pointcloud Voxel_grid_downsample(src_cloud, new_src_cloud, downsample); Voxel_grid_downsample(des_cloud, new_des_cloud, downsample); vector<vector<float>> src_feature, des_feature; FPFH_descriptor(new_src_cloud, downsample*5, src_feature); FPFH_descriptor(new_des_cloud, downsample*5, des_feature); 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); //FPFH 0.95 or 0.9
Please follow the above instructions. If the processing time is still significant, increase the parameter of the last line, for example, to 0.999
from 3d-registration-with-maximal-cliques.
Hello, my problem has been resolved,Thank you very much!
from 3d-registration-with-maximal-cliques.
Related Issues (20)
- About README
- bad_alloc() HOT 2
- Dataset Query HOT 2
- error report in python version HOT 9
- How to run this code?
- Linux version compiling error HOT 14
- RE < 15 and TE < 30? HOT 1
- About U3M dataset HOT 4
- Out of memory when testing 3DMatch Dataset with FPFH descriptors. HOT 4
- 数据集链接似乎失效了 HOT 2
- 请求提供更多的实验结果
- 请求提供geotransformer处理的3dmatch/3dlomatch数据集处理结果
- Parameter Conversion Errors: when Running C++ Code with igraph, PCL on Windows HOT 1
- 关于版本MSVC =2022 x64
- 您好,关于demo运行时间问题 HOT 1
- python调用c++版本mac出现segmentation falut
- 你好,关于在Linux中编译时igraph中出现了类型错误 HOT 4
- Problems with reproduction of registration results FPFH+MAC from the paper HOT 2
- 作者您好,我在结合FCGF和MAC在3DMatch数据集上测试了一下发现将体素大小设置为0.05的情况,部分最大团数量过多(2000万以上),这情况不知道您是否遇到,然后我将体素大小设为0.08,测试完和性能远不如原论文的性能,作者您当时是怎么解决这个问题的 HOT 7
- Wrong registration results. What can I do? HOT 3
Recommend Projects
-
React
A declarative, efficient, and flexible JavaScript library for building user interfaces.
-
Vue.js
🖖 Vue.js is a progressive, incrementally-adoptable JavaScript framework for building UI on the web.
-
Typescript
TypeScript is a superset of JavaScript that compiles to clean JavaScript output.
-
TensorFlow
An Open Source Machine Learning Framework for Everyone
-
Django
The Web framework for perfectionists with deadlines.
-
Laravel
A PHP framework for web artisans
-
D3
Bring data to life with SVG, Canvas and HTML. 📊📈🎉
-
Recommend Topics
-
javascript
JavaScript (JS) is a lightweight interpreted programming language with first-class functions.
-
web
Some thing interesting about web. New door for the world.
-
server
A server is a program made to process requests and deliver data to clients.
-
Machine learning
Machine learning is a way of modeling and interpreting data that allows a piece of software to respond intelligently.
-
Visualization
Some thing interesting about visualization, use data art
-
Game
Some thing interesting about game, make everyone happy.
Recommend Org
-
Facebook
We are working to build community through open source technology. NB: members must have two-factor auth.
-
Microsoft
Open source projects and samples from Microsoft.
-
Google
Google ❤️ Open Source for everyone.
-
Alibaba
Alibaba Open Source for everyone
-
D3
Data-Driven Documents codes.
-
Tencent
China tencent open source team.
from 3d-registration-with-maximal-cliques.