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/ear_clipping.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, EarClipping)
00066 {
00067   PointCloud<PointXYZ>::Ptr cloud (new PointCloud<PointXYZ>());
00068   cloud->height = 1;
00069   cloud->points.push_back (PointXYZ ( 0.f, 0.f, 0.5f));
00070   cloud->points.push_back (PointXYZ ( 5.f, 0.f, 0.6f));
00071   cloud->points.push_back (PointXYZ ( 9.f, 4.f, 0.5f));
00072   cloud->points.push_back (PointXYZ ( 4.f, 7.f, 0.5f));
00073   cloud->points.push_back (PointXYZ ( 2.f, 5.f, 0.5f));
00074   cloud->points.push_back (PointXYZ (-1.f, 8.f, 0.5f));
00075   cloud->width = static_cast<uint32_t> (cloud->points.size ());
00076 
00077   Vertices vertices;
00078   vertices.vertices.resize (cloud->points.size ());
00079   for (int i = 0; i < static_cast<int> (vertices.vertices.size ()); ++i)
00080     vertices.vertices[i] = i;
00081 
00082   PolygonMesh::Ptr mesh (new PolygonMesh);
00083   toPCLPointCloud2 (*cloud, mesh->cloud);
00084   mesh->polygons.push_back (vertices);
00085 
00086   EarClipping clipper;
00087   PolygonMesh::ConstPtr mesh_aux (mesh);
00088   clipper.setInputMesh (mesh_aux);
00089 
00090   PolygonMesh triangulated_mesh;
00091   clipper.process (triangulated_mesh);
00092 
00093   EXPECT_EQ (triangulated_mesh.polygons.size (), 4);
00094   for (int i = 0; i < static_cast<int> (triangulated_mesh.polygons.size ()); ++i)
00095     EXPECT_EQ (triangulated_mesh.polygons[i].vertices.size (), 3);
00096 
00097   const int truth[][3] = { {5, 0, 1},
00098                            {2, 3, 4},
00099                            {4, 5, 1},
00100                            {1, 2, 4} };
00101 
00102   for (int pi = 0; pi < static_cast<int> (triangulated_mesh.polygons.size ()); ++pi)
00103   for (int vi = 0; vi < 3; ++vi)
00104   {
00105     EXPECT_EQ (triangulated_mesh.polygons[pi].vertices[vi], truth[pi][vi]);
00106   }
00107 }
00108 
00109 
00110 int
00111 main (int argc, char** argv)
00112 {
00113   if (argc < 2)
00114   {
00115     std::cerr << "No test file given. Please download `bun0.pcd` and pass its path to the test." << std::endl;
00116     return (-1);
00117   }
00118 
00119   
00120   pcl::PCLPointCloud2 cloud_blob;
00121   loadPCDFile (argv[1], cloud_blob);
00122   fromPCLPointCloud2 (cloud_blob, *cloud);
00123 
00124   
00125   tree.reset (new search::KdTree<PointXYZ> (false));
00126   tree->setInputCloud (cloud);
00127 
00128   
00129   NormalEstimation<PointXYZ, Normal> n;
00130   PointCloud<Normal>::Ptr normals (new PointCloud<Normal> ());
00131   n.setInputCloud (cloud);
00132   
00133   n.setSearchMethod (tree);
00134   n.setKSearch (20);
00135   n.compute (*normals);
00136 
00137   
00138   pcl::concatenateFields (*cloud, *normals, *cloud_with_normals);
00139       
00140   
00141   tree2.reset (new search::KdTree<PointNormal>);
00142   tree2->setInputCloud (cloud_with_normals);
00143 
00144   
00145   if(argc == 3){
00146     pcl::PCLPointCloud2 cloud_blob1;
00147     loadPCDFile (argv[2], cloud_blob1);
00148     fromPCLPointCloud2 (cloud_blob1, *cloud1);
00149         
00150     tree3.reset (new search::KdTree<PointXYZ> (false));
00151     tree3->setInputCloud (cloud1);
00152 
00153     
00154     NormalEstimation<PointXYZ, Normal> n1;
00155     PointCloud<Normal>::Ptr normals1 (new PointCloud<Normal> ());
00156     n1.setInputCloud (cloud1);
00157 
00158     n1.setSearchMethod (tree3);
00159     n1.setKSearch (20);
00160     n1.compute (*normals1);
00161 
00162     
00163     pcl::concatenateFields (*cloud1, *normals1, *cloud_with_normals1);
00164     
00165     tree4.reset (new search::KdTree<PointNormal>);
00166     tree4->setInputCloud (cloud_with_normals1);
00167   }
00168 
00169   
00170   testing::InitGoogleTest (&argc, argv);
00171   return (RUN_ALL_TESTS ());
00172 }
00173