00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037
00038
00039
00040 #include <gtest/gtest.h>
00041
00042 #include <pcl/point_types.h>
00043 #include <pcl/io/pcd_io.h>
00044 #include <pcl/features/normal_3d.h>
00045 #include <pcl/features/fpfh.h>
00046 #include <pcl/registration/registration.h>
00047 #include <pcl/registration/icp.h>
00048 #include <pcl/registration/icp_nl.h>
00049 #include <pcl/registration/gicp.h>
00050 #include <pcl/registration/transformation_estimation_point_to_plane.h>
00051 #include <pcl/registration/transformation_validation_euclidean.h>
00052 #include <pcl/registration/ia_ransac.h>
00053 #include <pcl/registration/pyramid_feature_matching.h>
00054 #include <pcl/features/ppf.h>
00055 #include <pcl/registration/ppf_registration.h>
00056 #include <pcl/registration/ndt.h>
00057 #include <pcl/registration/sample_consensus_prerejective.h>
00058
00059 #include <pcl/kdtree/impl/kdtree_flann.hpp>
00060
00061
00062 using namespace pcl;
00063 using namespace pcl::io;
00064 using namespace std;
00065
00066 PointCloud<PointXYZ> cloud_source, cloud_target, cloud_reg;
00067
00068 template <typename PointSource, typename PointTarget>
00069 class RegistrationWrapper : public Registration<PointSource, PointTarget>
00070 {
00071 public:
00072 void computeTransformation (pcl::PointCloud<PointSource> &, const Eigen::Matrix4f&) { }
00073
00074 bool hasValidFeaturesTest ()
00075 {
00076 return (this->hasValidFeatures ());
00077 }
00078 void findFeatureCorrespondencesTest (int index, std::vector<int> &correspondence_indices)
00079 {
00080 this->findFeatureCorrespondences (index, correspondence_indices);
00081 }
00082 };
00083
00085 TEST (PCL, findFeatureCorrespondences)
00086 {
00087 typedef Histogram<2> FeatureT;
00088 typedef PointCloud<FeatureT> FeatureCloud;
00089
00090 RegistrationWrapper <PointXYZ, PointXYZ> reg;
00091
00092 FeatureCloud feature0, feature1, feature2, feature3;
00093 feature0.height = feature1.height = feature2.height = feature3.height = 1;
00094 feature0.is_dense = feature1.is_dense = feature2.is_dense = feature3.is_dense = true;
00095
00096 for (float x = -5.0f; x <= 5.0f; x += 0.2f)
00097 {
00098 for (float y = -5.0f; y <= 5.0f; y += 0.2f)
00099 {
00100 FeatureT f;
00101 f.histogram[0] = x;
00102 f.histogram[1] = y;
00103 feature0.points.push_back (f);
00104
00105 f.histogram[0] = x;
00106 f.histogram[1] = y - 2.5f;
00107 feature1.points.push_back (f);
00108
00109 f.histogram[0] = x - 2.0f;
00110 f.histogram[1] = y + 1.5f;
00111 feature2.points.push_back (f);
00112
00113 f.histogram[0] = x + 2.0f;
00114 f.histogram[1] = y + 1.5f;
00115 feature3.points.push_back (f);
00116 }
00117 }
00118 feature0.width = static_cast<uint32_t> (feature0.points.size ());
00119 feature1.width = static_cast<uint32_t> (feature1.points.size ());
00120 feature2.width = static_cast<uint32_t> (feature2.points.size ());
00121 feature3.width = static_cast<uint32_t> (feature3.points.size ());
00122
00123 KdTreeFLANN<FeatureT> tree;
00124
00125
00126
00127
00128
00129
00130
00131
00132
00133
00134
00135
00136
00137
00138
00139
00140
00141
00142
00143
00144
00145
00146
00147
00148
00149
00150
00151 }
00152
00154 TEST (PCL, IterativeClosestPoint)
00155 {
00156 IterativeClosestPoint<PointXYZ, PointXYZ> reg;
00157 PointCloud<PointXYZ>::ConstPtr source (cloud_source.makeShared ());
00158 #pragma GCC diagnostic push
00159 #pragma GCC diagnostic ignored "-Wdeprecated-declarations"
00160 reg.setInputCloud (source);
00161 source = reg.getInputCloud ();
00162 #pragma GCC diagnostic pop
00163 reg.setInputSource (source);
00164 reg.setInputTarget (cloud_target.makeShared ());
00165 reg.setMaximumIterations (50);
00166 reg.setTransformationEpsilon (1e-8);
00167 reg.setMaxCorrespondenceDistance (0.05);
00168
00169
00170 reg.align (cloud_reg);
00171 EXPECT_EQ (int (cloud_reg.points.size ()), int (cloud_source.points.size ()));
00172
00173
00174
00175
00176
00177
00178
00179
00180
00181
00182
00183
00184
00185
00186
00187
00188
00189
00190
00191
00192
00193 }
00194
00196 TEST (PCL, IterativeClosestPointNonLinear)
00197 {
00198 typedef PointXYZRGB PointT;
00199 PointCloud<PointT>::Ptr temp_src (new PointCloud<PointT>);
00200 copyPointCloud (cloud_source, *temp_src);
00201 PointCloud<PointT>::Ptr temp_tgt (new PointCloud<PointT>);
00202 copyPointCloud (cloud_target, *temp_tgt);
00203 PointCloud<PointT> output;
00204
00205 IterativeClosestPointNonLinear<PointT, PointT> reg;
00206 reg.setInputSource (temp_src);
00207 reg.setInputTarget (temp_tgt);
00208 reg.setMaximumIterations (50);
00209 reg.setTransformationEpsilon (1e-8);
00210
00211
00212 reg.align (output);
00213 EXPECT_EQ (int (output.points.size ()), int (cloud_source.points.size ()));
00214
00215
00216
00217
00218
00219
00220
00221
00222
00223
00224
00225
00226
00227
00228
00229
00230
00231
00232
00233
00234
00235
00236
00237
00238
00239
00240 EXPECT_LT (reg.getFitnessScore (), 0.001);
00241
00242
00243 for (int iter = 0; iter < 4; iter++)
00244 {
00245 bool force_cache = static_cast<bool> (iter / 2);
00246 bool force_cache_reciprocal = static_cast<bool> (iter % 2);
00247 pcl::search::KdTree<PointT>::Ptr tree(new pcl::search::KdTree<PointT>);
00248
00249 if (force_cache)
00250 tree->setInputCloud (temp_tgt);
00251 reg.setSearchMethodTarget (tree, force_cache);
00252
00253 pcl::search::KdTree<PointT>::Ptr tree_recip (new pcl::search::KdTree<PointT>);
00254 if (force_cache_reciprocal)
00255 tree_recip->setInputCloud (temp_src);
00256 reg.setSearchMethodSource (tree_recip, force_cache_reciprocal);
00257
00258
00259 reg.align (output);
00260 EXPECT_EQ (int (output.points.size ()), int (cloud_source.points.size ()));
00261 EXPECT_LT (reg.getFitnessScore (), 0.001);
00262 }
00263
00264 }
00265
00267 TEST (PCL, IterativeClosestPoint_PointToPlane)
00268 {
00269 typedef PointNormal PointT;
00270 PointCloud<PointT>::Ptr src (new PointCloud<PointT>);
00271 copyPointCloud (cloud_source, *src);
00272 PointCloud<PointT>::Ptr tgt (new PointCloud<PointT>);
00273 copyPointCloud (cloud_target, *tgt);
00274 PointCloud<PointT> output;
00275
00276 NormalEstimation<PointNormal, PointNormal> norm_est;
00277 norm_est.setSearchMethod (search::KdTree<PointNormal>::Ptr (new search::KdTree<PointNormal>));
00278 norm_est.setKSearch (10);
00279 norm_est.setInputCloud (tgt);
00280 norm_est.compute (*tgt);
00281
00282 IterativeClosestPoint<PointT, PointT> reg;
00283 typedef registration::TransformationEstimationPointToPlane<PointT, PointT> PointToPlane;
00284 boost::shared_ptr<PointToPlane> point_to_plane (new PointToPlane);
00285 reg.setTransformationEstimation (point_to_plane);
00286 reg.setInputSource (src);
00287 reg.setInputTarget (tgt);
00288 reg.setMaximumIterations (50);
00289 reg.setTransformationEpsilon (1e-8);
00290
00291
00292 reg.align (output);
00293 EXPECT_EQ (int (output.points.size ()), int (cloud_source.points.size ()));
00294 EXPECT_LT (reg.getFitnessScore (), 0.001);
00295
00296
00297 for (int iter = 0; iter < 4; iter++)
00298 {
00299 bool force_cache = (bool) iter/2;
00300 bool force_cache_reciprocal = (bool) iter%2;
00301 pcl::search::KdTree<PointT>::Ptr tree(new pcl::search::KdTree<PointT>);
00302
00303 if (force_cache)
00304 tree->setInputCloud (tgt);
00305 reg.setSearchMethodTarget (tree, force_cache);
00306
00307 pcl::search::KdTree<PointT>::Ptr tree_recip (new pcl::search::KdTree<PointT>);
00308 if (force_cache_reciprocal)
00309 tree_recip->setInputCloud (src);
00310 reg.setSearchMethodSource (tree_recip, force_cache_reciprocal);
00311
00312
00313 reg.align (output);
00314 EXPECT_EQ (int (output.points.size ()), int (cloud_source.points.size ()));
00315 EXPECT_LT (reg.getFitnessScore (), 0.001);
00316 }
00317
00318
00319
00320
00321
00322
00323
00324
00325
00326
00327
00328
00329
00330
00331
00332
00333
00334
00335
00336
00337
00338
00339
00340
00341
00342
00343
00344
00345
00346 }
00347
00349 TEST (PCL, GeneralizedIterativeClosestPoint)
00350 {
00351 typedef PointXYZ PointT;
00352 PointCloud<PointT>::Ptr src (new PointCloud<PointT>);
00353 copyPointCloud (cloud_source, *src);
00354 PointCloud<PointT>::Ptr tgt (new PointCloud<PointT>);
00355 copyPointCloud (cloud_target, *tgt);
00356 PointCloud<PointT> output;
00357
00358
00359 GeneralizedIterativeClosestPoint<PointT, PointT> reg;
00360 reg.setInputSource (src);
00361 reg.setInputTarget (tgt);
00362 reg.setMaximumIterations (50);
00363 reg.setTransformationEpsilon (1e-8);
00364
00365
00366 reg.align (output);
00367 EXPECT_EQ (int (output.points.size ()), int (cloud_source.points.size ()));
00368 EXPECT_LT (reg.getFitnessScore (), 0.001);
00369
00370
00371 for (int iter = 0; iter < 4; iter++)
00372 {
00373 bool force_cache = (bool) iter/2;
00374 bool force_cache_reciprocal = (bool) iter%2;
00375 pcl::search::KdTree<PointT>::Ptr tree(new pcl::search::KdTree<PointT>);
00376
00377 if (force_cache)
00378 tree->setInputCloud (tgt);
00379 reg.setSearchMethodTarget (tree, force_cache);
00380
00381 pcl::search::KdTree<PointT>::Ptr tree_recip (new pcl::search::KdTree<PointT>);
00382 if (force_cache_reciprocal)
00383 tree_recip->setInputCloud (src);
00384 reg.setSearchMethodSource (tree_recip, force_cache_reciprocal);
00385
00386
00387 reg.align (output);
00388 EXPECT_EQ (int (output.points.size ()), int (cloud_source.points.size ()));
00389 EXPECT_LT (reg.getFitnessScore (), 0.001);
00390 }
00391
00392 }
00393
00395 TEST (PCL, NormalDistributionsTransform)
00396 {
00397 typedef PointNormal PointT;
00398 PointCloud<PointT>::Ptr src (new PointCloud<PointT>);
00399 copyPointCloud (cloud_source, *src);
00400 PointCloud<PointT>::Ptr tgt (new PointCloud<PointT>);
00401 copyPointCloud (cloud_target, *tgt);
00402 PointCloud<PointT> output;
00403
00404 NormalDistributionsTransform<PointT, PointT> reg;
00405 reg.setStepSize (0.05);
00406 reg.setResolution (0.025f);
00407 reg.setInputSource (src);
00408 reg.setInputTarget (tgt);
00409 reg.setMaximumIterations (50);
00410 reg.setTransformationEpsilon (1e-8);
00411
00412 reg.align (output);
00413 EXPECT_EQ (int (output.points.size ()), int (cloud_source.points.size ()));
00414 EXPECT_LT (reg.getFitnessScore (), 0.001);
00415
00416
00417 for (int iter = 0; iter < 4; iter++)
00418 {
00419 bool force_cache = (bool) iter/2;
00420 bool force_cache_reciprocal = (bool) iter%2;
00421 pcl::search::KdTree<PointT>::Ptr tree(new pcl::search::KdTree<PointT>);
00422
00423 if (force_cache)
00424 tree->setInputCloud (tgt);
00425 reg.setSearchMethodTarget (tree, force_cache);
00426
00427 pcl::search::KdTree<PointT>::Ptr tree_recip (new pcl::search::KdTree<PointT>);
00428 if (force_cache_reciprocal)
00429 tree_recip->setInputCloud (src);
00430 reg.setSearchMethodSource (tree_recip, force_cache_reciprocal);
00431
00432
00433 reg.align (output);
00434 EXPECT_EQ (int (output.points.size ()), int (cloud_source.points.size ()));
00435 EXPECT_LT (reg.getFitnessScore (), 0.001);
00436 }
00437 }
00438
00439
00441 TEST (PCL, SampleConsensusInitialAlignment)
00442 {
00443
00444 Eigen::Vector3f initial_offset (100, 0, 0);
00445 float angle = static_cast<float> (M_PI) / 2.0f;
00446 Eigen::Quaternionf initial_rotation (cos (angle / 2), 0, 0, sin (angle / 2));
00447 PointCloud<PointXYZ> cloud_source_transformed;
00448 transformPointCloud (cloud_source, cloud_source_transformed, initial_offset, initial_rotation);
00449
00450
00451 PointCloud<PointXYZ>::Ptr cloud_source_ptr, cloud_target_ptr;
00452 cloud_source_ptr = cloud_source_transformed.makeShared ();
00453 cloud_target_ptr = cloud_target.makeShared ();
00454
00455
00456 search::KdTree<PointXYZ>::Ptr tree (new search::KdTree<PointXYZ>);
00457
00458 NormalEstimation<PointXYZ, Normal> norm_est;
00459 norm_est.setSearchMethod (tree);
00460 norm_est.setRadiusSearch (0.05);
00461 PointCloud<Normal> normals;
00462
00463 FPFHEstimation<PointXYZ, Normal, FPFHSignature33> fpfh_est;
00464 fpfh_est.setSearchMethod (tree);
00465 fpfh_est.setRadiusSearch (0.05);
00466 PointCloud<FPFHSignature33> features_source, features_target;
00467
00468
00469 norm_est.setInputCloud (cloud_source_ptr);
00470 norm_est.compute (normals);
00471 fpfh_est.setInputCloud (cloud_source_ptr);
00472 fpfh_est.setInputNormals (normals.makeShared ());
00473 fpfh_est.compute (features_source);
00474
00475
00476 norm_est.setInputCloud (cloud_target_ptr);
00477 norm_est.compute (normals);
00478 fpfh_est.setInputCloud (cloud_target_ptr);
00479 fpfh_est.setInputNormals (normals.makeShared ());
00480 fpfh_est.compute (features_target);
00481
00482
00483 SampleConsensusInitialAlignment<PointXYZ, PointXYZ, FPFHSignature33> reg;
00484 reg.setMinSampleDistance (0.05f);
00485 reg.setMaxCorrespondenceDistance (0.1);
00486 reg.setMaximumIterations (1000);
00487
00488 reg.setInputSource (cloud_source_ptr);
00489 reg.setInputTarget (cloud_target_ptr);
00490 reg.setSourceFeatures (features_source.makeShared ());
00491 reg.setTargetFeatures (features_target.makeShared ());
00492
00493
00494 reg.align (cloud_reg);
00495 EXPECT_EQ (int (cloud_reg.points.size ()), int (cloud_source.points.size ()));
00496 EXPECT_LT (reg.getFitnessScore (), 0.0005);
00497
00498
00499 typedef pcl::PointXYZ PointT;
00500 for (int iter = 0; iter < 4; iter++)
00501 {
00502 bool force_cache = (bool) iter/2;
00503 bool force_cache_reciprocal = (bool) iter%2;
00504 pcl::search::KdTree<PointT>::Ptr tree(new pcl::search::KdTree<PointT>);
00505
00506 if (force_cache)
00507 tree->setInputCloud (cloud_target_ptr);
00508 reg.setSearchMethodTarget (tree, force_cache);
00509
00510 pcl::search::KdTree<PointT>::Ptr tree_recip (new pcl::search::KdTree<PointT>);
00511 if (force_cache_reciprocal)
00512 tree_recip->setInputCloud (cloud_source_ptr);
00513 reg.setSearchMethodSource(tree_recip, force_cache_reciprocal);
00514
00515
00516 reg.align (cloud_reg);
00517 EXPECT_EQ (int (cloud_reg.points.size ()), int (cloud_source.points.size ()));
00518 EXPECT_LT (reg.getFitnessScore (), 0.0005);
00519 }
00520 }
00521
00522
00524 TEST (PCL, SampleConsensusPrerejective)
00525 {
00526
00527
00528
00529
00530
00531
00532
00533
00534 Eigen::Vector3f initial_offset (100, 0, 0);
00535 float angle = static_cast<float> (M_PI) / 2.0f;
00536 Eigen::Quaternionf initial_rotation (cos (angle / 2), 0, 0, sin (angle / 2));
00537 PointCloud<PointXYZ> cloud_source_transformed;
00538 transformPointCloud (cloud_source, cloud_source_transformed, initial_offset, initial_rotation);
00539
00540
00541 PointCloud<PointXYZ>::Ptr cloud_source_ptr, cloud_target_ptr;
00542 cloud_source_ptr = cloud_source_transformed.makeShared ();
00543 cloud_target_ptr = cloud_target.makeShared ();
00544
00545
00546 search::KdTree<PointXYZ>::Ptr tree (new search::KdTree<PointXYZ>);
00547
00548
00549 NormalEstimation<PointXYZ, Normal> norm_est;
00550 norm_est.setSearchMethod (tree);
00551 norm_est.setRadiusSearch (0.05);
00552 PointCloud<Normal> normals;
00553
00554
00555 FPFHEstimation<PointXYZ, Normal, FPFHSignature33> fpfh_est;
00556 fpfh_est.setSearchMethod (tree);
00557 fpfh_est.setRadiusSearch (0.05);
00558 PointCloud<FPFHSignature33> features_source, features_target;
00559
00560
00561 norm_est.setInputCloud (cloud_source_ptr);
00562 norm_est.compute (normals);
00563 fpfh_est.setInputCloud (cloud_source_ptr);
00564 fpfh_est.setInputNormals (normals.makeShared ());
00565 fpfh_est.compute (features_source);
00566
00567
00568 norm_est.setInputCloud (cloud_target_ptr);
00569 norm_est.compute (normals);
00570 fpfh_est.setInputCloud (cloud_target_ptr);
00571 fpfh_est.setInputNormals (normals.makeShared ());
00572 fpfh_est.compute (features_target);
00573
00574
00575 SampleConsensusPrerejective<PointXYZ, PointXYZ, FPFHSignature33> reg;
00576 reg.setMaxCorrespondenceDistance (0.1);
00577 reg.setMaximumIterations (5000);
00578 reg.setSimilarityThreshold (0.6f);
00579 reg.setCorrespondenceRandomness (2);
00580
00581
00582 reg.setInputSource (cloud_source_ptr);
00583 reg.setInputTarget (cloud_target_ptr);
00584 reg.setSourceFeatures (features_source.makeShared ());
00585 reg.setTargetFeatures (features_target.makeShared ());
00586
00587
00588 reg.align (cloud_reg);
00589
00590
00591 EXPECT_EQ (static_cast<int> (cloud_reg.points.size ()), static_cast<int> (cloud_source.points.size ()));
00592 float inlier_fraction = static_cast<float> (reg.getInliers ().size ()) / static_cast<float> (cloud_source.points.size ());
00593 EXPECT_GT (inlier_fraction, 0.95f);
00594
00595
00596 typedef pcl::PointXYZ PointT;
00597 for (int iter = 0; iter < 4; iter++)
00598 {
00599 bool force_cache = (bool) iter/2;
00600 bool force_cache_reciprocal = (bool) iter%2;
00601 pcl::search::KdTree<PointT>::Ptr tree(new pcl::search::KdTree<PointT>);
00602
00603 if (force_cache)
00604 tree->setInputCloud (cloud_target_ptr);
00605 reg.setSearchMethodTarget (tree, force_cache);
00606
00607 pcl::search::KdTree<PointT>::Ptr tree_recip (new pcl::search::KdTree<PointT>);
00608 if (force_cache_reciprocal)
00609 tree_recip->setInputCloud (cloud_source_ptr);
00610 reg.setSearchMethodSource(tree_recip, force_cache_reciprocal);
00611
00612
00613 reg.align (cloud_reg);
00614
00615
00616 EXPECT_EQ (int (cloud_reg.points.size ()), int (cloud_source.points.size ()));
00617 inlier_fraction = static_cast<float> (reg.getInliers ().size ()) / static_cast<float> (cloud_source.points.size ());
00618 EXPECT_GT (inlier_fraction, 0.95f);
00619 }
00620 }
00621
00622
00624 TEST (PCL, PyramidFeatureHistogram)
00625 {
00626
00627 PointCloud<PointXYZ>::Ptr cloud_source_ptr = cloud_source.makeShared (),
00628 cloud_target_ptr = cloud_target.makeShared ();
00629
00630 PointCloud<Normal>::Ptr cloud_source_normals (new PointCloud<Normal> ()),
00631 cloud_target_normals (new PointCloud<Normal> ());
00632 search::KdTree<PointXYZ>::Ptr tree (new search::KdTree<PointXYZ>);
00633 NormalEstimation<PointXYZ, Normal> normal_estimator;
00634 normal_estimator.setSearchMethod (tree);
00635 normal_estimator.setRadiusSearch (0.05);
00636 normal_estimator.setInputCloud (cloud_source_ptr);
00637 normal_estimator.compute (*cloud_source_normals);
00638
00639 normal_estimator.setInputCloud (cloud_target_ptr);
00640 normal_estimator.compute (*cloud_target_normals);
00641
00642
00643 PointCloud<PPFSignature>::Ptr ppf_signature_source (new PointCloud<PPFSignature> ()),
00644 ppf_signature_target (new PointCloud<PPFSignature> ());
00645 PPFEstimation<PointXYZ, Normal, PPFSignature> ppf_estimator;
00646 ppf_estimator.setInputCloud (cloud_source_ptr);
00647 ppf_estimator.setInputNormals (cloud_source_normals);
00648 ppf_estimator.compute (*ppf_signature_source);
00649
00650 ppf_estimator.setInputCloud (cloud_target_ptr);
00651 ppf_estimator.setInputNormals (cloud_target_normals);
00652 ppf_estimator.compute (*ppf_signature_target);
00653
00654
00655 vector<pair<float, float> > dim_range_input, dim_range_target;
00656 for (size_t i = 0; i < 3; ++i) dim_range_input.push_back (pair<float, float> (static_cast<float> (-M_PI), static_cast<float> (M_PI)));
00657 dim_range_input.push_back (pair<float, float> (0.0f, 1.0f));
00658 for (size_t i = 0; i < 3; ++i) dim_range_target.push_back (pair<float, float> (static_cast<float> (-M_PI) * 10.0f, static_cast<float> (M_PI) * 10.0f));
00659 dim_range_target.push_back (pair<float, float> (0.0f, 50.0f));
00660
00661
00662 PyramidFeatureHistogram<PPFSignature>::Ptr pyramid_source (new PyramidFeatureHistogram<PPFSignature> ()),
00663 pyramid_target (new PyramidFeatureHistogram<PPFSignature> ());
00664 pyramid_source->setInputCloud (ppf_signature_source);
00665 pyramid_source->setInputDimensionRange (dim_range_input);
00666 pyramid_source->setTargetDimensionRange (dim_range_target);
00667 pyramid_source->compute ();
00668
00669 pyramid_target->setInputCloud (ppf_signature_target);
00670 pyramid_target->setInputDimensionRange (dim_range_input);
00671 pyramid_target->setTargetDimensionRange (dim_range_target);
00672 pyramid_target->compute ();
00673
00674 float similarity_value = PyramidFeatureHistogram<PPFSignature>::comparePyramidFeatureHistograms (pyramid_source, pyramid_target);
00675 EXPECT_NEAR (similarity_value, 0.74101555347442627, 1e-4);
00676
00677 vector<pair<float, float> > dim_range_target2;
00678 for (size_t i = 0; i < 3; ++i) dim_range_target2.push_back (pair<float, float> (static_cast<float> (-M_PI) * 5.0f, static_cast<float> (M_PI) * 5.0f));
00679 dim_range_target2.push_back (pair<float, float> (0.0f, 20.0f));
00680
00681 pyramid_source->setTargetDimensionRange (dim_range_target2);
00682 pyramid_source->compute ();
00683
00684 pyramid_target->setTargetDimensionRange (dim_range_target2);
00685 pyramid_target->compute ();
00686
00687 float similarity_value2 = PyramidFeatureHistogram<PPFSignature>::comparePyramidFeatureHistograms (pyramid_source, pyramid_target);
00688 EXPECT_NEAR (similarity_value2, 0.80097091197967529, 1e-4);
00689
00690
00691 vector<pair<float, float> > dim_range_target3;
00692 for (size_t i = 0; i < 3; ++i) dim_range_target3.push_back (pair<float, float> (static_cast<float> (-M_PI) * 2.0f, static_cast<float> (M_PI) * 2.0f));
00693 dim_range_target3.push_back (pair<float, float> (0.0f, 10.0f));
00694
00695 pyramid_source->setTargetDimensionRange (dim_range_target3);
00696 pyramid_source->compute ();
00697
00698 pyramid_target->setTargetDimensionRange (dim_range_target3);
00699 pyramid_target->compute ();
00700
00701 float similarity_value3 = PyramidFeatureHistogram<PPFSignature>::comparePyramidFeatureHistograms (pyramid_source, pyramid_target);
00702 EXPECT_NEAR (similarity_value3, 0.87623238563537598, 1e-3);
00703 }
00704
00705
00706
00707 #if 0
00708
00709 TEST (PCL, PPFRegistration)
00710 {
00711
00712 Eigen::Vector3f initial_offset (100, 0, 0);
00713 float angle = M_PI/6;
00714 Eigen::Quaternionf initial_rotation (cos (angle / 2), 0, 0, sin (angle / 2));
00715 PointCloud<PointXYZ> cloud_source_transformed;
00716 transformPointCloud (cloud_source, cloud_source_transformed, initial_offset, initial_rotation);
00717
00718
00719
00720 PointCloud<PointXYZ>::Ptr cloud_source_ptr, cloud_target_ptr, cloud_source_transformed_ptr;
00721 cloud_source_transformed_ptr = cloud_source_transformed.makeShared ();
00722 cloud_target_ptr = cloud_target.makeShared ();
00723
00724
00725 NormalEstimation<PointXYZ, Normal> normal_estimation;
00726 search::KdTree<PointXYZ>::Ptr search_tree (new search::KdTree<PointXYZ> ());
00727 normal_estimation.setSearchMethod (search_tree);
00728 normal_estimation.setRadiusSearch (0.05);
00729 PointCloud<Normal>::Ptr normals_target (new PointCloud<Normal> ()),
00730 normals_source_transformed (new PointCloud<Normal> ());
00731 normal_estimation.setInputCloud (cloud_target_ptr);
00732 normal_estimation.compute (*normals_target);
00733 normal_estimation.setInputCloud (cloud_source_transformed_ptr);
00734 normal_estimation.compute (*normals_source_transformed);
00735
00736 PointCloud<PointNormal>::Ptr cloud_target_with_normals (new PointCloud<PointNormal> ()),
00737 cloud_source_transformed_with_normals (new PointCloud<PointNormal> ());
00738 concatenateFields (*cloud_target_ptr, *normals_target, *cloud_target_with_normals);
00739 concatenateFields (*cloud_source_transformed_ptr, *normals_source_transformed, *cloud_source_transformed_with_normals);
00740
00741
00742 PPFEstimation<PointXYZ, Normal, PPFSignature> ppf_estimator;
00743 PointCloud<PPFSignature>::Ptr features_source_transformed (new PointCloud<PPFSignature> ());
00744 ppf_estimator.setInputCloud (cloud_source_transformed_ptr);
00745 ppf_estimator.setInputNormals (normals_source_transformed);
00746 ppf_estimator.compute (*features_source_transformed);
00747
00748
00749
00750 PPFHashMapSearch::Ptr hash_map_search (new PPFHashMapSearch (15.0 / 180 * M_PI,
00751 0.05));
00752 hash_map_search->setInputFeatureCloud (features_source_transformed);
00753
00754
00755 PPFRegistration<PointNormal, PointNormal> ppf_registration;
00756 ppf_registration.setSceneReferencePointSamplingRate (20);
00757 ppf_registration.setPositionClusteringThreshold (0.15);
00758 ppf_registration.setRotationClusteringThreshold (45.0 / 180 * M_PI);
00759 ppf_registration.setSearchMethod (hash_map_search);
00760 ppf_registration.setInputCloud (cloud_source_transformed_with_normals);
00761 ppf_registration.setInputTarget (cloud_target_with_normals);
00762
00763 PointCloud<PointNormal> cloud_output;
00764 ppf_registration.align (cloud_output);
00765 Eigen::Matrix4f transformation = ppf_registration.getFinalTransformation ();
00766
00767 EXPECT_NEAR (transformation(0, 0), -0.153768, 1e-4);
00768 EXPECT_NEAR (transformation(0, 1), -0.628136, 1e-4);
00769 EXPECT_NEAR (transformation(0, 2), 0.762759, 1e-4);
00770 EXPECT_NEAR (transformation(0, 3), 15.472, 1e-4);
00771 EXPECT_NEAR (transformation(1, 0), 0.967397, 1e-4);
00772 EXPECT_NEAR (transformation(1, 1), -0.252918, 1e-4);
00773 EXPECT_NEAR (transformation(1, 2), -0.0132578, 1e-4);
00774 EXPECT_NEAR (transformation(1, 3), -96.6221, 1e-4);
00775 EXPECT_NEAR (transformation(2, 0), 0.201243, 1e-4);
00776 EXPECT_NEAR (transformation(2, 1), 0.735852, 1e-4);
00777 EXPECT_NEAR (transformation(2, 2), 0.646547, 1e-4);
00778 EXPECT_NEAR (transformation(2, 3), -20.134, 1e-4);
00779 EXPECT_NEAR (transformation(3, 0), 0.000000, 1e-4);
00780 EXPECT_NEAR (transformation(3, 1), 0.000000, 1e-4);
00781 EXPECT_NEAR (transformation(3, 2), 0.000000, 1e-4);
00782 EXPECT_NEAR (transformation(3, 3), 1.000000, 1e-4);
00783 }
00784 #endif
00785
00786
00787 int
00788 main (int argc, char** argv)
00789 {
00790 if (argc < 3)
00791 {
00792 std::cerr << "No test files given. Please download `bun0.pcd` and `bun4.pcd` and pass their path to the test." << std::endl;
00793 return (-1);
00794 }
00795
00796
00797 if (loadPCDFile (argv[1], cloud_source) < 0)
00798 {
00799 std::cerr << "Failed to read test file. Please download `bun0.pcd` and pass its path to the test." << std::endl;
00800 return (-1);
00801 }
00802 if (loadPCDFile (argv[2], cloud_target) < 0)
00803 {
00804 std::cerr << "Failed to read test file. Please download `bun4.pcd` and pass its path to the test." << std::endl;
00805 return (-1);
00806 }
00807
00808 testing::InitGoogleTest (&argc, argv);
00809 return (RUN_ALL_TESTS ());
00810
00811
00812
00813
00814
00815
00816 }
00817