Skip to content

Commit d1f4b02

Browse files
WIP: GlobalRegistration methods now static
1 parent 0e11970 commit d1f4b02

File tree

3 files changed

+25
-34
lines changed

3 files changed

+25
-34
lines changed

src/diffCheck/registration/registration.cc renamed to src/diffCheck/registration/globalregistration.cc

Lines changed: 6 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -1,8 +1,8 @@
1-
#include "registration.hh"
1+
#include "globalregistration.hh"
22

33
namespace diffCheck::registration
44
{
5-
std::vector<double> Registration::ComputeP2PDistance(std::shared_ptr<geometry::DFPointCloud> source, std::shared_ptr<geometry::DFPointCloud> target)
5+
std::vector<double> GlobalRegistration::ComputeP2PDistance(std::shared_ptr<geometry::DFPointCloud> source, std::shared_ptr<geometry::DFPointCloud> target)
66
{
77
std::vector<double> errors;
88
auto O3DSourcePointCloud = source->Cvt2O3DPointCloud();
@@ -13,7 +13,7 @@ namespace diffCheck::registration
1313
distances = O3DSourcePointCloud->ComputePointCloudDistance(*O3DTargetPointCloud);
1414
return distances;
1515
}
16-
open3d::pipelines::registration::RegistrationResult Registration::O3DFastGlobalRegistrationFeatureMatching(std::shared_ptr<geometry::DFPointCloud> source, std::shared_ptr<geometry::DFPointCloud> target)
16+
open3d::pipelines::registration::RegistrationResult GlobalRegistration::O3DFastGlobalRegistrationFeatureMatching(std::shared_ptr<geometry::DFPointCloud> source, std::shared_ptr<geometry::DFPointCloud> target)
1717
{
1818
std::shared_ptr<open3d::geometry::PointCloud> sourceO3D = source->Cvt2O3DPointCloud();
1919
std::shared_ptr<open3d::geometry::PointCloud> targetO3D = target->Cvt2O3DPointCloud();
@@ -39,7 +39,7 @@ namespace diffCheck::registration
3939
return result;
4040
}
4141

42-
open3d::pipelines::registration::RegistrationResult Registration::O3DFastGlobalRegistrationBasedOnCorrespondence(std::shared_ptr<geometry::DFPointCloud> source, std::shared_ptr<geometry::DFPointCloud> target)
42+
open3d::pipelines::registration::RegistrationResult GlobalRegistration::O3DFastGlobalRegistrationBasedOnCorrespondence(std::shared_ptr<geometry::DFPointCloud> source, std::shared_ptr<geometry::DFPointCloud> target)
4343
{
4444
std::shared_ptr<open3d::geometry::PointCloud> sourceO3D = source->Cvt2O3DPointCloud();
4545
std::shared_ptr<open3d::geometry::PointCloud> targetO3D = target->Cvt2O3DPointCloud();
@@ -68,7 +68,7 @@ namespace diffCheck::registration
6868
return result;
6969
}
7070

71-
open3d::pipelines::registration::RegistrationResult Registration::O3DRansacOnCorrespondence(std::shared_ptr<geometry::DFPointCloud> source, std::shared_ptr<geometry::DFPointCloud> target)
71+
open3d::pipelines::registration::RegistrationResult GlobalRegistration::O3DRansacOnCorrespondence(std::shared_ptr<geometry::DFPointCloud> source, std::shared_ptr<geometry::DFPointCloud> target)
7272
{
7373
std::shared_ptr<open3d::geometry::PointCloud> sourceO3D = source->Cvt2O3DPointCloud();
7474
std::shared_ptr<open3d::geometry::PointCloud> targetO3D = target->Cvt2O3DPointCloud();
@@ -94,7 +94,7 @@ namespace diffCheck::registration
9494
return result;
9595
}
9696

97-
open3d::pipelines::registration::RegistrationResult Registration::O3DRansacOnFeatureMatching(std::shared_ptr<geometry::DFPointCloud> source, std::shared_ptr<geometry::DFPointCloud> target)
97+
open3d::pipelines::registration::RegistrationResult GlobalRegistration::O3DRansacOnFeatureMatching(std::shared_ptr<geometry::DFPointCloud> source, std::shared_ptr<geometry::DFPointCloud> target)
9898
{
9999
std::shared_ptr<open3d::geometry::PointCloud> sourceO3D = source->Cvt2O3DPointCloud();
100100
std::shared_ptr<open3d::geometry::PointCloud> targetO3D = target->Cvt2O3DPointCloud();

src/diffCheck/registration/registration.hh renamed to src/diffCheck/registration/globalregistration.hh

Lines changed: 8 additions & 10 deletions
Original file line numberDiff line numberDiff line change
@@ -3,13 +3,14 @@
33
#include "diffCheck.hh"
44
#include <open3d/pipelines/registration/Registration.h>
55

6-
namespace diffCheck::registration{
6+
namespace diffCheck::registration
7+
{
78

8-
class Registration
9+
class GlobalRegistration //Must convert to static class
910
{
1011
public:
1112

12-
std::vector<double> ComputeP2PDistance(std::shared_ptr<geometry::DFPointCloud> source, std::shared_ptr<geometry::DFPointCloud> target);
13+
static std::vector<double> ComputeP2PDistance(std::shared_ptr<geometry::DFPointCloud> source, std::shared_ptr<geometry::DFPointCloud> target);
1314

1415
/*
1516
Documentation on Fast Point Feature Historigrams: https://pcl.readthedocs.io/projects/tutorials/en/latest/fpfh_estimation.html
@@ -25,14 +26,14 @@ class Registration
2526
2627
Quite important for us: the resultant hyperspace is dependent on the quality of the surface normal estimations at each point (if pc noisy, historigram different).
2728
*/
28-
open3d::pipelines::registration::RegistrationResult O3DFastGlobalRegistrationFeatureMatching(std::shared_ptr<geometry::DFPointCloud> source, std::shared_ptr<geometry::DFPointCloud> target);
29+
static open3d::pipelines::registration::RegistrationResult O3DFastGlobalRegistrationFeatureMatching(std::shared_ptr<geometry::DFPointCloud> source, std::shared_ptr<geometry::DFPointCloud> target);
2930

3031
/*
3132
Very little information on this registration method compared to the previous one.
3233
If I understand correctly, this method finds keypoints in the FPFH hyperspaces of the source and target point clouds and then tries to match them.
3334
https://pcl.readthedocs.io/projects/tutorials/en/latest/correspondence_grouping.html
3435
*/
35-
open3d::pipelines::registration::RegistrationResult O3DFastGlobalRegistrationBasedOnCorrespondence(std::shared_ptr<geometry::DFPointCloud> source, std::shared_ptr<geometry::DFPointCloud> target);
36+
static open3d::pipelines::registration::RegistrationResult O3DFastGlobalRegistrationBasedOnCorrespondence(std::shared_ptr<geometry::DFPointCloud> source, std::shared_ptr<geometry::DFPointCloud> target);
3637
/*
3738
Ransac registration based on correspondence:
3839
Correspondances are computed between the source and target point clouds.
@@ -42,15 +43,12 @@ class Registration
4243
In practice, Open3D gives little information about the feature correspondence
4344
4445
*/
45-
open3d::pipelines::registration::RegistrationResult Registration::O3DRansacOnCorrespondence(std::shared_ptr<geometry::DFPointCloud> source, std::shared_ptr<geometry::DFPointCloud> target);
46+
static open3d::pipelines::registration::RegistrationResult O3DRansacOnCorrespondence(std::shared_ptr<geometry::DFPointCloud> source, std::shared_ptr<geometry::DFPointCloud> target);
4647
/*
4748
Ransac registration based on Feature Matching
4849
https://www.open3d.org/docs/release/tutorial/pipelines/global_registration.html#RANSAC
4950
*/
50-
open3d::pipelines::registration::RegistrationResult Registration::O3DRansacOnFeatureMatching(std::shared_ptr<geometry::DFPointCloud> source, std::shared_ptr<geometry::DFPointCloud> target);
51-
52-
51+
static open3d::pipelines::registration::RegistrationResult O3DRansacOnFeatureMatching(std::shared_ptr<geometry::DFPointCloud> source, std::shared_ptr<geometry::DFPointCloud> target);
5352

54-
5553
};
5654
}

src/diffCheckApp.cc

Lines changed: 11 additions & 18 deletions
Original file line numberDiff line numberDiff line change
@@ -31,7 +31,7 @@ int main()
3131
// add noise to dfPointCloudPtr
3232
for (int i = 0; i < dfPointCloudPtr->Points.size(); i++)
3333
{
34-
dfPointCloudPtr->Points[i] += Eigen::Vector3d::Random() * 0.01;
34+
dfPointCloudPtr->Points[i] += Eigen::Vector3d::Random() * 0.01 ;
3535
}
3636

3737
std::vector<double> timesFGRFeatureMatching;
@@ -76,55 +76,52 @@ int iterations = 50;
7676
dfPointCloudPtrAfterTrans_3->Cvt2DFPointCloud(o3DPointCloudAfterTrans);
7777
dfPointCloudPtrAfterTrans_4->Cvt2DFPointCloud(o3DPointCloudAfterTrans);
7878

79-
80-
std::shared_ptr<diffCheck::registration::Registration> reg = std::make_shared<diffCheck::registration::Registration>();
81-
8279
// Testing the Fast Global Registration on Feature Matching method
8380
std::shared_ptr<diffCheck::geometry::DFPointCloud> dfPointCloudPtrAfterReg_1 = std::make_shared<diffCheck::geometry::DFPointCloud>();
8481
clock_t start_1 = clock();
85-
auto result_1 = reg->O3DFastGlobalRegistrationFeatureMatching(dfPointCloudPtrAfterTrans_1, dfPointCloudPtr);
82+
auto result_1 = diffCheck::registration::GlobalRegistration::O3DFastGlobalRegistrationBasedOnCorrespondence(dfPointCloudPtrAfterTrans_1, dfPointCloudPtr);
8683
double _intermediate_time_1 = (clock() - start_1) / (double) CLOCKS_PER_SEC;
8784
timesFGRFeatureMatching.push_back(_intermediate_time_1);
8885
Eigen::Matrix<double, 4, 4> transformation = result_1.transformation_;
8986
std::shared_ptr<open3d::geometry::PointCloud> o3DPointCloudPtrAfterReg_1 = std::make_shared<open3d::geometry::PointCloud>(dfPointCloudPtrAfterTrans_1->Cvt2O3DPointCloud()->Transform(transformation));
9087
dfPointCloudPtrAfterReg_1->Cvt2DFPointCloud(o3DPointCloudPtrAfterReg_1);
91-
std::vector<double> errors_1 = reg->ComputeP2PDistance(dfPointCloudPtrAfterReg_1, dfPointCloudPtrGroundTruth);
88+
std::vector<double> errors_1 = diffCheck::registration::GlobalRegistration::ComputeP2PDistance(dfPointCloudPtrAfterReg_1, dfPointCloudPtrGroundTruth);
9289
errorsFGRFeatureMatching.push_back(std::accumulate(errors_1.begin(), errors_1.end(), 0.0) / errors_1.size());
9390

9491
// Testing the Fast Global Registration on Correspondance method
9592
std::shared_ptr<diffCheck::geometry::DFPointCloud> dfPointCloudPtrAfterReg_2 = std::make_shared<diffCheck::geometry::DFPointCloud>();
9693
clock_t start_2 = clock();
97-
auto result_2 = reg->O3DFastGlobalRegistrationBasedOnCorrespondence(dfPointCloudPtrAfterTrans_2, dfPointCloudPtr);
94+
auto result_2 = diffCheck::registration::GlobalRegistration::O3DFastGlobalRegistrationBasedOnCorrespondence(dfPointCloudPtrAfterTrans_2, dfPointCloudPtr);
9895
double _intermediate_time_2 = (clock() - start_2) / (double) CLOCKS_PER_SEC;
9996
timesFGRCorrespondance.push_back(_intermediate_time_2);
10097
Eigen::Matrix<double, 4, 4> transformation_2 = result_2.transformation_;
10198
std::shared_ptr<open3d::geometry::PointCloud> o3DPointCloudPtrAfterReg_2 = std::make_shared<open3d::geometry::PointCloud>(dfPointCloudPtrAfterTrans_2->Cvt2O3DPointCloud()->Transform(transformation_2));
10299
dfPointCloudPtrAfterReg_2->Cvt2DFPointCloud(o3DPointCloudPtrAfterReg_2);
103-
std::vector<double> errors_2 = reg->ComputeP2PDistance(dfPointCloudPtrAfterReg_2, dfPointCloudPtrGroundTruth);
100+
std::vector<double> errors_2 = diffCheck::registration::GlobalRegistration::ComputeP2PDistance(dfPointCloudPtrAfterReg_2, dfPointCloudPtrGroundTruth);
104101
errorsFGRCorrespondance.push_back(std::accumulate(errors_2.begin(), errors_2.end(), 0.0) / errors_2.size());
105102

106103
// Testing the Ransac registration based on correspondance method
107104
std::shared_ptr<diffCheck::geometry::DFPointCloud> dfPointCloudPtrAfterReg_3 = std::make_shared<diffCheck::geometry::DFPointCloud>();
108105
clock_t start_3 = clock();
109-
auto result_3 = reg->O3DRansacOnCorrespondence(dfPointCloudPtrAfterTrans_3, dfPointCloudPtr);
106+
auto result_3 = diffCheck::registration::GlobalRegistration::O3DRansacOnCorrespondence(dfPointCloudPtrAfterTrans_3, dfPointCloudPtr);
110107
double _intermediate_time_3 = (clock() - start_3) / (double) CLOCKS_PER_SEC;
111108
timesRansacCorrespondance.push_back(_intermediate_time_3);
112109
Eigen::Matrix<double, 4, 4> transformation_3 = result_3.transformation_;
113110
std::shared_ptr<open3d::geometry::PointCloud> o3DPointCloudPtrAfterReg_3 = std::make_shared<open3d::geometry::PointCloud>(dfPointCloudPtrAfterTrans_3->Cvt2O3DPointCloud()->Transform(transformation_3));
114111
dfPointCloudPtrAfterReg_3->Cvt2DFPointCloud(o3DPointCloudPtrAfterReg_3);
115-
std::vector<double> errors_3 = reg->ComputeP2PDistance(dfPointCloudPtrAfterReg_3, dfPointCloudPtrGroundTruth);
112+
std::vector<double> errors_3 = diffCheck::registration::GlobalRegistration::ComputeP2PDistance(dfPointCloudPtrAfterReg_3, dfPointCloudPtrGroundTruth);
116113
errorsRansacCorrespondance.push_back(std::accumulate(errors_3.begin(), errors_3.end(), 0.0) / errors_3.size());
117114

118115
// Testing the Ransac registration based on Feature Matching method
119116
std::shared_ptr<diffCheck::geometry::DFPointCloud> dfPointCloudPtrAfterReg_4 = std::make_shared<diffCheck::geometry::DFPointCloud>();
120117
clock_t start_4 = clock();
121-
auto result_4 = reg->O3DRansacOnFeatureMatching(dfPointCloudPtrAfterTrans_4, dfPointCloudPtr);
118+
auto result_4 = diffCheck::registration::GlobalRegistration::O3DRansacOnFeatureMatching(dfPointCloudPtrAfterTrans_4, dfPointCloudPtr);
122119
double _intermediate_time_4 = (clock() - start_4) / (double) CLOCKS_PER_SEC;
123120
timesRansacFeatureMatching.push_back(_intermediate_time_4);
124121
Eigen::Matrix<double, 4, 4> transformation_4 = result_4.transformation_;
125122
std::shared_ptr<open3d::geometry::PointCloud> o3DPointCloudPtrAfterReg_4 = std::make_shared<open3d::geometry::PointCloud>(dfPointCloudPtrAfterTrans_4->Cvt2O3DPointCloud()->Transform(transformation_4));
126123
dfPointCloudPtrAfterReg_4->Cvt2DFPointCloud(o3DPointCloudPtrAfterReg_4);
127-
std::vector<double> errors_4 = reg->ComputeP2PDistance(dfPointCloudPtrAfterReg_4, dfPointCloudPtrGroundTruth);
124+
std::vector<double> errors_4 = diffCheck::registration::GlobalRegistration::ComputeP2PDistance(dfPointCloudPtrAfterReg_4, dfPointCloudPtrGroundTruth);
128125
errorsRansacFeatureMatching.push_back(std::accumulate(errors_4.begin(), errors_4.end(), 0.0) / errors_4.size());
129126

130127
std::cout<<"Iteration: "<<i<<" "<<std::flush;
@@ -166,11 +163,7 @@ int iterations = 50;
166163
fileErrors<<errorsFGRFeatureMatching[i]<<","<<errorsFGRCorrespondance[i]<<","<<errorsRansacCorrespondance[i]<<","<<errorsRansacFeatureMatching[i]<<std::endl;
167164
fileTimes<<timesFGRFeatureMatching[i]<<","<<timesFGRCorrespondance[i]<<","<<timesRansacCorrespondance[i]<<","<<timesRansacFeatureMatching[i]<<std::endl;
168165
}
169-
170-
171-
172-
173-
174-
166+
fileErrors.close();
167+
fileTimes.close();
175168
return 0;
176169
}

0 commit comments

Comments
 (0)