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/normal_3d_omp.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, computePointNormal)
00058 {
00059   Eigen::Vector4f plane_parameters;
00060   float curvature;
00061 
00062   PointCloud<PointXYZ> c;
00063   
00064   PointXYZ p11 (706952.31f, 4087.6958f, 0.00000000f),
00065            p21 (707002.31f, 6037.6958f, 0.00000000f),
00066            p31 (706952.31f, 7937.6958f, 0.00000000f);
00067   c.push_back (p11); c.push_back (p21); c.push_back (p31);
00068 
00069   computePointNormal (cloud, plane_parameters, curvature);
00070 
00071   
00072   c.clear ();
00073   PointXYZ p12 (-439747.72f, -43597.250f, 0.0000000f),
00074            p22 (-439847.72f, -41697.250f, 0.0000000f),
00075            p32 (-439747.72f, -39797.250f, 0.0000000f);
00076 
00077   c.push_back (p12); c.push_back (p22); c.push_back (p32);
00078 
00079   computePointNormal (cloud, plane_parameters, curvature);
00080 
00081 
00082   c.clear ();
00083   PointXYZ p13 (567011.56f, -7741.8179f, 0.00000000f),
00084            p23 (567361.56f, -5841.8179f, 0.00000000f),
00085            p33 (567011.56f, -3941.8179f, 0.00000000f);
00086 
00087   c.push_back (p13); c.push_back (p23); c.push_back (p33);
00088 
00089   computePointNormal (cloud, plane_parameters, curvature);
00090 
00091 }
00092 
00094 TEST (PCL, NormalEstimation)
00095 {
00096   Eigen::Vector4f plane_parameters;
00097   float curvature;
00098 
00099   NormalEstimation<PointXYZ, Normal> n;
00100 
00101   
00102   computePointNormal (cloud, indices, plane_parameters, curvature);
00103   EXPECT_NEAR (fabs (plane_parameters[0]), 0.035592, 1e-4);
00104   EXPECT_NEAR (fabs (plane_parameters[1]), 0.369596, 1e-4);
00105   EXPECT_NEAR (fabs (plane_parameters[2]), 0.928511, 1e-4);
00106   EXPECT_NEAR (fabs (plane_parameters[3]), 0.0622552, 1e-4);
00107   EXPECT_NEAR (curvature, 0.0693136, 1e-4);
00108 
00109   float nx, ny, nz;
00110   
00111   n.computePointNormal (cloud, indices, nx, ny, nz, curvature);
00112   EXPECT_NEAR (fabs (nx), 0.035592, 1e-4);
00113   EXPECT_NEAR (fabs (ny), 0.369596, 1e-4);
00114   EXPECT_NEAR (fabs (nz), 0.928511, 1e-4);
00115   EXPECT_NEAR (curvature, 0.0693136, 1e-4);
00116 
00117   
00118   computePointNormal (cloud, plane_parameters, curvature);
00119   EXPECT_NEAR (plane_parameters[0],  0.035592,  1e-4);
00120   EXPECT_NEAR (plane_parameters[1],  0.369596,  1e-4);
00121   EXPECT_NEAR (plane_parameters[2],  0.928511,  1e-4);
00122   EXPECT_NEAR (plane_parameters[3], -0.0622552, 1e-4);
00123   EXPECT_NEAR (curvature,            0.0693136, 1e-4);
00124 
00125   
00126   flipNormalTowardsViewpoint (cloud.points[0], 0, 0, 0, plane_parameters);
00127   EXPECT_NEAR (plane_parameters[0], -0.035592,  1e-4);
00128   EXPECT_NEAR (plane_parameters[1], -0.369596,  1e-4);
00129   EXPECT_NEAR (plane_parameters[2], -0.928511,  1e-4);
00130   EXPECT_NEAR (plane_parameters[3],  0.0799743, 1e-4);
00131 
00132   
00133   flipNormalTowardsViewpoint (cloud.points[0], 0, 0, 0, nx, ny, nz);
00134   EXPECT_NEAR (nx, -0.035592, 1e-4);
00135   EXPECT_NEAR (ny, -0.369596, 1e-4);
00136   EXPECT_NEAR (nz, -0.928511, 1e-4);
00137 
00138   
00139   PointCloud<Normal>::Ptr normals (new PointCloud<Normal> ());
00140 
00141   
00142   PointCloud<PointXYZ>::Ptr cloudptr = cloud.makeShared ();
00143   n.setInputCloud (cloudptr);
00144   EXPECT_EQ (n.getInputCloud (), cloudptr);
00145   boost::shared_ptr<vector<int> > indicesptr (new vector<int> (indices));
00146   n.setIndices (indicesptr);
00147   EXPECT_EQ (n.getIndices (), indicesptr);
00148   n.setSearchMethod (tree);
00149   EXPECT_EQ (n.getSearchMethod (), tree);
00150   n.setKSearch (static_cast<int> (indices.size ()));
00151 
00152   
00153   n.compute (*normals);
00154   EXPECT_EQ (normals->points.size (), indices.size ());
00155 
00156   for (size_t i = 0; i < normals->points.size (); ++i)
00157   {
00158     EXPECT_NEAR (normals->points[i].normal[0], -0.035592, 1e-4);
00159     EXPECT_NEAR (normals->points[i].normal[1], -0.369596, 1e-4);
00160     EXPECT_NEAR (normals->points[i].normal[2], -0.928511, 1e-4);
00161     EXPECT_NEAR (normals->points[i].curvature, 0.0693136, 1e-4);
00162   }
00163 
00164   PointCloud<PointXYZ>::Ptr surfaceptr = cloudptr;
00165   n.setSearchSurface (surfaceptr);
00166   EXPECT_EQ (n.getSearchSurface (), surfaceptr);
00167 
00168   
00169   surfaceptr.reset (new PointCloud<PointXYZ>);
00170   *surfaceptr = *cloudptr;
00171   surfaceptr->points.resize (640 * 480);
00172   surfaceptr->width = 640;
00173   surfaceptr->height = 480;
00174   EXPECT_EQ (surfaceptr->points.size (), surfaceptr->width * surfaceptr->height);
00175   n.setSearchSurface (surfaceptr);
00176   tree.reset ();
00177   n.setSearchMethod (tree);
00178 
00179   
00180   n.compute (*normals);
00181   EXPECT_EQ (normals->points.size (), indices.size ());
00182 }
00183 
00185 TEST (PCL, NormalEstimationOpenMP)
00186 {
00187   NormalEstimationOMP<PointXYZ, Normal> n (4); 
00188 
00189   
00190   PointCloud<Normal>::Ptr normals (new PointCloud<Normal> ());
00191 
00192   
00193   PointCloud<PointXYZ>::Ptr cloudptr = cloud.makeShared ();
00194   n.setInputCloud (cloudptr);
00195   EXPECT_EQ (n.getInputCloud (), cloudptr);
00196   boost::shared_ptr<vector<int> > indicesptr (new vector<int> (indices));
00197   n.setIndices (indicesptr);
00198   EXPECT_EQ (n.getIndices (), indicesptr);
00199   n.setSearchMethod (tree);
00200   EXPECT_EQ (n.getSearchMethod (), tree);
00201   n.setKSearch (static_cast<int> (indices.size ()));
00202 
00203   
00204   n.compute (*normals);
00205   EXPECT_EQ (normals->points.size (), indices.size ());
00206 
00207   for (size_t i = 0; i < normals->points.size (); ++i)
00208   {
00209     EXPECT_NEAR (normals->points[i].normal[0], -0.035592, 1e-4);
00210     EXPECT_NEAR (normals->points[i].normal[1], -0.369596, 1e-4);
00211     EXPECT_NEAR (normals->points[i].normal[2], -0.928511, 1e-4);
00212     EXPECT_NEAR (normals->points[i].curvature, 0.0693136, 1e-4);
00213   }
00214 }
00215 
00216 
00217 int
00218 main (int argc, char** argv)
00219 {
00220   if (argc < 2)
00221   {
00222     std::cerr << "No test file given. Please download `bun0.pcd` and pass its path to the test." << std::endl;
00223     return (-1);
00224   }
00225 
00226   if (loadPCDFile<PointXYZ> (argv[1], cloud) < 0)
00227   {
00228     std::cerr << "Failed to read test file. Please download `bun0.pcd` and pass its path to the test." << std::endl;
00229     return (-1);
00230   }
00231 
00232   indices.resize (cloud.points.size ());
00233   for (int i = 0; i < static_cast<int> (indices.size ()); ++i)
00234     indices[i] = i;
00235 
00236   tree.reset (new search::KdTree<PointXYZ> (false));
00237   tree->setInputCloud (cloud.makeShared ());
00238 
00239   testing::InitGoogleTest (&argc, argv);
00240   return (RUN_ALL_TESTS ());
00241 }
00242