Go to the documentation of this file.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 #include <pcl/point_cloud.h>
00042 #include <pcl/features/normal_3d.h>
00043 #include <pcl/features/ppf.h>
00044 #include <pcl/io/pcd_io.h>
00045 
00046 using namespace pcl;
00047 using namespace pcl::io;
00048 using namespace std;
00049 
00050 typedef search::KdTree<PointXYZ>::Ptr KdTreePtr;
00051 
00052 PointCloud<PointXYZ> cloud;
00053 vector<int> indices;
00054 KdTreePtr tree;
00055 
00057 TEST (PCL, PPFEstimation)
00058 {
00059   
00060   NormalEstimation<PointXYZ, Normal> normal_estimation;
00061   PointCloud<Normal>::Ptr normals (new PointCloud<Normal> ());
00062   normal_estimation.setInputCloud (cloud.makeShared ());
00063   boost::shared_ptr<vector<int> > indicesptr (new vector<int> (indices));
00064   normal_estimation.setIndices (indicesptr);
00065   normal_estimation.setSearchMethod (tree);
00066   normal_estimation.setKSearch (10); 
00067   normal_estimation.compute (*normals);
00068 
00069   PPFEstimation <PointXYZ, Normal, PPFSignature> ppf_estimation;
00070   ppf_estimation.setInputCloud (cloud.makeShared ());
00071   ppf_estimation.setInputNormals (normals);
00072   PointCloud<PPFSignature>::Ptr feature_cloud (new PointCloud<PPFSignature> ());
00073   ppf_estimation.compute (*feature_cloud);
00074 
00075   
00076   EXPECT_EQ (feature_cloud->points.size (), indices.size () * cloud.points.size ());
00077 
00078   
00079   EXPECT_TRUE (pcl_isnan (feature_cloud->points[0].f1));
00080   EXPECT_TRUE (pcl_isnan (feature_cloud->points[0].f2));
00081   EXPECT_TRUE (pcl_isnan (feature_cloud->points[0].f3));
00082   EXPECT_TRUE (pcl_isnan (feature_cloud->points[0].f4));
00083   EXPECT_TRUE (pcl_isnan (feature_cloud->points[0].alpha_m));
00084 
00085   EXPECT_NEAR (feature_cloud->points[15127].f1, -2.51637, 1e-4);
00086   EXPECT_NEAR (feature_cloud->points[15127].f2, -0.00365916, 1e-4);
00087   EXPECT_NEAR (feature_cloud->points[15127].f3, -0.521141, 1e-4);
00088   EXPECT_NEAR (feature_cloud->points[15127].f4, 0.0106809, 1e-4);
00089   EXPECT_NEAR (feature_cloud->points[15127].alpha_m, -0.255664, 1e-4);
00090   EXPECT_NEAR (feature_cloud->points[30254].f1, 0.185142, 1e-4);
00091   EXPECT_NEAR (feature_cloud->points[30254].f2, 0.0425001, 1e-4);
00092   EXPECT_NEAR (feature_cloud->points[30254].f3, -0.191276, 1e-4);
00093   EXPECT_NEAR (feature_cloud->points[30254].f4, 0.0138508, 1e-4);
00094   EXPECT_NEAR (feature_cloud->points[30254].alpha_m, 2.42955, 1e-4);
00095   EXPECT_NEAR (feature_cloud->points[45381].f1, -1.96263, 1e-4);
00096   EXPECT_NEAR (feature_cloud->points[45381].f2, -0.431919, 1e-4);
00097   EXPECT_NEAR (feature_cloud->points[45381].f3, 0.868716, 1e-4);
00098   EXPECT_NEAR (feature_cloud->points[45381].f4, 0.140129, 1e-4);
00099   EXPECT_NEAR (feature_cloud->points[45381].alpha_m, -1.97276, 1e-4);
00100 }
00101 
00102 
00103 int
00104 main (int argc, char** argv)
00105 {
00106   if (argc < 2)
00107   {
00108     std::cerr << "No test file given. Please download `bun0.pcd` and pass its path to the test." << std::endl;
00109     return (-1);
00110   }
00111 
00112   if (loadPCDFile<PointXYZ> (argv[1], cloud) < 0)
00113   {
00114     std::cerr << "Failed to read test file. Please download `bun0.pcd` and pass its path to the test." << std::endl;
00115     return (-1);
00116   }
00117 
00118   indices.resize (cloud.points.size ());
00119   for (int i = 0; i < static_cast<int> (indices.size ()); ++i)
00120     indices[i] = i;
00121 
00122   tree.reset (new search::KdTree<PointXYZ> (false));
00123   tree->setInputCloud (cloud.makeShared ());
00124 
00125   testing::InitGoogleTest (&argc, argv);
00126   return (RUN_ALL_TESTS ());
00127 }
00128