test_surface.cpp
Go to the documentation of this file.
00001 /*
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Point Cloud Library (PCL) - www.pointclouds.org
00005  *  Copyright (c) 2009-2012, Willow Garage, Inc.
00006  *
00007  *  All rights reserved.
00008  *
00009  *  Redistribution and use in source and binary forms, with or without
00010  *  modification, are permitted provided that the following conditions
00011  *  are met:
00012  *
00013  *   * Redistributions of source code must retain the above copyright
00014  *     notice, this list of conditions and the following disclaimer.
00015  *   * Redistributions in binary form must reproduce the above
00016  *     copyright notice, this list of conditions and the following
00017  *     disclaimer in the documentation and/or other materials provided
00018  *     with the distribution.
00019  *   * Neither the name of Willow Garage, Inc. nor the names of its
00020  *     contributors may be used to endorse or promote products derived
00021  *     from this software without specific prior written permission.
00022  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00023  *
00024  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00025  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00026  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00027  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00028  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00029  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00030  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00031  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00032  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00033  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00034  *  POSSIBILITY OF SUCH DAMAGE.
00035  *
00036  * $Id: test_surface.cpp 6437 2012-07-17 07:00:19Z aichim $
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/mls.h>
00047 #include <pcl/surface/mls_omp.h>
00048 #include <pcl/surface/gp3.h>
00049 #include <pcl/surface/grid_projection.h>
00050 #include <pcl/surface/convex_hull.h>
00051 #include <pcl/surface/concave_hull.h>
00052 #include <pcl/surface/organized_fast_mesh.h>
00053 #include <pcl/surface/ear_clipping.h>
00054 #include <pcl/surface/poisson.h>
00055 #include <pcl/surface/marching_cubes_hoppe.h>
00056 #include <pcl/surface/marching_cubes_rbf.h>
00057 #include <pcl/common/common.h>
00058 #include <boost/random.hpp>
00059 
00060 #include <pcl/io/obj_io.h>
00061 #include <pcl/TextureMesh.h>
00062 #include <pcl/surface/texture_mapping.h>
00063 using namespace pcl;
00064 using namespace pcl::io;
00065 using namespace std;
00066 
00067 PointCloud<PointXYZ>::Ptr cloud (new PointCloud<PointXYZ>);
00068 PointCloud<PointNormal>::Ptr cloud_with_normals (new PointCloud<PointNormal>);
00069 search::KdTree<PointXYZ>::Ptr tree;
00070 search::KdTree<PointNormal>::Ptr tree2;
00071 
00072 // add by ktran to test update functions
00073 PointCloud<PointXYZ>::Ptr cloud1 (new PointCloud<PointXYZ>);
00074 PointCloud<PointNormal>::Ptr cloud_with_normals1 (new PointCloud<PointNormal>);
00075 search::KdTree<PointXYZ>::Ptr tree3;
00076 search::KdTree<PointNormal>::Ptr tree4;
00077 
00079 TEST (PCL, MarchingCubesTest)
00080 {
00081   MarchingCubesHoppe<PointNormal> hoppe;
00082   hoppe.setIsoLevel (0);
00083   hoppe.setGridResolution (30, 30, 30);
00084   hoppe.setPercentageExtendGrid (0.3f);
00085   hoppe.setInputCloud (cloud_with_normals);
00086   PointCloud<PointNormal> points;
00087   std::vector<Vertices> vertices;
00088   hoppe.reconstruct (points, vertices);
00089 
00090   EXPECT_NEAR (points.points[points.size()/2].x, -0.042528, 1e-3);
00091   EXPECT_NEAR (points.points[points.size()/2].y, 0.080196, 1e-3);
00092   EXPECT_NEAR (points.points[points.size()/2].z, 0.043159, 1e-3);
00093   EXPECT_EQ (vertices[vertices.size ()/2].vertices[0], 10854);
00094   EXPECT_EQ (vertices[vertices.size ()/2].vertices[1], 10855);
00095   EXPECT_EQ (vertices[vertices.size ()/2].vertices[2], 10856);
00096 
00097 
00098   MarchingCubesRBF<PointNormal> rbf;
00099   rbf.setIsoLevel (0);
00100   rbf.setGridResolution (20, 20, 20);
00101   rbf.setPercentageExtendGrid (0.1f);
00102   rbf.setInputCloud (cloud_with_normals);
00103   rbf.setOffSurfaceDisplacement (0.02f);
00104   rbf.reconstruct (points, vertices);
00105 
00106   EXPECT_NEAR (points.points[points.size()/2].x, -0.033919, 1e-3);
00107   EXPECT_NEAR (points.points[points.size()/2].y, 0.151683, 1e-3);
00108   EXPECT_NEAR (points.points[points.size()/2].z, -0.000086, 1e-3);
00109   EXPECT_EQ (vertices[vertices.size ()/2].vertices[0], 4284);
00110   EXPECT_EQ (vertices[vertices.size ()/2].vertices[1], 4285);
00111   EXPECT_EQ (vertices[vertices.size ()/2].vertices[2], 4286);
00112 }
00113 
00114 
00116 TEST (PCL, MovingLeastSquares)
00117 {
00118   // Init objects
00119   PointCloud<PointXYZ> mls_points;
00120   PointCloud<PointNormal>::Ptr mls_normals (new PointCloud<PointNormal> ());
00121   MovingLeastSquares<PointXYZ, PointNormal> mls;
00122 
00123   // Set parameters
00124   mls.setInputCloud (cloud);
00125   mls.setComputeNormals (true);
00126   mls.setPolynomialFit (true);
00127   mls.setSearchMethod (tree);
00128   mls.setSearchRadius (0.03);
00129 
00130   // Reconstruct
00131   mls.process (*mls_normals);
00132 
00133   EXPECT_NEAR (mls_normals->points[0].x, 0.005417, 1e-3);
00134   EXPECT_NEAR (mls_normals->points[0].y, 0.113463, 1e-3);
00135   EXPECT_NEAR (mls_normals->points[0].z, 0.040715, 1e-3);
00136   EXPECT_NEAR (fabs (mls_normals->points[0].normal[0]), 0.111894, 1e-3);
00137   EXPECT_NEAR (fabs (mls_normals->points[0].normal[1]), 0.594906, 1e-3);
00138   EXPECT_NEAR (fabs (mls_normals->points[0].normal[2]), 0.795969, 1e-3);
00139   EXPECT_NEAR (mls_normals->points[0].curvature, 0.012019, 1e-3);
00140 
00141 
00142   // Testing OpenMP version
00143   MovingLeastSquaresOMP<PointXYZ, PointNormal> mls_omp;
00144   mls_omp.setInputCloud (cloud);
00145   mls_omp.setComputeNormals (true);
00146   mls_omp.setPolynomialFit (true);
00147   mls_omp.setSearchMethod (tree);
00148   mls_omp.setSearchRadius (0.03);
00149   mls_omp.setNumberOfThreads (4);
00150 
00151   // Reconstruct
00152   mls_normals->clear ();
00153   mls_omp.process (*mls_normals);
00154 
00155   int count = 0;
00156   for (size_t i = 0; i < mls_normals->size (); ++i)
00157   {
00158         if (fabs (mls_normals->points[i].x - 0.005417) < 1e-3 &&
00159             fabs (mls_normals->points[i].y - 0.113463) < 1e-3 &&
00160             fabs (mls_normals->points[i].z - 0.040715) < 1e-3 &&
00161             fabs (fabs (mls_normals->points[i].normal[0]) - 0.111894) < 1e-3 &&
00162                 fabs (fabs (mls_normals->points[i].normal[1]) - 0.594906) < 1e-3 &&
00163                 fabs (fabs (mls_normals->points[i].normal[2]) - 0.795969) < 1e-3 &&
00164                 fabs (mls_normals->points[i].curvature - 0.012019) < 1e-3)
00165                 count ++;
00166   }
00167 
00168   EXPECT_EQ (count, 1);
00169 
00170 
00171 
00172   // Testing upsampling
00173   MovingLeastSquares<PointXYZ, PointNormal> mls_upsampling;
00174   // Set parameters
00175   mls_upsampling.setInputCloud (cloud);
00176   mls_upsampling.setComputeNormals (true);
00177   mls_upsampling.setPolynomialFit (true);
00178   mls_upsampling.setSearchMethod (tree);
00179   mls_upsampling.setSearchRadius (0.03);
00180   mls_upsampling.setUpsamplingMethod (MovingLeastSquares<PointXYZ, PointNormal>::SAMPLE_LOCAL_PLANE);
00181   mls_upsampling.setUpsamplingRadius (0.025);
00182   mls_upsampling.setUpsamplingStepSize (0.01);
00183 
00184   mls_normals->clear ();
00185   mls_upsampling.process (*mls_normals);
00186 
00187   EXPECT_NEAR (mls_normals->points[10].x, -0.000538, 1e-3);
00188   EXPECT_NEAR (mls_normals->points[10].y, 0.110080, 1e-3);
00189   EXPECT_NEAR (mls_normals->points[10].z, 0.043602, 1e-3);
00190   EXPECT_NEAR (fabs (mls_normals->points[10].normal[0]), 0.022678, 1e-3);
00191   EXPECT_NEAR (fabs (mls_normals->points[10].normal[1]), 0.554978, 1e-3);
00192   EXPECT_NEAR (fabs (mls_normals->points[10].normal[2]), 0.831556, 1e-3);
00193   EXPECT_NEAR (mls_normals->points[10].curvature, 0.012019, 1e-3);
00194   EXPECT_EQ (mls_normals->size (), 6352);
00195 
00196 
00200 //  mls_upsampling.setUpsamplingMethod (MovingLeastSquares<PointXYZ, PointNormal>::RANDOM_UNIFORM_DENSITY);
00201 //  mls_upsampling.setPointDensity (100);
00202 //  mls_normals->clear ();
00203 //  mls_upsampling.process (*mls_normals);
00204 //
00205 //  EXPECT_NEAR (mls_normals->points[10].x, 0.018806, 1e-3);
00206 //  EXPECT_NEAR (mls_normals->points[10].y, 0.114685, 1e-3);
00207 //  EXPECT_NEAR (mls_normals->points[10].z, 0.037500, 1e-3);
00208 //  EXPECT_NEAR (fabs (mls_normals->points[10].normal[0]), 0.351352, 1e-3);
00209 //  EXPECT_NEAR (fabs (mls_normals->points[10].normal[1]), 0.537741, 1e-3);
00210 //  EXPECT_NEAR (fabs (mls_normals->points[10].normal[2]), 0.766411, 1e-3);
00211 //  EXPECT_NEAR (mls_normals->points[10].curvature, 0.019003, 1e-3);
00212 //  EXPECT_EQ (mls_normals->size (), 457);
00213 
00214 
00215   mls_upsampling.setUpsamplingMethod (MovingLeastSquares<PointXYZ, PointNormal>::VOXEL_GRID_DILATION);
00216   mls_upsampling.setDilationIterations (5);
00217   mls_upsampling.setDilationVoxelSize (0.005f);
00218   mls_normals->clear ();
00219   mls_upsampling.process (*mls_normals);
00220   EXPECT_NEAR (mls_normals->points[10].x, -0.075887121260166168, 2e-3);
00221   EXPECT_NEAR (mls_normals->points[10].y, 0.030984390527009964, 2e-3);
00222   EXPECT_NEAR (mls_normals->points[10].z, 0.020856190472841263, 2e-3);
00223   EXPECT_NEAR (mls_normals->points[10].curvature, 0.107273, 1e-1);
00224   EXPECT_NEAR (double (mls_normals->size ()), 26266, 2);
00225 }
00226 
00228 TEST (PCL, GreedyProjectionTriangulation)
00229 {
00230   // Init objects
00231   PolygonMesh triangles;
00232   GreedyProjectionTriangulation<PointNormal> gp3;
00233 
00234   // Set parameters
00235   gp3.setInputCloud (cloud_with_normals);
00236   gp3.setSearchMethod (tree2);
00237   gp3.setSearchRadius (0.025);
00238   gp3.setMu (2.5);
00239   gp3.setMaximumNearestNeighbors (100);
00240   gp3.setMaximumSurfaceAngle(M_PI/4); // 45 degrees
00241   gp3.setMinimumAngle(M_PI/18); // 10 degrees
00242   gp3.setMaximumAngle(2*M_PI/3); // 120 degrees
00243   gp3.setNormalConsistency(false);
00244 
00245   // Reconstruct
00246   gp3.reconstruct (triangles);
00247   //saveVTKFile ("./test/bun0-gp3.vtk", triangles);
00248   EXPECT_EQ (triangles.cloud.width, cloud_with_normals->width);
00249   EXPECT_EQ (triangles.cloud.height, cloud_with_normals->height);
00250   EXPECT_NEAR (int (triangles.polygons.size ()), 685, 5);
00251 
00252   // Check triangles
00253   EXPECT_EQ (int (triangles.polygons.at (0).vertices.size ()), 3);
00254   EXPECT_EQ (int (triangles.polygons.at (0).vertices.at (0)), 0);
00255   EXPECT_EQ (int (triangles.polygons.at (0).vertices.at (1)), 12);
00256   EXPECT_EQ (int (triangles.polygons.at (0).vertices.at (2)), 198);
00257   EXPECT_EQ (int (triangles.polygons.at (684).vertices.size ()), 3);
00258   EXPECT_EQ (int (triangles.polygons.at (684).vertices.at (0)), 393);
00259   EXPECT_EQ (int (triangles.polygons.at (684).vertices.at (1)), 394);
00260   EXPECT_EQ (int (triangles.polygons.at (684).vertices.at (2)), 395);
00261 
00262   // Additional vertex information
00263   std::vector<int> parts = gp3.getPartIDs();
00264   std::vector<int> states = gp3.getPointStates();
00265   int nr_points = cloud_with_normals->width * cloud_with_normals->height;
00266   EXPECT_EQ (int (parts.size ()), nr_points);
00267   EXPECT_EQ (int (states.size ()), nr_points);
00268   EXPECT_EQ (parts[0], 0);
00269   EXPECT_EQ (states[0], gp3.COMPLETED);
00270   EXPECT_EQ (parts[393], 5);
00271   EXPECT_EQ (states[393], gp3.BOUNDARY);
00272 }
00273 
00275 TEST (PCL, GreedyProjectionTriangulation_Merge2Meshes)
00276 {
00277   // check if exist update cloud
00278   if(cloud_with_normals1->width * cloud_with_normals1->height > 0){
00279     // Init objects
00280     PolygonMesh triangles;
00281     PolygonMesh triangles1;
00282     GreedyProjectionTriangulation<PointNormal> gp3;
00283     GreedyProjectionTriangulation<PointNormal> gp31;
00284 
00285     // Set parameters
00286     gp3.setInputCloud (cloud_with_normals);
00287     gp3.setSearchMethod (tree2);
00288     gp3.setSearchRadius (0.025);
00289     gp3.setMu (2.5);
00290     gp3.setMaximumNearestNeighbors (100);
00291     gp3.setMaximumSurfaceAngle(M_PI/4); // 45 degrees
00292     gp3.setMinimumAngle(M_PI/18); // 10 degrees
00293     gp3.setMaximumAngle(2*M_PI/3); // 120 degrees
00294     gp3.setNormalConsistency(false);
00295 
00296     // for mesh 2
00297     // Set parameters
00298     gp31.setInputCloud (cloud_with_normals1);
00299     gp31.setSearchMethod (tree4);
00300     gp31.setSearchRadius (0.025);
00301     gp31.setMu (2.5);
00302     gp31.setMaximumNearestNeighbors (100);
00303     gp31.setMaximumSurfaceAngle(M_PI/4); // 45 degrees
00304     gp31.setMinimumAngle(M_PI/18); // 10 degrees
00305     gp31.setMaximumAngle(2*M_PI/3); // 120 degrees
00306     gp31.setNormalConsistency(false);
00307 
00308 
00309     // Reconstruct
00310     //gp3.reconstruct (triangles);
00311     //saveVTKFile ("bun01.vtk", triangles);
00312 
00313     //gp31.reconstruct (triangles1);
00314     //saveVTKFile ("bun02.vtk", triangles1);
00315   }
00316 }
00318 TEST (PCL, UpdateMesh_With_TextureMapping)
00319 {
00320   if(cloud_with_normals1->width * cloud_with_normals1->height > 0){
00321     // Init objects
00322     PolygonMesh triangles;
00323     PolygonMesh triangles1;
00324     GreedyProjectionTriangulation<PointNormal> gp3;
00325     GreedyProjectionTriangulation<PointNormal> gp31;
00326 
00327     // Set parameters
00328     gp3.setInputCloud (cloud_with_normals);
00329     gp3.setSearchMethod (tree2);
00330     gp3.setSearchRadius (0.025);
00331     gp3.setMu (2.5);
00332     gp3.setMaximumNearestNeighbors (100);
00333     gp3.setMaximumSurfaceAngle(M_PI/4); // 45 degrees
00334     gp3.setMinimumAngle(M_PI/18); // 10 degrees
00335     gp3.setMaximumAngle(2*M_PI/3); // 120 degrees
00336     gp3.setNormalConsistency(false);
00337 
00338     gp3.reconstruct (triangles);
00339 
00340     EXPECT_EQ (triangles.cloud.width, cloud_with_normals->width);
00341     EXPECT_EQ (triangles.cloud.height, cloud_with_normals->height);
00342     EXPECT_EQ (int (triangles.polygons.size ()), 685);
00343 
00344     // update with texture mapping
00345     // set 2 texture for 2 mesh
00346     std::vector<std::string> tex_files;
00347     tex_files.push_back("tex4.jpg");
00348 
00349     // initialize texture mesh
00350     TextureMesh tex_mesh;
00351     tex_mesh.header = triangles.header;
00352     tex_mesh.cloud = triangles.cloud;
00353 
00354     // add the 1st mesh
00355     tex_mesh.tex_polygons.push_back(triangles.polygons);
00356 
00357     // update mesh and texture mesh
00358     //gp3.updateMesh(cloud_with_normals1, triangles, tex_mesh);
00359     // set texture for added cloud
00360     //tex_files.push_back("tex8.jpg");
00361     // save updated mesh
00362     //saveVTKFile ("update_bunny.vtk", triangles);
00363 
00364     //TextureMapping<PointXYZ> tm;
00365 
00367     //tm.setF(0.01);
00368 
00370     //tm.setVectorField(1, 0, 0);
00371 
00372     //TexMaterial tex_material;
00373 
00375     //tex_material.tex_Ka.r = 0.2f;
00376     //tex_material.tex_Ka.g = 0.2f;
00377     //tex_material.tex_Ka.b = 0.2f;
00378 
00379     //tex_material.tex_Kd.r = 0.8f;
00380     //tex_material.tex_Kd.g = 0.8f;
00381     //tex_material.tex_Kd.b = 0.8f;
00382 
00383     //tex_material.tex_Ks.r = 1.0f;
00384     //tex_material.tex_Ks.g = 1.0f;
00385     //tex_material.tex_Ks.b = 1.0f;
00386     //tex_material.tex_d = 1.0f;
00387     //tex_material.tex_Ns = 0.0f;
00388     //tex_material.tex_illum = 2;
00389 
00391     //tm.setTextureMaterials(tex_material);
00392 
00394     //tm.setTextureFiles(tex_files);
00395 
00397     //tm.mapTexture2Mesh(tex_mesh);
00398 
00399     //saveOBJFile ("update_bunny.obj", tex_mesh);
00400   }
00401 }
00402 
00404 TEST (PCL, Organized)
00405 {
00406   //construct dataset
00407   pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_organized (new pcl::PointCloud<pcl::PointXYZ> ());
00408   cloud_organized->width = 5;
00409   cloud_organized->height = 10;
00410   cloud_organized->points.resize (cloud_organized->width * cloud_organized->height);
00411 
00412   int npoints = 0;
00413   for (size_t i = 0; i < cloud_organized->height; i++)
00414   {
00415     for (size_t j = 0; j < cloud_organized->width; j++)
00416     {
00417       cloud_organized->points[npoints].x = static_cast<float> (i);
00418       cloud_organized->points[npoints].y = static_cast<float> (j);
00419       cloud_organized->points[npoints].z = static_cast<float> (cloud_organized->points.size ()); // to avoid shadowing
00420       npoints++;
00421     }
00422   }
00423   int nan_idx = cloud_organized->width*cloud_organized->height - 2*cloud_organized->width + 1;
00424   cloud_organized->points[nan_idx].x = numeric_limits<float>::quiet_NaN ();
00425   cloud_organized->points[nan_idx].y = numeric_limits<float>::quiet_NaN ();
00426   cloud_organized->points[nan_idx].z = numeric_limits<float>::quiet_NaN ();
00427   
00428   // Init objects
00429   PolygonMesh triangles;
00430   OrganizedFastMesh<PointXYZ> ofm;
00431 
00432   // Set parameters
00433   ofm.setInputCloud (cloud_organized);
00434   ofm.setMaxEdgeLength (1.5);
00435   ofm.setTrianglePixelSize (1);
00436   ofm.setTriangulationType (OrganizedFastMesh<PointXYZ>::TRIANGLE_ADAPTIVE_CUT);
00437 
00438   // Reconstruct
00439   ofm.reconstruct (triangles);
00440   //saveVTKFile ("./test/organized.vtk", triangles);
00441 
00442   // Check triangles
00443   EXPECT_EQ (triangles.cloud.width, cloud_organized->width);
00444   EXPECT_EQ (triangles.cloud.height, cloud_organized->height);
00445   EXPECT_EQ (int (triangles.polygons.size ()), 2*(triangles.cloud.width-1)*(triangles.cloud.height-1) - 4);
00446   EXPECT_EQ (int (triangles.polygons.at (0).vertices.size ()), 3);
00447   EXPECT_EQ (int (triangles.polygons.at (0).vertices.at (0)), 0);
00448   EXPECT_EQ (int (triangles.polygons.at (0).vertices.at (1)), triangles.cloud.width+1);
00449   EXPECT_EQ (int (triangles.polygons.at (0).vertices.at (2)), 1);
00450 }
00451 
00453 TEST (PCL, GridProjection)
00454 {
00455   // Init objects
00456   PolygonMesh grid;
00457   GridProjection<PointNormal> gp;
00458 
00459   // Set parameters
00460   gp.setInputCloud (cloud_with_normals);
00461   gp.setSearchMethod (tree2);
00462   gp.setResolution (0.005);
00463   gp.setPaddingSize (3);
00464 
00465   // Reconstruct
00466   gp.reconstruct (grid);
00467   //saveVTKFile ("./test/bun0-grid.vtk", grid);
00468   EXPECT_GE (grid.cloud.width, 5180);
00469   EXPECT_GE (int (grid.polygons.size ()), 1295);
00470   EXPECT_EQ (int (grid.polygons.at (0).vertices.size ()), 4);
00471   EXPECT_EQ (int (grid.polygons.at (0).vertices.at (0)), 0);
00472 }
00473 
00475 TEST (PCL, ConvexHull_bunny)
00476 {
00477   pcl::PointCloud<pcl::PointXYZ> hull;
00478   std::vector<pcl::Vertices> polygons;
00479 
00480   pcl::ConvexHull<pcl::PointXYZ> chull;
00481   chull.setInputCloud (cloud);
00482   chull.reconstruct (hull, polygons);
00483 
00484   //PolygonMesh convex;
00485   //toROSMsg (hull, convex.cloud);
00486   //convex.polygons = polygons;
00487   //saveVTKFile ("./test/bun0-convex.vtk", convex);
00488 
00489   EXPECT_EQ (polygons.size (), 206);
00490 
00491   //check distance between min and max in the hull
00492   Eigen::Vector4f min_pt_hull, max_pt_hull;
00493   pcl::getMinMax3D (hull, min_pt_hull, max_pt_hull);
00494 
00495   Eigen::Vector4f min_pt, max_pt;
00496   pcl::getMinMax3D (hull, min_pt, max_pt);
00497 
00498   EXPECT_NEAR ((min_pt - max_pt).norm (), (min_pt_hull - max_pt_hull).norm (), 1e-5);
00499 
00500   //
00501   // Test the face-vertices-only output variant
00502   //
00503 
00504   // construct the hull mesh
00505   std::vector<pcl::Vertices> polygons2;
00506   chull.reconstruct (polygons2);
00507 
00508   // compare the face vertices (polygons2) to the output from the original test --- they should be identical
00509   ASSERT_EQ (polygons.size (), polygons2.size ());
00510   for (size_t i = 0; i < polygons.size (); ++i)
00511   {
00512     const pcl::Vertices & face1 = polygons[i];
00513     const pcl::Vertices & face2 = polygons2[i];
00514     ASSERT_EQ (face1.vertices.size (), face2.vertices.size ());
00515     for (size_t j = 0; j < face1.vertices.size (); ++j)
00516     {
00517       ASSERT_EQ (face1.vertices[j], face2.vertices[j]);
00518     }
00519   }
00520 
00521 
00522   //
00523   // Test the PolygonMesh output variant
00524   //
00525 
00526   // construct the hull mesh
00527   PolygonMesh mesh;
00528   chull.reconstruct (mesh);
00529 
00530   // convert the internal PointCloud2 to a PointCloud
00531   PointCloud<pcl::PointXYZ> hull2;
00532   pcl::fromROSMsg (mesh.cloud, hull2);
00533 
00534   // compare the PointCloud (hull2) to the output from the original test --- they should be identical
00535   ASSERT_EQ (hull.points.size (), hull2.points.size ());
00536   for (size_t i = 0; i < hull.points.size (); ++i)
00537   {
00538     const PointXYZ & p1 = hull.points[i];
00539     const PointXYZ & p2 = hull2.points[i];
00540     ASSERT_EQ (p1.x, p2.x);
00541     ASSERT_EQ (p1.y, p2.y);
00542     ASSERT_EQ (p1.z, p2.z);
00543   }
00544 
00545   // compare the face vertices (mesh.polygons) to the output from the original test --- they should be identical
00546   ASSERT_EQ (polygons.size (), mesh.polygons.size ());
00547   for (size_t i = 0; i < polygons.size (); ++i)
00548   {
00549     const pcl::Vertices & face1 = polygons[i];
00550     const pcl::Vertices & face2 = mesh.polygons[i];
00551     ASSERT_EQ (face1.vertices.size (), face2.vertices.size ());
00552     for (size_t j = 0; j < face1.vertices.size (); ++j)
00553     {
00554       ASSERT_EQ (face1.vertices[j], face2.vertices[j]);
00555     }
00556   }    
00557 
00558 }
00559 
00561 TEST (PCL, ConvexHull_LTable)
00562 {
00563   //construct dataset
00564   pcl::PointCloud<pcl::PointXYZ> cloud_out_ltable;
00565   cloud_out_ltable.points.resize (100);
00566 
00567   int npoints = 0;
00568   for (size_t i = 0; i < 8; i++)
00569   {
00570     for (size_t j = 0; j <= 2; j++)
00571     {
00572       cloud_out_ltable.points[npoints].x = float (i) * 0.5f;
00573       cloud_out_ltable.points[npoints].y = -float (j) * 0.5f;
00574       cloud_out_ltable.points[npoints].z = 0.f;
00575       npoints++;
00576     }
00577   }
00578 
00579   for (size_t i = 0; i <= 2; i++)
00580   {
00581     for (size_t j = 3; j < 8; j++)
00582     {
00583       cloud_out_ltable.points[npoints].x = float (i) * 0.5f;
00584       cloud_out_ltable.points[npoints].y = -float (j) * 0.5f;
00585       cloud_out_ltable.points[npoints].z = 0.f;
00586       npoints++;
00587     }
00588   }
00589 
00590   // add the five points on the hull
00591   cloud_out_ltable.points[npoints].x = -0.5f;
00592   cloud_out_ltable.points[npoints].y = 0.5f;
00593   cloud_out_ltable.points[npoints].z = 0.f;
00594   npoints++;
00595 
00596   cloud_out_ltable.points[npoints].x = 4.5f;
00597   cloud_out_ltable.points[npoints].y = 0.5f;
00598   cloud_out_ltable.points[npoints].z = 0.f;
00599   npoints++;
00600 
00601   cloud_out_ltable.points[npoints].x = 4.5f;
00602   cloud_out_ltable.points[npoints].y = -1.0f;
00603   cloud_out_ltable.points[npoints].z = 0.f;
00604   npoints++;
00605 
00606   cloud_out_ltable.points[npoints].x = 1.0f;
00607   cloud_out_ltable.points[npoints].y = -4.5f;
00608   cloud_out_ltable.points[npoints].z = 0.f;
00609   npoints++;
00610 
00611   cloud_out_ltable.points[npoints].x = -0.5f;
00612   cloud_out_ltable.points[npoints].y = -4.5f;
00613   cloud_out_ltable.points[npoints].z = 0.f;
00614   npoints++;
00615 
00616   cloud_out_ltable.points.resize (npoints);
00617 
00618   pcl::PointCloud<pcl::PointXYZ> hull;
00619   std::vector<pcl::Vertices> polygons;
00620   pcl::PointCloud<pcl::PointXYZ>::ConstPtr cloudptr (new pcl::PointCloud<pcl::PointXYZ> (cloud_out_ltable));
00621   pcl::ConvexHull<pcl::PointXYZ> chull;
00622   chull.setInputCloud (cloudptr);
00623   chull.reconstruct (hull, polygons);
00624 
00625   EXPECT_EQ (polygons.size (), 1);
00626   EXPECT_EQ (hull.points.size (), 5);
00627 
00628 
00629   //
00630   // Test the face-vertices-only output variant
00631   //
00632 
00633   // construct the hull mesh
00634   std::vector<pcl::Vertices> polygons2;
00635   chull.reconstruct (polygons2);
00636 
00637   // compare the face vertices (polygons2) to the output from the original test --- they should be identical
00638   ASSERT_EQ (polygons.size (), polygons2.size ());
00639   for (size_t i = 0; i < polygons.size (); ++i)
00640   {
00641     const pcl::Vertices & face1 = polygons[i];
00642     const pcl::Vertices & face2 = polygons2[i];
00643     ASSERT_EQ (face1.vertices.size (), face2.vertices.size ());
00644     for (size_t j = 0; j < face1.vertices.size (); ++j)
00645     {
00646       ASSERT_EQ (face1.vertices[j], face2.vertices[j]);
00647     }
00648   }
00649 
00650 
00651   //
00652   // Test the PolygonMesh output variant
00653   //
00654 
00655   // construct the hull mesh
00656   PolygonMesh mesh;
00657   chull.reconstruct (mesh);
00658 
00659   // convert the internal PointCloud2 to a PointCloud
00660   PointCloud<pcl::PointXYZ> hull2;
00661   pcl::fromROSMsg (mesh.cloud, hull2);
00662 
00663   // compare the PointCloud (hull2) to the output from the original test --- they should be identical
00664   ASSERT_EQ (hull.points.size (), hull2.points.size ());
00665   for (size_t i = 0; i < hull.points.size (); ++i)
00666   {
00667     const PointXYZ & p1 = hull.points[i];
00668     const PointXYZ & p2 = hull2.points[i];
00669     ASSERT_EQ (p1.x, p2.x);
00670     ASSERT_EQ (p1.y, p2.y);
00671     ASSERT_EQ (p1.z, p2.z);
00672   }
00673 
00674   // compare the face vertices (mesh.polygons) to the output from the original test --- they should be identical
00675   ASSERT_EQ (polygons.size (), mesh.polygons.size ());
00676   for (size_t i = 0; i < polygons.size (); ++i)
00677   {
00678     const pcl::Vertices & face1 = polygons[i];
00679     const pcl::Vertices & face2 = mesh.polygons[i];
00680     ASSERT_EQ (face1.vertices.size (), face2.vertices.size ());
00681     for (size_t j = 0; j < face1.vertices.size (); ++j)
00682     {
00683       ASSERT_EQ (face1.vertices[j], face2.vertices[j]);
00684     }
00685   }    
00686 
00687 }
00688 
00690 TEST (PCL, ConvexHull_2dsquare)
00691 {
00692   //Generate data
00693   pcl::PointCloud<pcl::PointXYZ>::Ptr input_cloud (new pcl::PointCloud<pcl::PointXYZ> ());
00694   input_cloud->width = 1000000;
00695   input_cloud->height = 1;
00696   input_cloud->points.resize (input_cloud->width * input_cloud->height);
00697   
00698   //rng
00699   boost::mt19937 rng_alg;
00700   boost::uniform_01<boost::mt19937> rng (rng_alg);
00701   rng.base ().seed (12345u);
00702 
00703   for (size_t i = 0; i < input_cloud->points.size (); i++)
00704   {
00705     input_cloud->points[i].x = (2.0f * float (rng ()))-1.0f;
00706     input_cloud->points[i].y = (2.0f * float (rng ()))-1.0f;
00707     input_cloud->points[i].z = 1.0f;
00708   }
00709 
00710   //Set up for creating a hull
00711   pcl::PointCloud<pcl::PointXYZ> hull;
00712   pcl::ConvexHull<pcl::PointXYZ> chull;
00713   chull.setInputCloud (input_cloud);
00714   //chull.setDim (2); //We'll skip this, so we can check auto-detection
00715   chull.reconstruct (hull);
00716 
00717   //Check that input was correctly detected as 2D input
00718   ASSERT_EQ (2, chull.getDimension ());
00719   
00720   //Verify that all points lie within the plane we generated
00721   //This plane has normal equal to the z-axis (parallel to the xy plane, 1m up)
00722   Eigen::Vector4f plane_normal (0.0, 0.0, -1.0, 1.0);
00723 
00724   //Make sure they're actually near some edge
00725   std::vector<Eigen::Vector4f, Eigen::aligned_allocator<Eigen::Vector4f> > facets;
00726   facets.push_back (Eigen::Vector4f (-1.0, 0.0, 0.0, 1.0));
00727   facets.push_back (Eigen::Vector4f (-1.0, 0.0, 0.0, -1.0));
00728   facets.push_back (Eigen::Vector4f (0.0, -1.0, 0.0, 1.0));
00729   facets.push_back (Eigen::Vector4f (0.0, -1.0, 0.0, -1.0));
00730 
00731   //Make sure they're in the plane
00732   for (size_t i = 0; i < hull.points.size (); i++)
00733   {
00734     float dist = fabs (hull.points[i].getVector4fMap ().dot (plane_normal));
00735     EXPECT_NEAR (dist, 0.0, 1e-2);
00736 
00737     float min_dist = std::numeric_limits<float>::infinity ();
00738     for (size_t j = 0; j < facets.size (); j++)
00739     {
00740       float d2 = fabs (hull.points[i].getVector4fMap ().dot (facets[j]));
00741       
00742       if (d2 < min_dist)
00743         min_dist = d2;
00744     }
00745     EXPECT_NEAR (min_dist, 0.0, 1e-2);
00746   }
00747 }
00748 
00750 TEST (PCL, ConvexHull_3dcube)
00751 {
00752   //Generate data
00753   pcl::PointCloud<pcl::PointXYZ>::Ptr input_cloud (new pcl::PointCloud<pcl::PointXYZ> ());
00754   input_cloud->width = 10000000;
00755   input_cloud->height = 1;
00756   input_cloud->points.resize (input_cloud->width * input_cloud->height);
00757   
00758   //rng
00759   boost::mt19937 rng_alg;
00760   boost::uniform_01<boost::mt19937> rng (rng_alg);
00761   rng.base ().seed (12345u);
00762 
00763   for (size_t i = 0; i < input_cloud->points.size (); i++)
00764   {
00765     input_cloud->points[i].x =  (2.0f * float (rng ()))-1.0f;
00766     input_cloud->points[i].y =  (2.0f * float (rng ()))-1.0f;
00767     input_cloud->points[i].z =  (2.0f * float (rng ()))-1.0f;
00768   }
00769 
00770   //Set up for creating a hull
00771   pcl::PointCloud<pcl::PointXYZ> hull;
00772   pcl::ConvexHull<pcl::PointXYZ> chull;
00773   chull.setInputCloud (input_cloud);
00774   //chull.setDim (3); //We'll skip this, so we can check auto-detection
00775   chull.reconstruct (hull);
00776 
00777   //Check that input was correctly detected as 3D input
00778   ASSERT_EQ (3, chull.getDimension ());
00779   
00780   //Make sure they're actually near some edge
00781   std::vector<Eigen::Vector4f, Eigen::aligned_allocator<Eigen::Vector4f> > facets;
00782   facets.push_back (Eigen::Vector4f (-1.0f, 0.0f, 0.0f, 1.0f));
00783   facets.push_back (Eigen::Vector4f (-1.0f, 0.0f, 0.0f, -1.0f));
00784   facets.push_back (Eigen::Vector4f (0.0f, -1.0f, 0.0f, 1.0f));
00785   facets.push_back (Eigen::Vector4f (0.0f, -1.0f, 0.0f, -1.0f));
00786   facets.push_back (Eigen::Vector4f (0.0f, 0.0f, -1.0f, 1.0f));
00787   facets.push_back (Eigen::Vector4f (0.0f, 0.0f, -1.0f, -1.0f));
00788 
00789   //Make sure they're near a facet
00790   for (size_t i = 0; i < hull.points.size (); i++)
00791   {
00792     float min_dist = std::numeric_limits<float>::infinity ();
00793     for (size_t j = 0; j < facets.size (); j++)
00794     {
00795       float dist = fabs (hull.points[i].getVector4fMap ().dot (facets[j]));
00796       
00797       if (dist < min_dist)
00798         min_dist = dist;
00799     }
00800     EXPECT_NEAR (min_dist, 0.0, 1e-2);
00801   }
00802 }
00803 
00805 TEST (PCL, ConcaveHull_bunny)
00806 {
00807   //construct dataset
00808   pcl::PointCloud<pcl::PointXYZ>::Ptr cloud2D (new pcl::PointCloud<pcl::PointXYZ> (*cloud));
00809   for (size_t i = 0; i < cloud2D->points.size (); i++)
00810     cloud2D->points[i].z = 0;
00811 
00812   pcl::PointCloud<pcl::PointXYZ> alpha_shape;
00813   pcl::PointCloud<pcl::PointXYZ>::Ptr voronoi_centers (new pcl::PointCloud<pcl::PointXYZ>);
00814   std::vector<pcl::Vertices> polygons_alpha;
00815 
00816   pcl::ConcaveHull<pcl::PointXYZ> concave_hull;
00817   concave_hull.setInputCloud (cloud2D);
00818   concave_hull.setAlpha (0.5);
00819   concave_hull.setVoronoiCenters (voronoi_centers);
00820   concave_hull.reconstruct (alpha_shape, polygons_alpha);
00821 
00822   EXPECT_EQ (alpha_shape.points.size (), 21);
00823 
00824   pcl::PointCloud<pcl::PointXYZ> alpha_shape1;
00825   pcl::PointCloud<pcl::PointXYZ>::Ptr voronoi_centers1 (new pcl::PointCloud<pcl::PointXYZ>);
00826   std::vector<pcl::Vertices> polygons_alpha1;
00827 
00828   pcl::ConcaveHull<pcl::PointXYZ> concave_hull1;
00829   concave_hull1.setInputCloud (cloud2D);
00830   concave_hull1.setAlpha (1.5);
00831   concave_hull1.setVoronoiCenters (voronoi_centers1);
00832   concave_hull1.reconstruct (alpha_shape1, polygons_alpha1);
00833 
00834   EXPECT_EQ (alpha_shape1.points.size (), 20);
00835 
00836   pcl::PointCloud<pcl::PointXYZ> alpha_shape2;
00837   pcl::PointCloud<pcl::PointXYZ>::Ptr voronoi_centers2 (new pcl::PointCloud<pcl::PointXYZ>);
00838   std::vector<pcl::Vertices> polygons_alpha2;
00839   pcl::ConcaveHull<pcl::PointXYZ> concave_hull2;
00840   concave_hull2.setInputCloud (cloud2D);
00841   concave_hull2.setAlpha (0.01);
00842   concave_hull2.setVoronoiCenters (voronoi_centers2);
00843   concave_hull2.reconstruct (alpha_shape2, polygons_alpha2);
00844 
00845   EXPECT_EQ (alpha_shape2.points.size (), 81);
00846 
00847   //PolygonMesh concave;
00848   //toROSMsg (alpha_shape2, concave.cloud);
00849   //concave.polygons = polygons_alpha2;
00850   //saveVTKFile ("./test/bun0-concave2d.vtk", concave);
00851 }
00852 
00854 TEST (PCL, ConcaveHull_LTable)
00855 {
00856   //construct dataset
00857   pcl::PointCloud<pcl::PointXYZ> cloud_out_ltable;
00858   cloud_out_ltable.points.resize (100);
00859 
00860   int npoints = 0;
00861   for (size_t i = 0; i < 8; i++)
00862   {
00863     for (size_t j = 0; j <= 2; j++)
00864     {
00865       cloud_out_ltable.points[npoints].x = float (i) * 0.5f;
00866       cloud_out_ltable.points[npoints].y = -float (j) * 0.5f;
00867       cloud_out_ltable.points[npoints].z = 0.f;
00868       npoints++;
00869     }
00870   }
00871 
00872   for (size_t i = 0; i <= 2; i++)
00873   {
00874     for(size_t j = 3; j < 8; j++)
00875     {
00876       cloud_out_ltable.points[npoints].x = float (i) * 0.5f;
00877       cloud_out_ltable.points[npoints].y = -float (j) * 0.5f;
00878       cloud_out_ltable.points[npoints].z = 0.f;
00879       npoints++;
00880     }
00881   }
00882 
00883   cloud_out_ltable.points.resize (npoints);
00884 
00885   pcl::PointCloud<pcl::PointXYZ>::ConstPtr cloudptr (new pcl::PointCloud<pcl::PointXYZ> (cloud_out_ltable));
00886 
00887   pcl::PointCloud<pcl::PointXYZ> alpha_shape;
00888   pcl::PointCloud<pcl::PointXYZ>::Ptr voronoi_centers (new pcl::PointCloud<pcl::PointXYZ>);
00889   std::vector<pcl::Vertices> polygons_alpha;
00890 
00891   pcl::ConcaveHull<pcl::PointXYZ> concave_hull;
00892   concave_hull.setInputCloud (cloudptr);
00893   concave_hull.setAlpha (0.5);
00894   concave_hull.setVoronoiCenters (voronoi_centers);
00895   concave_hull.reconstruct (alpha_shape, polygons_alpha);
00896 
00897   EXPECT_EQ (alpha_shape.points.size (), 27);
00898 
00899   pcl::PointCloud<pcl::PointXYZ> alpha_shape1;
00900   pcl::PointCloud<pcl::PointXYZ>::Ptr voronoi_centers1 (new pcl::PointCloud<pcl::PointXYZ>);
00901   std::vector<pcl::Vertices> polygons_alpha1;
00902 
00903   pcl::ConcaveHull<pcl::PointXYZ> concave_hull1;
00904   concave_hull1.setInputCloud (cloudptr);
00905   concave_hull1.setAlpha (1.5);
00906   concave_hull1.setVoronoiCenters (voronoi_centers1);
00907   concave_hull1.reconstruct (alpha_shape1, polygons_alpha1);
00908 
00909   EXPECT_EQ (alpha_shape1.points.size (), 23);
00910 
00911   pcl::PointCloud<pcl::PointXYZ> alpha_shape2;
00912   pcl::PointCloud<pcl::PointXYZ>::Ptr voronoi_centers2 (new pcl::PointCloud<pcl::PointXYZ>);
00913   std::vector<pcl::Vertices> polygons_alpha2;
00914   pcl::ConcaveHull<pcl::PointXYZ> concave_hull2;
00915   concave_hull2.setInputCloud (cloudptr);
00916   concave_hull2.setAlpha (3);
00917   concave_hull2.setVoronoiCenters (voronoi_centers2);
00918   concave_hull2.reconstruct (alpha_shape2, polygons_alpha2);
00919 
00920   EXPECT_EQ (alpha_shape2.points.size (), 19);
00921 }
00922 
00924 TEST (PCL, EarClipping)
00925 {
00926   PointCloud<PointXYZ>::Ptr cloud (new PointCloud<PointXYZ>());
00927   cloud->height = 1;
00928   cloud->points.push_back (PointXYZ ( 0.f, 0.f, 0.5f));
00929   cloud->points.push_back (PointXYZ ( 5.f, 0.f, 0.6f));
00930   cloud->points.push_back (PointXYZ ( 9.f, 4.f, 0.5f));
00931   cloud->points.push_back (PointXYZ ( 4.f, 7.f, 0.5f));
00932   cloud->points.push_back (PointXYZ ( 2.f, 5.f, 0.5f));
00933   cloud->points.push_back (PointXYZ (-1.f, 8.f, 0.5f));
00934   cloud->width = static_cast<uint32_t> (cloud->points.size ());
00935 
00936   Vertices vertices;
00937   vertices.vertices.resize (cloud->points.size ());
00938   for (int i = 0; i < static_cast<int> (vertices.vertices.size ()); ++i)
00939     vertices.vertices[i] = i;
00940 
00941   PolygonMesh::Ptr mesh (new PolygonMesh);
00942   toROSMsg (*cloud, mesh->cloud);
00943   mesh->polygons.push_back (vertices);
00944 
00945   EarClipping clipper;
00946   PolygonMesh::ConstPtr mesh_aux (mesh);
00947   clipper.setInputMesh (mesh_aux);
00948 
00949   PolygonMesh triangulated_mesh;
00950   clipper.process (triangulated_mesh);
00951 
00952   EXPECT_EQ (triangulated_mesh.polygons.size (), 4);
00953   for (int i = 0; i < static_cast<int> (triangulated_mesh.polygons.size ()); ++i)
00954     EXPECT_EQ (triangulated_mesh.polygons[i].vertices.size (), 3);
00955 
00956   const int truth[][3] = { {5, 0, 1},
00957                            {2, 3, 4},
00958                            {4, 5, 1},
00959                            {1, 2, 4} };
00960 
00961   for (int pi = 0; pi < static_cast<int> (triangulated_mesh.polygons.size ()); ++pi)
00962   for (int vi = 0; vi < 3; ++vi)
00963   {
00964     EXPECT_EQ (triangulated_mesh.polygons[pi].vertices[vi], truth[pi][vi]);
00965   }
00966 }
00967 
00969 TEST (PCL, Poisson)
00970 {
00971   Poisson<PointNormal> poisson;
00972   poisson.setInputCloud (cloud_with_normals);
00973   PolygonMesh mesh;
00974   poisson.reconstruct (mesh);
00975 
00976 
00977 //  io::saveVTKFile ("bunny_poisson.vtk", mesh);
00978 
00979   ASSERT_EQ (mesh.polygons.size (), 1051);
00980   // All polygons should be triangles
00981   for (size_t i = 0; i < mesh.polygons.size (); ++i)
00982     EXPECT_EQ (mesh.polygons[i].vertices.size (), 3);
00983 
00984   EXPECT_EQ (mesh.polygons[10].vertices[0], 121);
00985   EXPECT_EQ (mesh.polygons[10].vertices[1], 120);
00986   EXPECT_EQ (mesh.polygons[10].vertices[2], 23);
00987 
00988   EXPECT_EQ (mesh.polygons[200].vertices[0], 130);
00989   EXPECT_EQ (mesh.polygons[200].vertices[1], 119);
00990   EXPECT_EQ (mesh.polygons[200].vertices[2], 131);
00991 
00992   EXPECT_EQ (mesh.polygons[1000].vertices[0], 521);
00993   EXPECT_EQ (mesh.polygons[1000].vertices[1], 516);
00994   EXPECT_EQ (mesh.polygons[1000].vertices[2], 517);
00995 }
00996 
00997 
00998 
00999 /* ---[ */
01000 int
01001 main (int argc, char** argv)
01002 {
01003   if (argc < 2)
01004   {
01005     std::cerr << "No test file given. Please download `bun0.pcd` and pass its path to the test." << std::endl;
01006     return (-1);
01007   }
01008 
01009   // Load file
01010   sensor_msgs::PointCloud2 cloud_blob;
01011   loadPCDFile (argv[1], cloud_blob);
01012   fromROSMsg (cloud_blob, *cloud);
01013 
01014   // Create search tree
01015   tree.reset (new search::KdTree<PointXYZ> (false));
01016   tree->setInputCloud (cloud);
01017 
01018   // Normal estimation
01019   NormalEstimation<PointXYZ, Normal> n;
01020   PointCloud<Normal>::Ptr normals (new PointCloud<Normal> ());
01021   n.setInputCloud (cloud);
01022   //n.setIndices (indices[B);
01023   n.setSearchMethod (tree);
01024   n.setKSearch (20);
01025   n.compute (*normals);
01026 
01027   // Concatenate XYZ and normal information
01028   pcl::concatenateFields (*cloud, *normals, *cloud_with_normals);
01029       
01030   // Create search tree
01031   tree2.reset (new search::KdTree<PointNormal>);
01032   tree2->setInputCloud (cloud_with_normals);
01033 
01034   // Process for update cloud
01035   if(argc == 3){
01036     sensor_msgs::PointCloud2 cloud_blob1;
01037     loadPCDFile (argv[2], cloud_blob1);
01038     fromROSMsg (cloud_blob1, *cloud1);
01039         // Create search tree
01040     tree3.reset (new search::KdTree<PointXYZ> (false));
01041     tree3->setInputCloud (cloud1);
01042 
01043     // Normal estimation
01044     NormalEstimation<PointXYZ, Normal> n1;
01045     PointCloud<Normal>::Ptr normals1 (new PointCloud<Normal> ());
01046     n1.setInputCloud (cloud1);
01047 
01048     n1.setSearchMethod (tree3);
01049     n1.setKSearch (20);
01050     n1.compute (*normals1);
01051 
01052     // Concatenate XYZ and normal information
01053     pcl::concatenateFields (*cloud1, *normals1, *cloud_with_normals1);
01054     // Create search tree
01055     tree4.reset (new search::KdTree<PointNormal>);
01056     tree4->setInputCloud (cloud_with_normals1);
01057   }
01058 
01059   // Testing
01060   testing::InitGoogleTest (&argc, argv);
01061   return (RUN_ALL_TESTS ());
01062 }
01063 /* ]--- */


pcl
Author(s): Open Perception
autogenerated on Mon Oct 6 2014 03:18:39