@@ -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