test_registration.cpp
Go to the documentation of this file.
00001 /*
00002 * Software License Agreement (BSD License)
00003 *
00004 *  Point Cloud Library (PCL) - www.pointclouds.org
00005 *  Copyright (c) 2010-2011, Willow Garage, Inc.
00006 *
00007 *  All rights reserved.
00008 *
00009 *  Redistribution and use in source and binary forms, with or without
00010 *  modification, are permitted provided that the following conditions
00011 *  are met:
00012 *
00013 *   * Redistributions of source code must retain the above copyright
00014 *     notice, this list of conditions and the following disclaimer.
00015 *   * Redistributions in binary form must reproduce the above
00016 *     copyright notice, this list of conditions and the following
00017 *     disclaimer in the documentation and/or other materials provided
00018 *     with the distribution.
00019 *   * Neither the name of the copyright holder(s) nor the names of its
00020 *     contributors may be used to endorse or promote products derived
00021 *     from this software without specific prior written permission.
00022 *
00023 *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00024 *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00025 *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00026 *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00027 *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00028 *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00029 *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00030 *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00031 *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00032 *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00033 *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00034 *  POSSIBILITY OF SUCH DAMAGE.
00035 *
00036 * $Id$
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 // We need Histogram<2> to function, so we'll explicitely add kdtree_flann.hpp here
00059 #include <pcl/kdtree/impl/kdtree_flann.hpp>
00060 //(pcl::Histogram<2>)
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 /*  int k = 600;
00126 
00127   reg.setSourceFeature<FeatureT> (feature0.makeShared (), "feature1");
00128   reg.setTargetFeature<FeatureT> (feature1.makeShared (), "feature1");
00129   reg.setKSearch<FeatureT> (tree.makeShared (), k, "feature1");
00130 
00131   reg.setSourceFeature<FeatureT> (feature0.makeShared (), "feature2");
00132   reg.setTargetFeature<FeatureT> (feature2.makeShared (), "feature2");
00133   reg.setKSearch<FeatureT> (tree.makeShared (), k, "feature2");
00134 
00135   reg.setSourceFeature<FeatureT> (feature0.makeShared (), "feature3");
00136   reg.setTargetFeature<FeatureT> (feature3.makeShared (), "feature3");
00137   reg.setKSearch<FeatureT> (tree.makeShared (), k, "feature3");
00138 
00139   ASSERT_TRUE (reg.hasValidFeaturesTest ());
00140 
00141   std::vector<int> indices;
00142   reg.findFeatureCorrespondencesTest (1300, indices);
00143 
00144   ASSERT_EQ ((int)indices.size (), 10);
00145   const int correct_values[] = {1197, 1248, 1249, 1299, 1300, 1301, 1302, 1350, 1351, 1401};
00146   for (size_t i = 0; i < indices.size (); ++i)
00147   {
00148     EXPECT_EQ (indices[i], correct_values[i]);
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);     // test for PCL_DEPRECATED
00161   source = reg.getInputCloud ();  // test for PCL_DEPRECATED
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   // Register
00170   reg.align (cloud_reg);
00171   EXPECT_EQ (int (cloud_reg.points.size ()), int (cloud_source.points.size ()));
00172 
00173   //Eigen::Matrix4f transformation = reg.getFinalTransformation ();
00174 //  EXPECT_NEAR (transformation (0, 0), 0.8806,  1e-3);
00175 //  EXPECT_NEAR (transformation (0, 1), 0.036481287330389023, 1e-2);
00176 //  EXPECT_NEAR (transformation (0, 2), -0.4724, 1e-3);
00177 //  EXPECT_NEAR (transformation (0, 3), 0.03453, 1e-3);
00178 //
00179 //  EXPECT_NEAR (transformation (1, 0), -0.02354,  1e-3);
00180 //  EXPECT_NEAR (transformation (1, 1),  0.9992,   1e-3);
00181 //  EXPECT_NEAR (transformation (1, 2),  0.03326,  1e-3);
00182 //  EXPECT_NEAR (transformation (1, 3), -0.001519, 1e-3);
00183 //
00184 //  EXPECT_NEAR (transformation (2, 0),  0.4732,  1e-3);
00185 //  EXPECT_NEAR (transformation (2, 1), -0.01817, 1e-3);
00186 //  EXPECT_NEAR (transformation (2, 2),  0.8808,  1e-3);
00187 //  EXPECT_NEAR (transformation (2, 3),  0.04116, 1e-3);
00188 //
00189 //  EXPECT_EQ (transformation (3, 0), 0);
00190 //  EXPECT_EQ (transformation (3, 1), 0);
00191 //  EXPECT_EQ (transformation (3, 2), 0);
00192 //  EXPECT_EQ (transformation (3, 3), 1);
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   // Register
00212   reg.align (output);
00213   EXPECT_EQ (int (output.points.size ()), int (cloud_source.points.size ()));
00214   // We get different results on 32 vs 64-bit systems.  To address this, we've removed the explicit output test
00215   // on the transformation matrix.  Instead, we're testing to make sure the algorithm converges to a sufficiently
00216   // low error by checking the fitness score.
00217   /*
00218   Eigen::Matrix4f transformation = reg.getFinalTransformation ();
00219 
00220   EXPECT_NEAR (transformation (0, 0),  0.941755, 1e-2);
00221   EXPECT_NEAR (transformation (0, 1),  0.147362, 1e-2);
00222   EXPECT_NEAR (transformation (0, 2), -0.281285, 1e-2);
00223   EXPECT_NEAR (transformation (0, 3),  0.029813, 1e-2);
00224 
00225   EXPECT_NEAR (transformation (1, 0), -0.111655, 1e-2);
00226   EXPECT_NEAR (transformation (1, 1),  0.990408, 1e-2);
00227   EXPECT_NEAR (transformation (1, 2),  0.139090, 1e-2);
00228   EXPECT_NEAR (transformation (1, 3), -0.001864, 1e-2);
00229 
00230   EXPECT_NEAR (transformation (2, 0),  0.297271, 1e-2);
00231   EXPECT_NEAR (transformation (2, 1), -0.092015, 1e-2);
00232   EXPECT_NEAR (transformation (2, 2),  0.939670, 1e-2);
00233   EXPECT_NEAR (transformation (2, 3),  0.042721, 1e-2);
00234 
00235   EXPECT_EQ (transformation (3, 0), 0);
00236   EXPECT_EQ (transformation (3, 1), 0);
00237   EXPECT_EQ (transformation (3, 2), 0);
00238   EXPECT_EQ (transformation (3, 3), 1);
00239   */
00240   EXPECT_LT (reg.getFitnessScore (), 0.001);
00241  
00242   // Check again, for all possible caching schemes
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     // Ensure that, when force_cache is not set, we are robust to the wrong input
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     // Register
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   // Register
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   // Check again, for all possible caching schemes
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     // Ensure that, when force_cache is not set, we are robust to the wrong input
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     // Register
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   // We get different results on 32 vs 64-bit systems.  To address this, we've removed the explicit output test
00321   // on the transformation matrix.  Instead, we're testing to make sure the algorithm converges to a sufficiently
00322   // low error by checking the fitness score.
00323   /*
00324   Eigen::Matrix4f transformation = reg.getFinalTransformation ();
00325 
00326   EXPECT_NEAR (transformation (0, 0),  0.9046, 1e-2);
00327   EXPECT_NEAR (transformation (0, 1),  0.0609, 1e-2);
00328   EXPECT_NEAR (transformation (0, 2), -0.4219, 1e-2);
00329   EXPECT_NEAR (transformation (0, 3),  0.0327, 1e-2);
00330 
00331   EXPECT_NEAR (transformation (1, 0), -0.0328, 1e-2);
00332   EXPECT_NEAR (transformation (1, 1),  0.9968, 1e-2);
00333   EXPECT_NEAR (transformation (1, 2),  0.0851, 1e-2);
00334   EXPECT_NEAR (transformation (1, 3), -0.0003, 1e-2);
00335 
00336   EXPECT_NEAR (transformation (2, 0),  0.4250, 1e-2);
00337   EXPECT_NEAR (transformation (2, 1), -0.0641, 1e-2);
00338   EXPECT_NEAR (transformation (2, 2),  0.9037, 1e-2);
00339   EXPECT_NEAR (transformation (2, 3),  0.0413, 1e-2);
00340 
00341   EXPECT_EQ (transformation (3, 0), 0);
00342   EXPECT_EQ (transformation (3, 1), 0);
00343   EXPECT_EQ (transformation (3, 2), 0);
00344   EXPECT_EQ (transformation (3, 3), 1);
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   // Register
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   // Check again, for all possible caching schemes
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     // Ensure that, when force_cache is not set, we are robust to the wrong input
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     // Register
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   // Register
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   // Check again, for all possible caching schemes
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     // Ensure that, when force_cache is not set, we are robust to the wrong input
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     // Register
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   // Transform the source cloud by a large amount
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   // Create shared pointers
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   // Initialize estimators for surface normals and FPFH features
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   // Estimate the FPFH features for the source cloud
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   // Estimate the FPFH features for the target cloud
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   // Initialize Sample Consensus Initial Alignment (SAC-IA)
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   // Register
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   // Check again, for all possible caching schemes
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     // Ensure that, when force_cache is not set, we are robust to the wrong input
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     // Register
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    * This test is a near-exact copy of the SampleConsensusInitialAlignment test,
00528    * with the only modifications that:
00529    *   1) the number of iterations is increased 1000 --> 5000
00530    *   2) the feature correspondence randomness (the number of kNNs) is decreased 10 --> 2
00531    */
00532   
00533   // Transform the source cloud by a large amount
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   // Create shared pointers
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   // Initialize estimators for surface normals and FPFH features
00546   search::KdTree<PointXYZ>::Ptr tree (new search::KdTree<PointXYZ>);
00547 
00548   // Normal estimator
00549   NormalEstimation<PointXYZ, Normal> norm_est;
00550   norm_est.setSearchMethod (tree);
00551   norm_est.setRadiusSearch (0.05);
00552   PointCloud<Normal> normals;
00553 
00554   // FPFH estimator
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   // Estimate the normals and the FPFH features for the source cloud
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   // Estimate the normals and the FPFH features for the target cloud
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   // Initialize Sample Consensus Prerejective with 5x the number of iterations and 1/5 feature kNNs as SAC-IA 
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   // Set source and target cloud/features
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   // Register
00588   reg.align (cloud_reg);
00589   
00590   // Check output consistency and quality of alignment
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   // Check again, for all possible caching schemes
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     // Ensure that, when force_cache is not set, we are robust to the wrong input
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     // Register
00613     reg.align (cloud_reg);
00614 
00615     // Check output consistency and quality of alignment
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   // Create shared pointers
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 // Suat G: disabled, since the transformation does not look correct.
00706 // ToDo: update transformation from the ground truth.
00707 #if 0
00708 
00709 TEST (PCL, PPFRegistration)
00710 {
00711   // Transform the source cloud by a large amount
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   // Create shared pointers
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   // Estimate normals for both clouds
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   // Compute PPFSignature feature clouds for source cloud
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   // Train the source cloud - create the hash map search structure
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   // Finally, do the registration
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   // Input
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   // Tranpose the cloud_model
00812   /*for (size_t i = 0; i < cloud_model.points.size (); ++i)
00813   {
00814   //  cloud_model.points[i].z += 1;
00815   }*/
00816 }
00817 /* ]--- */


pcl
Author(s): Open Perception
autogenerated on Wed Aug 26 2015 15:35:46