test_curvatures_estimation.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) 2010-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  *
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$
00037  *
00038  */
00039 
00040 #include <gtest/gtest.h>
00041 #include <pcl/point_cloud.h>
00042 #include <pcl/features/normal_3d.h>
00043 #include <pcl/features/principal_curvatures.h>
00044 #include <pcl/io/pcd_io.h>
00045 
00046 using namespace pcl;
00047 using namespace pcl::io;
00048 using namespace std;
00049 
00050 typedef search::KdTree<PointXYZ>::Ptr KdTreePtr;
00051 
00052 PointCloud<PointXYZ> cloud;
00053 vector<int> indices;
00054 KdTreePtr tree;
00055 
00057 TEST (PCL, PrincipalCurvaturesEstimation)
00058 {
00059   float pcx, pcy, pcz, pc1, pc2;
00060 
00061   // Estimate normals first
00062   NormalEstimation<PointXYZ, Normal> n;
00063   PointCloud<Normal>::Ptr normals (new PointCloud<Normal> ());
00064   // set parameters
00065   n.setInputCloud (cloud.makeShared ());
00066   boost::shared_ptr<vector<int> > indicesptr (new vector<int> (indices));
00067   n.setIndices (indicesptr);
00068   n.setSearchMethod (tree);
00069   n.setKSearch (10); // Use 10 nearest neighbors to estimate the normals
00070   // estimate
00071   n.compute (*normals);
00072 
00073   PrincipalCurvaturesEstimation<PointXYZ, Normal, PrincipalCurvatures> pc;
00074   pc.setInputNormals (normals);
00075   EXPECT_EQ (pc.getInputNormals (), normals);
00076 
00077   // computePointPrincipalCurvatures (indices)
00078   pc.computePointPrincipalCurvatures (*normals, 0, indices, pcx, pcy, pcz, pc1, pc2);
00079   EXPECT_NEAR (fabs (pcx), 0.98509, 1e-4);
00080   EXPECT_NEAR (fabs (pcy), 0.10714, 1e-4);
00081   EXPECT_NEAR (fabs (pcz), 0.13462, 1e-4);
00082   EXPECT_NEAR (pc1, 0.23997423052787781, 1e-4);
00083   EXPECT_NEAR (pc2, 0.19400238990783691, 1e-4);
00084 
00085   pc.computePointPrincipalCurvatures (*normals, 2, indices, pcx, pcy, pcz, pc1, pc2);
00086   EXPECT_NEAR (pcx, 0.98079, 1e-4);
00087   EXPECT_NEAR (pcy, -0.04019, 1e-4);
00088   EXPECT_NEAR (pcz, 0.19086, 1e-4);
00089   EXPECT_NEAR (pc1, 0.27207490801811218, 1e-4);
00090   EXPECT_NEAR (pc2, 0.19464978575706482, 1e-4);
00091 
00092   int indices_size = static_cast<int> (indices.size ());
00093   pc.computePointPrincipalCurvatures (*normals, indices_size - 3, indices, pcx, pcy, pcz, pc1, pc2);
00094   EXPECT_NEAR (pcx, 0.86725, 1e-4);
00095   EXPECT_NEAR (pcy, -0.37599, 1e-4);
00096   EXPECT_NEAR (pcz, 0.32635, 1e-4);
00097   EXPECT_NEAR (pc1, 0.25900053977966309, 1e-4);
00098   EXPECT_NEAR (pc2, 0.17906945943832397, 1e-4);
00099 
00100   pc.computePointPrincipalCurvatures (*normals, indices_size - 1, indices, pcx, pcy, pcz, pc1, pc2);
00101   EXPECT_NEAR (pcx, 0.86725, 1e-4);
00102   EXPECT_NEAR (pcy, -0.375851, 1e-3);
00103   EXPECT_NEAR (pcz, 0.32636, 1e-4);
00104   EXPECT_NEAR (pc1, 0.2590005099773407,  1e-4);
00105   EXPECT_NEAR (pc2, 0.17906956374645233, 1e-4);
00106 
00107   // Object
00108   PointCloud<PrincipalCurvatures>::Ptr pcs (new PointCloud<PrincipalCurvatures> ());
00109 
00110   // set parameters
00111   pc.setInputCloud (cloud.makeShared ());
00112   pc.setIndices (indicesptr);
00113   pc.setSearchMethod (tree);
00114   pc.setKSearch (indices_size);
00115 
00116   // estimate
00117   pc.compute (*pcs);
00118   EXPECT_EQ (pcs->points.size (), indices.size ());
00119 
00120   // Adjust for small numerical inconsitencies (due to nn_indices not being sorted)
00121   EXPECT_NEAR (fabs (pcs->points[0].principal_curvature[0]), 0.98509, 1e-4);
00122   EXPECT_NEAR (fabs (pcs->points[0].principal_curvature[1]), 0.10713, 1e-4);
00123   EXPECT_NEAR (fabs (pcs->points[0].principal_curvature[2]), 0.13462, 1e-4);
00124   EXPECT_NEAR (fabs (pcs->points[0].pc1), 0.23997458815574646, 1e-4);
00125   EXPECT_NEAR (fabs (pcs->points[0].pc2), 0.19400238990783691, 1e-4);
00126 
00127   EXPECT_NEAR (pcs->points[2].principal_curvature[0], 0.98079, 1e-4);
00128   EXPECT_NEAR (pcs->points[2].principal_curvature[1], -0.04019, 1e-4);
00129   EXPECT_NEAR (pcs->points[2].principal_curvature[2], 0.19086, 1e-4);
00130   EXPECT_NEAR (pcs->points[2].pc1, 0.27207502722740173, 1e-4);
00131   EXPECT_NEAR (pcs->points[2].pc2, 0.1946497857570648,  1e-4);
00132 
00133   EXPECT_NEAR (pcs->points[indices.size () - 3].principal_curvature[0], 0.86725, 1e-4);
00134   EXPECT_NEAR (pcs->points[indices.size () - 3].principal_curvature[1], -0.37599, 1e-4);
00135   EXPECT_NEAR (pcs->points[indices.size () - 3].principal_curvature[2], 0.32636, 1e-4);
00136   EXPECT_NEAR (pcs->points[indices.size () - 3].pc1, 0.2590007483959198,  1e-4);
00137   EXPECT_NEAR (pcs->points[indices.size () - 3].pc2, 0.17906941473484039, 1e-4);
00138 
00139   EXPECT_NEAR (pcs->points[indices.size () - 1].principal_curvature[0], 0.86725, 1e-4);
00140   EXPECT_NEAR (pcs->points[indices.size () - 1].principal_curvature[1], -0.375851, 1e-3);
00141   EXPECT_NEAR (pcs->points[indices.size () - 1].principal_curvature[2], 0.32636, 1e-4);
00142   EXPECT_NEAR (pcs->points[indices.size () - 1].pc1, 0.25900065898895264, 1e-4);
00143   EXPECT_NEAR (pcs->points[indices.size () - 1].pc2, 0.17906941473484039, 1e-4);
00144 }
00145 
00146 #ifndef PCL_ONLY_CORE_POINT_TYPES
00147 
00148   TEST (PCL, PrincipalCurvaturesEstimationEigen)
00149   {
00150     float pcx, pcy, pcz, pc1, pc2;
00151 
00152     // Estimate normals first
00153     NormalEstimation<PointXYZ, Normal> n;
00154     PointCloud<Normal>::Ptr normals (new PointCloud<Normal> ());
00155     // set parameters
00156     n.setInputCloud (cloud.makeShared ());
00157     boost::shared_ptr<vector<int> > indicesptr (new vector<int> (indices));
00158     n.setIndices (indicesptr);
00159     n.setSearchMethod (tree);
00160     n.setKSearch (10); // Use 10 nearest neighbors to estimate the normals
00161     // estimate
00162     n.compute (*normals);
00163 
00164     PrincipalCurvaturesEstimation<PointXYZ, Normal, Eigen::MatrixXf> pc;
00165     pc.setInputNormals (normals);
00166     EXPECT_EQ (pc.getInputNormals (), normals);
00167 
00168     // computePointPrincipalCurvatures (indices)
00169     pc.computePointPrincipalCurvatures (*normals, 0, indices, pcx, pcy, pcz, pc1, pc2);
00170     EXPECT_NEAR (fabs (pcx), 0.98509, 1e-4);
00171     EXPECT_NEAR (fabs (pcy), 0.10714, 1e-4);
00172     EXPECT_NEAR (fabs (pcz), 0.13462, 1e-4);
00173     EXPECT_NEAR (pc1, 0.23997423052787781, 1e-4);
00174     EXPECT_NEAR (pc2, 0.19400238990783691, 1e-4);
00175 
00176     pc.computePointPrincipalCurvatures (*normals, 2, indices, pcx, pcy, pcz, pc1, pc2);
00177     EXPECT_NEAR (pcx, 0.98079, 1e-4);
00178     EXPECT_NEAR (pcy, -0.04019, 1e-4);
00179     EXPECT_NEAR (pcz, 0.19086, 1e-4);
00180     EXPECT_NEAR (pc1, 0.27207490801811218, 1e-4);
00181     EXPECT_NEAR (pc2, 0.19464978575706482, 1e-4);
00182 
00183     int indices_size = static_cast<int> (indices.size ());
00184     pc.computePointPrincipalCurvatures (*normals, indices_size - 3, indices, pcx, pcy, pcz, pc1, pc2);
00185     EXPECT_NEAR (pcx, 0.86725, 1e-4);
00186     EXPECT_NEAR (pcy, -0.37599, 1e-4);
00187     EXPECT_NEAR (pcz, 0.32635, 1e-4);
00188     EXPECT_NEAR (pc1, 0.25900053977966309, 1e-4);
00189     EXPECT_NEAR (pc2, 0.17906945943832397, 1e-4);
00190 
00191     pc.computePointPrincipalCurvatures (*normals, indices_size - 1, indices, pcx, pcy, pcz, pc1, pc2);
00192     EXPECT_NEAR (pcx, 0.86725, 1e-4);
00193     EXPECT_NEAR (pcy, -0.375851, 1e-3);
00194     EXPECT_NEAR (pcz, 0.32636, 1e-4);
00195     EXPECT_NEAR (pc1, 0.2590005099773407,  1e-4);
00196     EXPECT_NEAR (pc2, 0.17906956374645233, 1e-4);
00197 
00198     // Object
00199     PointCloud<Eigen::MatrixXf>::Ptr pcs (new PointCloud<Eigen::MatrixXf>);
00200 
00201     // set parameters
00202     pc.setInputCloud (cloud.makeShared ());
00203     pc.setIndices (indicesptr);
00204     pc.setSearchMethod (tree);
00205     pc.setKSearch (indices_size);
00206 
00207     // estimate
00208     pc.computeEigen (*pcs);
00209     EXPECT_EQ (pcs->points.rows (), indices.size ());
00210 
00211     // Adjust for small numerical inconsitencies (due to nn_indices not being sorted)
00212     EXPECT_NEAR (fabs (pcs->points (0, 0)), 0.98509, 1e-4);
00213     EXPECT_NEAR (fabs (pcs->points (0, 1)), 0.10713, 1e-4);
00214     EXPECT_NEAR (fabs (pcs->points (0, 2)), 0.13462, 1e-4);
00215     EXPECT_NEAR (fabs (pcs->points (0, 3)), 0.23997458815574646, 1e-4);
00216     EXPECT_NEAR (fabs (pcs->points (0, 4)), 0.19400238990783691, 1e-4);
00217 
00218     EXPECT_NEAR (pcs->points (2, 0), 0.98079, 1e-4);
00219     EXPECT_NEAR (pcs->points (2, 1), -0.04019, 1e-4);
00220     EXPECT_NEAR (pcs->points (2, 2), 0.19086, 1e-4);
00221     EXPECT_NEAR (pcs->points (2, 3), 0.27207502722740173, 1e-4);
00222     EXPECT_NEAR (pcs->points (2, 4), 0.1946497857570648,  1e-4);
00223 
00224     EXPECT_NEAR (pcs->points (indices.size () - 3, 0), 0.86725, 1e-4);
00225     EXPECT_NEAR (pcs->points (indices.size () - 3, 1), -0.37599, 1e-4);
00226     EXPECT_NEAR (pcs->points (indices.size () - 3, 2), 0.32636, 1e-4);
00227     EXPECT_NEAR (pcs->points (indices.size () - 3, 3), 0.2590007483959198,  1e-4);
00228     EXPECT_NEAR (pcs->points (indices.size () - 3, 4), 0.17906941473484039, 1e-4);
00229 
00230     EXPECT_NEAR (pcs->points (indices.size () - 1, 0), 0.86725, 1e-4);
00231     EXPECT_NEAR (pcs->points (indices.size () - 1, 1), -0.375851, 1e-3);
00232     EXPECT_NEAR (pcs->points (indices.size () - 1, 2), 0.32636, 1e-4);
00233     EXPECT_NEAR (pcs->points (indices.size () - 1, 3), 0.25900065898895264, 1e-4);
00234     EXPECT_NEAR (pcs->points (indices.size () - 1, 4), 0.17906941473484039, 1e-4);
00235   }
00236 #endif
00237 
00238 /* ---[ */
00239 int
00240 main (int argc, char** argv)
00241 {
00242   if (argc < 2)
00243   {
00244     std::cerr << "No test file given. Please download `bun0.pcd` and pass its path to the test." << std::endl;
00245     return (-1);
00246   }
00247 
00248   if (loadPCDFile<PointXYZ> (argv[1], cloud) < 0)
00249   {
00250     std::cerr << "Failed to read test file. Please download `bun0.pcd` and pass its path to the test." << std::endl;
00251     return (-1);
00252   }
00253 
00254   indices.resize (cloud.points.size ());
00255   for (size_t i = 0; i < indices.size (); ++i)
00256     indices[i] = static_cast<int> (i);
00257 
00258   tree.reset (new search::KdTree<PointXYZ> (false));
00259   tree->setInputCloud (cloud.makeShared ());
00260 
00261   testing::InitGoogleTest (&argc, argv);
00262   return (RUN_ALL_TESTS ());
00263 }
00264 /* ]--- */


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