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 
00042 #include <pcl/point_types.h>
00043 #include <pcl/io/pcd_io.h>
00044 #include <pcl/io/vtk_io.h>
00045 #include <pcl/features/normal_3d.h>
00046 #include <pcl/surface/poisson.h>
00047 #include <pcl/common/common.h>
00048 
00049 using namespace pcl;
00050 using namespace pcl::io;
00051 using namespace std;
00052 
00053 PointCloud<PointXYZ>::Ptr cloud (new PointCloud<PointXYZ>);
00054 PointCloud<PointNormal>::Ptr cloud_with_normals (new PointCloud<PointNormal>);
00055 search::KdTree<PointXYZ>::Ptr tree;
00056 search::KdTree<PointNormal>::Ptr tree2;
00057 
00058 
00059 PointCloud<PointXYZ>::Ptr cloud1 (new PointCloud<PointXYZ>);
00060 PointCloud<PointNormal>::Ptr cloud_with_normals1 (new PointCloud<PointNormal>);
00061 search::KdTree<PointXYZ>::Ptr tree3;
00062 search::KdTree<PointNormal>::Ptr tree4;
00063 
00065 TEST (PCL, Poisson)
00066 {
00067   Poisson<PointNormal> poisson;
00068   poisson.setInputCloud (cloud_with_normals);
00069   PolygonMesh mesh;
00070   poisson.reconstruct (mesh);
00071 
00072 
00073 
00074 
00075   ASSERT_EQ (mesh.polygons.size (), 1051);
00076   
00077   for (size_t i = 0; i < mesh.polygons.size (); ++i)
00078     EXPECT_EQ (mesh.polygons[i].vertices.size (), 3);
00079 
00080   EXPECT_EQ (mesh.polygons[10].vertices[0], 121);
00081   EXPECT_EQ (mesh.polygons[10].vertices[1], 120);
00082   EXPECT_EQ (mesh.polygons[10].vertices[2], 23);
00083 
00084   EXPECT_EQ (mesh.polygons[200].vertices[0], 130);
00085   EXPECT_EQ (mesh.polygons[200].vertices[1], 119);
00086   EXPECT_EQ (mesh.polygons[200].vertices[2], 131);
00087 
00088   EXPECT_EQ (mesh.polygons[1000].vertices[0], 521);
00089   EXPECT_EQ (mesh.polygons[1000].vertices[1], 516);
00090   EXPECT_EQ (mesh.polygons[1000].vertices[2], 517);
00091 }
00092 
00093 
00094 int
00095 main (int argc, char** argv)
00096 {
00097   if (argc < 2)
00098   {
00099     std::cerr << "No test file given. Please download `bun0.pcd` and pass its path to the test." << std::endl;
00100     return (-1);
00101   }
00102 
00103   
00104   pcl::PCLPointCloud2 cloud_blob;
00105   loadPCDFile (argv[1], cloud_blob);
00106   fromPCLPointCloud2 (cloud_blob, *cloud);
00107 
00108   
00109   tree.reset (new search::KdTree<PointXYZ> (false));
00110   tree->setInputCloud (cloud);
00111 
00112   
00113   NormalEstimation<PointXYZ, Normal> n;
00114   PointCloud<Normal>::Ptr normals (new PointCloud<Normal> ());
00115   n.setInputCloud (cloud);
00116   
00117   n.setSearchMethod (tree);
00118   n.setKSearch (20);
00119   n.compute (*normals);
00120 
00121   
00122   pcl::concatenateFields (*cloud, *normals, *cloud_with_normals);
00123       
00124   
00125   tree2.reset (new search::KdTree<PointNormal>);
00126   tree2->setInputCloud (cloud_with_normals);
00127 
00128   
00129   if(argc == 3){
00130     pcl::PCLPointCloud2 cloud_blob1;
00131     loadPCDFile (argv[2], cloud_blob1);
00132     fromPCLPointCloud2 (cloud_blob1, *cloud1);
00133         
00134     tree3.reset (new search::KdTree<PointXYZ> (false));
00135     tree3->setInputCloud (cloud1);
00136 
00137     
00138     NormalEstimation<PointXYZ, Normal> n1;
00139     PointCloud<Normal>::Ptr normals1 (new PointCloud<Normal> ());
00140     n1.setInputCloud (cloud1);
00141 
00142     n1.setSearchMethod (tree3);
00143     n1.setKSearch (20);
00144     n1.compute (*normals1);
00145 
00146     
00147     pcl::concatenateFields (*cloud1, *normals1, *cloud_with_normals1);
00148     
00149     tree4.reset (new search::KdTree<PointNormal>);
00150     tree4->setInputCloud (cloud_with_normals1);
00151   }
00152 
00153   
00154   testing::InitGoogleTest (&argc, argv);
00155   return (RUN_ALL_TESTS ());
00156 }
00157