test_organized_fast_mesh.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) 2012-, Open Perception, 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 the copyright holder(s) 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  *
00023  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
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 6579 2012-07-27 18:57:32Z rusu $
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/organized_fast_mesh.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 // add by ktran to test update functions
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, Organized)
00066 {
00067   //construct dataset
00068   pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_organized (new pcl::PointCloud<pcl::PointXYZ> ());
00069   cloud_organized->width = 5;
00070   cloud_organized->height = 10;
00071   cloud_organized->points.resize (cloud_organized->width * cloud_organized->height);
00072 
00073   int npoints = 0;
00074   for (size_t i = 0; i < cloud_organized->height; i++)
00075   {
00076     for (size_t j = 0; j < cloud_organized->width; j++)
00077     {
00078       cloud_organized->points[npoints].x = static_cast<float> (i);
00079       cloud_organized->points[npoints].y = static_cast<float> (j);
00080       cloud_organized->points[npoints].z = static_cast<float> (cloud_organized->points.size ()); // to avoid shadowing
00081       npoints++;
00082     }
00083   }
00084   int nan_idx = cloud_organized->width*cloud_organized->height - 2*cloud_organized->width + 1;
00085   cloud_organized->points[nan_idx].x = numeric_limits<float>::quiet_NaN ();
00086   cloud_organized->points[nan_idx].y = numeric_limits<float>::quiet_NaN ();
00087   cloud_organized->points[nan_idx].z = numeric_limits<float>::quiet_NaN ();
00088   
00089   // Init objects
00090   PolygonMesh triangles;
00091   OrganizedFastMesh<PointXYZ> ofm;
00092 
00093   // Set parameters
00094   ofm.setInputCloud (cloud_organized);
00095   ofm.setMaxEdgeLength (1.5);
00096   ofm.setTrianglePixelSize (1);
00097   ofm.setTriangulationType (OrganizedFastMesh<PointXYZ>::TRIANGLE_ADAPTIVE_CUT);
00098 
00099   // Reconstruct
00100   ofm.reconstruct (triangles);
00101   //saveVTKFile ("./test/organized.vtk", triangles);
00102 
00103   // Check triangles
00104   EXPECT_EQ (triangles.cloud.width, cloud_organized->width);
00105   EXPECT_EQ (triangles.cloud.height, cloud_organized->height);
00106   EXPECT_EQ (int (triangles.polygons.size ()), 2*(triangles.cloud.width-1)*(triangles.cloud.height-1) - 4);
00107   EXPECT_EQ (int (triangles.polygons.at (0).vertices.size ()), 3);
00108   EXPECT_EQ (int (triangles.polygons.at (0).vertices.at (0)), 0);
00109   EXPECT_EQ (int (triangles.polygons.at (0).vertices.at (1)), triangles.cloud.width+1);
00110   EXPECT_EQ (int (triangles.polygons.at (0).vertices.at (2)), 1);
00111 }
00112 
00113 /* ---[ */
00114 int
00115 main (int argc, char** argv)
00116 {
00117   if (argc < 2)
00118   {
00119     std::cerr << "No test file given. Please download `bun0.pcd` and pass its path to the test." << std::endl;
00120     return (-1);
00121   }
00122 
00123   // Load file
00124   pcl::PCLPointCloud2 cloud_blob;
00125   loadPCDFile (argv[1], cloud_blob);
00126   fromPCLPointCloud2 (cloud_blob, *cloud);
00127 
00128   // Create search tree
00129   tree.reset (new search::KdTree<PointXYZ> (false));
00130   tree->setInputCloud (cloud);
00131 
00132   // Normal estimation
00133   NormalEstimation<PointXYZ, Normal> n;
00134   PointCloud<Normal>::Ptr normals (new PointCloud<Normal> ());
00135   n.setInputCloud (cloud);
00136   //n.setIndices (indices[B);
00137   n.setSearchMethod (tree);
00138   n.setKSearch (20);
00139   n.compute (*normals);
00140 
00141   // Concatenate XYZ and normal information
00142   pcl::concatenateFields (*cloud, *normals, *cloud_with_normals);
00143       
00144   // Create search tree
00145   tree2.reset (new search::KdTree<PointNormal>);
00146   tree2->setInputCloud (cloud_with_normals);
00147 
00148   // Process for update cloud
00149   if(argc == 3){
00150     pcl::PCLPointCloud2 cloud_blob1;
00151     loadPCDFile (argv[2], cloud_blob1);
00152     fromPCLPointCloud2 (cloud_blob1, *cloud1);
00153         // Create search tree
00154     tree3.reset (new search::KdTree<PointXYZ> (false));
00155     tree3->setInputCloud (cloud1);
00156 
00157     // Normal estimation
00158     NormalEstimation<PointXYZ, Normal> n1;
00159     PointCloud<Normal>::Ptr normals1 (new PointCloud<Normal> ());
00160     n1.setInputCloud (cloud1);
00161 
00162     n1.setSearchMethod (tree3);
00163     n1.setKSearch (20);
00164     n1.compute (*normals1);
00165 
00166     // Concatenate XYZ and normal information
00167     pcl::concatenateFields (*cloud1, *normals1, *cloud_with_normals1);
00168     // Create search tree
00169     tree4.reset (new search::KdTree<PointNormal>);
00170     tree4->setInputCloud (cloud_with_normals1);
00171   }
00172 
00173   // Testing
00174   testing::InitGoogleTest (&argc, argv);
00175   return (RUN_ALL_TESTS ());
00176 }
00177 /* ]--- */


pcl
Author(s): Open Perception
autogenerated on Wed Aug 26 2015 15:35:21