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/boundary.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, BoundaryEstimation)
00058 {
00059   Eigen::Vector4f u = Eigen::Vector4f::Zero ();
00060   Eigen::Vector4f v = Eigen::Vector4f::Zero ();
00061 
00062   
00063   NormalEstimation<PointXYZ, Normal> n;
00064   PointCloud<Normal>::Ptr normals (new PointCloud<Normal> ());
00065   
00066   n.setInputCloud (cloud.makeShared ());
00067   boost::shared_ptr<vector<int> > indicesptr (new vector<int> (indices));
00068   n.setIndices (indicesptr);
00069   n.setSearchMethod (tree);
00070   n.setKSearch (static_cast<int> (indices.size ()));
00071   
00072   n.compute (*normals);
00073 
00074   BoundaryEstimation<PointXYZ, Normal, Boundary> b;
00075   b.setInputNormals (normals);
00076   EXPECT_EQ (b.getInputNormals (), normals);
00077 
00078   
00079   for (size_t i = 0; i < normals->points.size (); ++i)
00080   {
00081     b.getCoordinateSystemOnPlane (normals->points[i], u, v);
00082     Vector4fMap n4uv = normals->points[i].getNormalVector4fMap ();
00083     EXPECT_NEAR (n4uv.dot(u), 0, 1e-4);
00084     EXPECT_NEAR (n4uv.dot(v), 0, 1e-4);
00085     EXPECT_NEAR (u.dot(v), 0, 1e-4);
00086   }
00087 
00088   
00089   bool pt = false;
00090   pt = b.isBoundaryPoint (cloud, 0, indices, u, v, float (M_PI) / 2.0);
00091   EXPECT_EQ (pt, false);
00092   pt = b.isBoundaryPoint (cloud, static_cast<int> (indices.size ()) / 3, indices, u, v, float (M_PI) / 2.0);
00093   EXPECT_EQ (pt, false);
00094   pt = b.isBoundaryPoint (cloud, static_cast<int> (indices.size ()) / 2, indices, u, v, float (M_PI) / 2.0);
00095   EXPECT_EQ (pt, false);
00096   pt = b.isBoundaryPoint (cloud, static_cast<int> (indices.size ()) - 1, indices, u, v, float (M_PI) / 2.0);
00097   EXPECT_EQ (pt, true);
00098 
00099   
00100   pt = false;
00101   pt = b.isBoundaryPoint (cloud, cloud.points[0], indices, u, v, float (M_PI) / 2.0);
00102   EXPECT_EQ (pt, false);
00103   pt = b.isBoundaryPoint (cloud, cloud.points[indices.size () / 3], indices, u, v, float (M_PI) / 2.0);
00104   EXPECT_EQ (pt, false);
00105   pt = b.isBoundaryPoint (cloud, cloud.points[indices.size () / 2], indices, u, v, float (M_PI) / 2.0);
00106   EXPECT_EQ (pt, false);
00107   pt = b.isBoundaryPoint (cloud, cloud.points[indices.size () - 1], indices, u, v, float (M_PI) / 2.0);
00108   EXPECT_EQ (pt, true);
00109 
00110   
00111   PointCloud<Boundary>::Ptr bps (new PointCloud<Boundary> ());
00112 
00113   
00114   b.setInputCloud (cloud.makeShared ());
00115   b.setIndices (indicesptr);
00116   b.setSearchMethod (tree);
00117   b.setKSearch (static_cast<int> (indices.size ()));
00118 
00119   
00120   b.compute (*bps);
00121   EXPECT_EQ (bps->points.size (), indices.size ());
00122 
00123   pt = bps->points[0].boundary_point;
00124   EXPECT_EQ (pt, false);
00125   pt = bps->points[indices.size () / 3].boundary_point;
00126   EXPECT_EQ (pt, false);
00127   pt = bps->points[indices.size () / 2].boundary_point;
00128   EXPECT_EQ (pt, false);
00129   pt = bps->points[indices.size () - 1].boundary_point;
00130   EXPECT_EQ (pt, true);
00131 }
00132 
00133 
00134 int
00135 main (int argc, char** argv)
00136 {
00137   if (argc < 2)
00138   {
00139     std::cerr << "No test file given. Please download `bun0.pcd` and pass its path to the test." << std::endl;
00140     return (-1);
00141   }
00142 
00143   if (loadPCDFile<PointXYZ> (argv[1], cloud) < 0)
00144   {
00145     std::cerr << "Failed to read test file. Please download `bun0.pcd` and pass its path to the test." << std::endl;
00146     return (-1);
00147   }
00148 
00149   indices.resize (cloud.points.size ());
00150   for (size_t i = 0; i < indices.size (); ++i)
00151     indices[i] = static_cast<int> (i);
00152 
00153   tree.reset (new search::KdTree<PointXYZ> (false));
00154   tree->setInputCloud (cloud.makeShared ());
00155 
00156   testing::InitGoogleTest (&argc, argv);
00157   return (RUN_ALL_TESTS ());
00158 }
00159