test_base_feature.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 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$
00037  *
00038  */
00039 
00040 #include <gtest/gtest.h>
00041 #include <pcl/point_cloud.h>
00042 #include <pcl/features/feature.h>
00043 #include <pcl/io/pcd_io.h>
00044 #include <pcl/common/centroid.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, BaseFeature)
00058 {
00059   // compute3DCentroid (indices)
00060   Eigen::Vector4f centroid3;
00061   compute3DCentroid (cloud, indices, centroid3);
00062   EXPECT_NEAR (centroid3[0], -0.0290809, 1e-4);
00063   EXPECT_NEAR (centroid3[1], 0.102653, 1e-4);
00064   EXPECT_NEAR (centroid3[2], 0.027302, 1e-4);
00065   EXPECT_NEAR (centroid3[3], 0, 1e-4);
00066 
00067   // compute3Dcentroid
00068   compute3DCentroid (cloud, centroid3);
00069   EXPECT_NEAR (centroid3[0], -0.0290809, 1e-4);
00070   EXPECT_NEAR (centroid3[1], 0.102653, 1e-4);
00071   EXPECT_NEAR (centroid3[2], 0.027302, 1e-4);
00072   EXPECT_NEAR (centroid3[3], 0, 1e-4);
00073 
00074   // computeNDCentroid (indices)
00075   Eigen::VectorXf centroidn;
00076   computeNDCentroid (cloud, indices, centroidn);
00077   EXPECT_NEAR (centroidn[0], -0.0290809, 1e-4);
00078   EXPECT_NEAR (centroidn[1], 0.102653, 1e-4);
00079   EXPECT_NEAR (centroidn[2], 0.027302, 1e-4);
00080 
00081   // computeNDCentroid
00082   computeNDCentroid (cloud, centroidn);
00083   EXPECT_NEAR (centroidn[0], -0.0290809, 1e-4);
00084   EXPECT_NEAR (centroidn[1], 0.102653, 1e-4);
00085   EXPECT_NEAR (centroidn[2], 0.027302, 1e-4);
00086 
00087   // computeCovarianceMatrix (indices)
00088   Eigen::Matrix3f covariance_matrix;
00089   computeCovarianceMatrix (cloud, indices, centroid3, covariance_matrix);
00090   EXPECT_NEAR (covariance_matrix (0, 0), 0.710046, 1e-4);
00091   EXPECT_NEAR (covariance_matrix (0, 1), -0.234843, 1e-4);
00092   EXPECT_NEAR (covariance_matrix (0, 2), 0.0704933, 1e-4);
00093   EXPECT_NEAR (covariance_matrix (1, 0), -0.234843, 1e-4);
00094   EXPECT_NEAR (covariance_matrix (1, 1), 0.68695, 1e-4);
00095   EXPECT_NEAR (covariance_matrix (1, 2), -0.220504, 1e-4);
00096   EXPECT_NEAR (covariance_matrix (2, 0), 0.0704933, 1e-4);
00097   EXPECT_NEAR (covariance_matrix (2, 1), -0.220504, 1e-4);
00098   EXPECT_NEAR (covariance_matrix (2, 2), 0.195448, 1e-4);
00099 
00100   // computeCovarianceMatrix
00101   computeCovarianceMatrix (cloud, centroid3, covariance_matrix);
00102   EXPECT_NEAR (covariance_matrix (0, 0), 0.710046, 1e-4);
00103   EXPECT_NEAR (covariance_matrix (0, 1), -0.234843, 1e-4);
00104   EXPECT_NEAR (covariance_matrix (0, 2), 0.0704933, 1e-4);
00105   EXPECT_NEAR (covariance_matrix (1, 0), -0.234843, 1e-4);
00106   EXPECT_NEAR (covariance_matrix (1, 1), 0.68695, 1e-4);
00107   EXPECT_NEAR (covariance_matrix (1, 2), -0.220504, 1e-4);
00108   EXPECT_NEAR (covariance_matrix (2, 0), 0.0704933, 1e-4);
00109   EXPECT_NEAR (covariance_matrix (2, 1), -0.220504, 1e-4);
00110   EXPECT_NEAR (covariance_matrix (2, 2), 0.195448, 1e-4);
00111 
00112   // computeCovarianceMatrixNormalized (indices)
00113   computeCovarianceMatrixNormalized (cloud, indices, centroid3, covariance_matrix);
00114   EXPECT_NEAR (covariance_matrix (0, 0), 1.7930e-03, 1e-5);
00115   EXPECT_NEAR (covariance_matrix (0, 1), -5.9304e-04, 1e-5);
00116   EXPECT_NEAR (covariance_matrix (0, 2), 1.7801e-04, 1e-5);
00117   EXPECT_NEAR (covariance_matrix (1, 0), -5.9304e-04, 1e-5);
00118   EXPECT_NEAR (covariance_matrix (1, 1), 1.7347e-03, 1e-5);
00119   EXPECT_NEAR (covariance_matrix (1, 2), -5.5683e-04, 1e-5);
00120   EXPECT_NEAR (covariance_matrix (2, 0), 1.7801e-04, 1e-5);
00121   EXPECT_NEAR (covariance_matrix (2, 1), -5.5683e-04, 1e-5);
00122   EXPECT_NEAR (covariance_matrix (2, 2), 4.9356e-04, 1e-5);
00123 
00124   // computeCovarianceMatrixNormalized
00125   computeCovarianceMatrixNormalized (cloud, centroid3, covariance_matrix);
00126   EXPECT_NEAR (covariance_matrix (0, 0), 1.7930e-03, 1e-5);
00127   EXPECT_NEAR (covariance_matrix (0, 1), -5.9304e-04, 1e-5);
00128   EXPECT_NEAR (covariance_matrix (0, 2), 1.7801e-04, 1e-5);
00129   EXPECT_NEAR (covariance_matrix (1, 0), -5.9304e-04, 1e-5);
00130   EXPECT_NEAR (covariance_matrix (1, 1), 1.7347e-03, 1e-5);
00131   EXPECT_NEAR (covariance_matrix (1, 2), -5.5683e-04, 1e-5);
00132   EXPECT_NEAR (covariance_matrix (2, 0), 1.7801e-04, 1e-5);
00133   EXPECT_NEAR (covariance_matrix (2, 1), -5.5683e-04, 1e-5);
00134   EXPECT_NEAR (covariance_matrix (2, 2), 4.9356e-04, 1e-5);
00135 
00136   // solvePlaneParameters (Vector)
00137   Eigen::Vector4f plane_parameters;
00138   float curvature;
00139   solvePlaneParameters (covariance_matrix, centroid3, plane_parameters, curvature);
00140   EXPECT_NEAR (fabs (plane_parameters[0]), 0.035592, 1e-4);
00141   EXPECT_NEAR (fabs (plane_parameters[1]), 0.369596, 1e-4);
00142   EXPECT_NEAR (fabs (plane_parameters[2]), 0.928511, 1e-4);
00143   EXPECT_NEAR (fabs (plane_parameters[3]), 0.0622552, 1e-4);
00144   EXPECT_NEAR (curvature, 0.0693136, 1e-4);
00145 
00146   // solvePlaneParameters
00147   float nx, ny, nz;
00148   solvePlaneParameters (covariance_matrix, nx, ny, nz, curvature);
00149   EXPECT_NEAR (fabs (nx), 0.035592, 1e-4);
00150   EXPECT_NEAR (fabs (ny), 0.369596, 1e-4);
00151   EXPECT_NEAR (fabs (nz), 0.928511, 1e-4);
00152   EXPECT_NEAR (curvature, 0.0693136, 1e-4);
00153 }
00154 
00155 /* ---[ */
00156 int
00157 main (int argc, char** argv)
00158 {
00159   if (argc < 2)
00160   {
00161     std::cerr << "No test file given. Please download `bun0.pcd` and pass its path to the test." << std::endl;
00162     return (-1);
00163   }
00164 
00165   if (loadPCDFile<PointXYZ> (argv[1], cloud) < 0)
00166   {
00167     std::cerr << "Failed to read test file. Please download `bun0.pcd` and pass its path to the test." << std::endl;
00168     return (-1);
00169   }
00170 
00171   indices.resize (cloud.points.size ());
00172   for (size_t i = 0; i < indices.size (); ++i)
00173     indices[i] = static_cast<int> (i);
00174 
00175   tree.reset (new search::KdTree<PointXYZ> (false));
00176   tree->setInputCloud (cloud.makeShared ());
00177 
00178   testing::InitGoogleTest (&argc, argv);
00179   return (RUN_ALL_TESTS ());
00180 }
00181 /* ]--- */


pcl
Author(s): Open Perception
autogenerated on Wed Aug 26 2015 15:34:22