test_moving_least_squares.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/mls.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, MovingLeastSquares)
00066 {
00067   // Init objects
00068   PointCloud<PointXYZ> mls_points;
00069   PointCloud<PointNormal>::Ptr mls_normals (new PointCloud<PointNormal> ());
00070   MovingLeastSquares<PointXYZ, PointNormal> mls;
00071 
00072   // Set parameters
00073   mls.setInputCloud (cloud);
00074   mls.setComputeNormals (true);
00075   mls.setPolynomialFit (true);
00076   mls.setSearchMethod (tree);
00077   mls.setSearchRadius (0.03);
00078 
00079   // Reconstruct
00080   mls.process (*mls_normals);
00081 
00082   EXPECT_NEAR (mls_normals->points[0].x, 0.005417, 1e-3);
00083   EXPECT_NEAR (mls_normals->points[0].y, 0.113463, 1e-3);
00084   EXPECT_NEAR (mls_normals->points[0].z, 0.040715, 1e-3);
00085   EXPECT_NEAR (fabs (mls_normals->points[0].normal[0]), 0.111894, 1e-3);
00086   EXPECT_NEAR (fabs (mls_normals->points[0].normal[1]), 0.594906, 1e-3);
00087   EXPECT_NEAR (fabs (mls_normals->points[0].normal[2]), 0.795969, 1e-3);
00088   EXPECT_NEAR (mls_normals->points[0].curvature, 0.012019, 1e-3);
00089 
00090 #ifdef _OPENMP
00091   // Testing OpenMP version
00092   MovingLeastSquaresOMP<PointXYZ, PointNormal> mls_omp;
00093   mls_omp.setInputCloud (cloud);
00094   mls_omp.setComputeNormals (true);
00095   mls_omp.setPolynomialFit (true);
00096   mls_omp.setSearchMethod (tree);
00097   mls_omp.setSearchRadius (0.03);
00098   mls_omp.setNumberOfThreads (4);
00099 
00100   // Reconstruct
00101   mls_normals->clear ();
00102   mls_omp.process (*mls_normals);
00103 
00104   int count = 0;
00105   for (size_t i = 0; i < mls_normals->size (); ++i)
00106   {
00107         if (fabs (mls_normals->points[i].x - 0.005417) < 1e-3 &&
00108             fabs (mls_normals->points[i].y - 0.113463) < 1e-3 &&
00109             fabs (mls_normals->points[i].z - 0.040715) < 1e-3 &&
00110             fabs (fabs (mls_normals->points[i].normal[0]) - 0.111894) < 1e-3 &&
00111                 fabs (fabs (mls_normals->points[i].normal[1]) - 0.594906) < 1e-3 &&
00112                 fabs (fabs (mls_normals->points[i].normal[2]) - 0.795969) < 1e-3 &&
00113                 fabs (mls_normals->points[i].curvature - 0.012019) < 1e-3)
00114                 count ++;
00115   }
00116 
00117   EXPECT_EQ (count, 1);
00118 
00119 #endif
00120 
00121   // Testing upsampling
00122   MovingLeastSquares<PointXYZ, PointNormal> mls_upsampling;
00123   // Set parameters
00124   mls_upsampling.setInputCloud (cloud);
00125   mls_upsampling.setComputeNormals (true);
00126   mls_upsampling.setPolynomialFit (true);
00127   mls_upsampling.setSearchMethod (tree);
00128   mls_upsampling.setSearchRadius (0.03);
00129   mls_upsampling.setUpsamplingMethod (MovingLeastSquares<PointXYZ, PointNormal>::SAMPLE_LOCAL_PLANE);
00130   mls_upsampling.setUpsamplingRadius (0.025);
00131   mls_upsampling.setUpsamplingStepSize (0.01);
00132 
00133   mls_normals->clear ();
00134   mls_upsampling.process (*mls_normals);
00135 
00136   EXPECT_NEAR (mls_normals->points[10].x, -0.000538, 1e-3);
00137   EXPECT_NEAR (mls_normals->points[10].y, 0.110080, 1e-3);
00138   EXPECT_NEAR (mls_normals->points[10].z, 0.043602, 1e-3);
00139   EXPECT_NEAR (fabs (mls_normals->points[10].normal[0]), 0.022678, 1e-3);
00140   EXPECT_NEAR (fabs (mls_normals->points[10].normal[1]), 0.554978, 1e-3);
00141   EXPECT_NEAR (fabs (mls_normals->points[10].normal[2]), 0.831556, 1e-3);
00142   EXPECT_NEAR (mls_normals->points[10].curvature, 0.012019, 1e-3);
00143   EXPECT_EQ (mls_normals->size (), 6352);
00144 
00145 
00149 //  mls_upsampling.setUpsamplingMethod (MovingLeastSquares<PointXYZ, PointNormal>::RANDOM_UNIFORM_DENSITY);
00150 //  mls_upsampling.setPointDensity (100);
00151 //  mls_normals->clear ();
00152 //  mls_upsampling.process (*mls_normals);
00153 //
00154 //  EXPECT_NEAR (mls_normals->points[10].x, 0.018806, 1e-3);
00155 //  EXPECT_NEAR (mls_normals->points[10].y, 0.114685, 1e-3);
00156 //  EXPECT_NEAR (mls_normals->points[10].z, 0.037500, 1e-3);
00157 //  EXPECT_NEAR (fabs (mls_normals->points[10].normal[0]), 0.351352, 1e-3);
00158 //  EXPECT_NEAR (fabs (mls_normals->points[10].normal[1]), 0.537741, 1e-3);
00159 //  EXPECT_NEAR (fabs (mls_normals->points[10].normal[2]), 0.766411, 1e-3);
00160 //  EXPECT_NEAR (mls_normals->points[10].curvature, 0.019003, 1e-3);
00161 //  EXPECT_EQ (mls_normals->size (), 457);
00162 
00163 
00164   mls_upsampling.setUpsamplingMethod (MovingLeastSquares<PointXYZ, PointNormal>::VOXEL_GRID_DILATION);
00165   mls_upsampling.setDilationIterations (5);
00166   mls_upsampling.setDilationVoxelSize (0.005f);
00167   mls_normals->clear ();
00168   mls_upsampling.process (*mls_normals);
00169   EXPECT_NEAR (mls_normals->points[10].x, -0.070005938410758972, 2e-3);
00170   EXPECT_NEAR (mls_normals->points[10].y, 0.028887597844004631, 2e-3);
00171   EXPECT_NEAR (mls_normals->points[10].z, 0.01788550429046154, 2e-3);
00172   EXPECT_NEAR (mls_normals->points[10].curvature, 0.107273, 1e-1);
00173   EXPECT_NEAR (double (mls_normals->size ()), 29394, 2);
00174 }
00175 
00176 /* ---[ */
00177 int
00178 main (int argc, char** argv)
00179 {
00180   if (argc < 2)
00181   {
00182     std::cerr << "No test file given. Please download `bun0.pcd` and pass its path to the test." << std::endl;
00183     return (-1);
00184   }
00185 
00186   // Load file
00187   pcl::PCLPointCloud2 cloud_blob;
00188   loadPCDFile (argv[1], cloud_blob);
00189   fromPCLPointCloud2 (cloud_blob, *cloud);
00190 
00191   // Create search tree
00192   tree.reset (new search::KdTree<PointXYZ> (false));
00193   tree->setInputCloud (cloud);
00194 
00195   // Normal estimation
00196   NormalEstimation<PointXYZ, Normal> n;
00197   PointCloud<Normal>::Ptr normals (new PointCloud<Normal> ());
00198   n.setInputCloud (cloud);
00199   //n.setIndices (indices[B);
00200   n.setSearchMethod (tree);
00201   n.setKSearch (20);
00202   n.compute (*normals);
00203 
00204   // Concatenate XYZ and normal information
00205   pcl::concatenateFields (*cloud, *normals, *cloud_with_normals);
00206       
00207   // Create search tree
00208   tree2.reset (new search::KdTree<PointNormal>);
00209   tree2->setInputCloud (cloud_with_normals);
00210 
00211   // Process for update cloud
00212   if(argc == 3){
00213     pcl::PCLPointCloud2 cloud_blob1;
00214     loadPCDFile (argv[2], cloud_blob1);
00215     fromPCLPointCloud2 (cloud_blob1, *cloud1);
00216         // Create search tree
00217     tree3.reset (new search::KdTree<PointXYZ> (false));
00218     tree3->setInputCloud (cloud1);
00219 
00220     // Normal estimation
00221     NormalEstimation<PointXYZ, Normal> n1;
00222     PointCloud<Normal>::Ptr normals1 (new PointCloud<Normal> ());
00223     n1.setInputCloud (cloud1);
00224 
00225     n1.setSearchMethod (tree3);
00226     n1.setKSearch (20);
00227     n1.compute (*normals1);
00228 
00229     // Concatenate XYZ and normal information
00230     pcl::concatenateFields (*cloud1, *normals1, *cloud_with_normals1);
00231     // Create search tree
00232     tree4.reset (new search::KdTree<PointNormal>);
00233     tree4->setInputCloud (cloud_with_normals1);
00234   }
00235 
00236   // Testing
00237   testing::InitGoogleTest (&argc, argv);
00238   return (RUN_ALL_TESTS ());
00239 }
00240 /* ]--- */


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