test_boundary_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/boundary.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, BoundaryEstimation)
00058 {
00059   Eigen::Vector4f u = Eigen::Vector4f::Zero ();
00060   Eigen::Vector4f v = Eigen::Vector4f::Zero ();
00061 
00062   // Estimate normals first
00063   NormalEstimation<PointXYZ, Normal> n;
00064   PointCloud<Normal>::Ptr normals (new PointCloud<Normal> ());
00065   // set parameters
00066   n.setInputCloud (cloud.makeShared ());
00067   boost::shared_ptr<vector<int> > indicesptr (new vector<int> (indices));
00068   n.setIndices (indicesptr);
00069   n.setSearchMethod (tree);
00070   n.setKSearch (static_cast<int> (indices.size ()));
00071   // estimate
00072   n.compute (*normals);
00073 
00074   BoundaryEstimation<PointXYZ, Normal, Boundary> b;
00075   b.setInputNormals (normals);
00076   EXPECT_EQ (b.getInputNormals (), normals);
00077 
00078   // getCoordinateSystemOnPlane
00079   for (size_t i = 0; i < normals->points.size (); ++i)
00080   {
00081     b.getCoordinateSystemOnPlane (normals->points[i], u, v);
00082     Vector4fMap n4uv = normals->points[i].getNormalVector4fMap ();
00083     EXPECT_NEAR (n4uv.dot(u), 0, 1e-4);
00084     EXPECT_NEAR (n4uv.dot(v), 0, 1e-4);
00085     EXPECT_NEAR (u.dot(v), 0, 1e-4);
00086   }
00087 
00088   // isBoundaryPoint (indices)
00089   bool pt = false;
00090   pt = b.isBoundaryPoint (cloud, 0, indices, u, v, float (M_PI) / 2.0);
00091   EXPECT_EQ (pt, false);
00092   pt = b.isBoundaryPoint (cloud, static_cast<int> (indices.size ()) / 3, indices, u, v, float (M_PI) / 2.0);
00093   EXPECT_EQ (pt, false);
00094   pt = b.isBoundaryPoint (cloud, static_cast<int> (indices.size ()) / 2, indices, u, v, float (M_PI) / 2.0);
00095   EXPECT_EQ (pt, false);
00096   pt = b.isBoundaryPoint (cloud, static_cast<int> (indices.size ()) - 1, indices, u, v, float (M_PI) / 2.0);
00097   EXPECT_EQ (pt, true);
00098 
00099   // isBoundaryPoint (points)
00100   pt = false;
00101   pt = b.isBoundaryPoint (cloud, cloud.points[0], indices, u, v, float (M_PI) / 2.0);
00102   EXPECT_EQ (pt, false);
00103   pt = b.isBoundaryPoint (cloud, cloud.points[indices.size () / 3], indices, u, v, float (M_PI) / 2.0);
00104   EXPECT_EQ (pt, false);
00105   pt = b.isBoundaryPoint (cloud, cloud.points[indices.size () / 2], indices, u, v, float (M_PI) / 2.0);
00106   EXPECT_EQ (pt, false);
00107   pt = b.isBoundaryPoint (cloud, cloud.points[indices.size () - 1], indices, u, v, float (M_PI) / 2.0);
00108   EXPECT_EQ (pt, true);
00109 
00110   // Object
00111   PointCloud<Boundary>::Ptr bps (new PointCloud<Boundary> ());
00112 
00113   // set parameters
00114   b.setInputCloud (cloud.makeShared ());
00115   b.setIndices (indicesptr);
00116   b.setSearchMethod (tree);
00117   b.setKSearch (static_cast<int> (indices.size ()));
00118 
00119   // estimate
00120   b.compute (*bps);
00121   EXPECT_EQ (bps->points.size (), indices.size ());
00122 
00123   pt = bps->points[0].boundary_point;
00124   EXPECT_EQ (pt, false);
00125   pt = bps->points[indices.size () / 3].boundary_point;
00126   EXPECT_EQ (pt, false);
00127   pt = bps->points[indices.size () / 2].boundary_point;
00128   EXPECT_EQ (pt, false);
00129   pt = bps->points[indices.size () - 1].boundary_point;
00130   EXPECT_EQ (pt, true);
00131 }
00132 
00133 #ifndef PCL_ONLY_CORE_POINT_TYPES
00134 
00135   TEST (PCL, BoundaryEstimationEigen)
00136   {
00137     Eigen::Vector4f u = Eigen::Vector4f::Zero ();
00138     Eigen::Vector4f v = Eigen::Vector4f::Zero ();
00139 
00140     // Estimate normals first
00141     NormalEstimation<PointXYZ, Normal> n;
00142     PointCloud<Normal>::Ptr normals (new PointCloud<Normal>);
00143     // set parameters
00144     n.setInputCloud (cloud.makeShared ());
00145     boost::shared_ptr<vector<int> > indicesptr (new vector<int> (indices));
00146     n.setIndices (indicesptr);
00147     n.setSearchMethod (tree);
00148     n.setKSearch (static_cast<int> (indices.size ()));
00149     // estimate
00150     n.compute (*normals);
00151 
00152     BoundaryEstimation<PointXYZ, Normal, Eigen::MatrixXf> b;
00153     b.setInputNormals (normals);
00154     EXPECT_EQ (b.getInputNormals (), normals);
00155 
00156     // getCoordinateSystemOnPlane
00157     for (size_t i = 0; i < normals->points.size (); ++i)
00158     {
00159       b.getCoordinateSystemOnPlane (normals->points[i], u, v);
00160       Vector4fMap n4uv = normals->points[i].getNormalVector4fMap ();
00161       EXPECT_NEAR (n4uv.dot(u), 0, 1e-4);
00162       EXPECT_NEAR (n4uv.dot(v), 0, 1e-4);
00163       EXPECT_NEAR (u.dot(v), 0, 1e-4);
00164     }
00165 
00166     // isBoundaryPoint (indices)
00167     bool pt = false;
00168     pt = b.isBoundaryPoint (cloud, 0, indices, u, v, float (M_PI) / 2.0);
00169     EXPECT_EQ (pt, false);
00170     pt = b.isBoundaryPoint (cloud, static_cast<int> (indices.size () / 3), indices, u, v, float (M_PI) / 2.0);
00171     EXPECT_EQ (pt, false);
00172     pt = b.isBoundaryPoint (cloud, static_cast<int> (indices.size () / 2), indices, u, v, float (M_PI) / 2.0);
00173     EXPECT_EQ (pt, false);
00174     pt = b.isBoundaryPoint (cloud, static_cast<int> (indices.size () - 1), indices, u, v, float (M_PI) / 2.0);
00175     EXPECT_EQ (pt, true);
00176 
00177     // isBoundaryPoint (points)
00178     pt = false;
00179     pt = b.isBoundaryPoint (cloud, cloud.points[0], indices, u, v, float (M_PI) / 2.0);
00180     EXPECT_EQ (pt, false);
00181     pt = b.isBoundaryPoint (cloud, cloud.points[indices.size () / 3], indices, u, v, float (M_PI) / 2.0);
00182     EXPECT_EQ (pt, false);
00183     pt = b.isBoundaryPoint (cloud, cloud.points[indices.size () / 2], indices, u, v, float (M_PI) / 2.0);
00184     EXPECT_EQ (pt, false);
00185     pt = b.isBoundaryPoint (cloud, cloud.points[indices.size () - 1], indices, u, v, float (M_PI) / 2.0);
00186     EXPECT_EQ (pt, true);
00187 
00188     // Object
00189     PointCloud<Eigen::MatrixXf>::Ptr bps (new PointCloud<Eigen::MatrixXf> ());
00190 
00191     // set parameters
00192     b.setInputCloud (cloud.makeShared ());
00193     b.setIndices (indicesptr);
00194     b.setSearchMethod (tree);
00195     b.setKSearch (static_cast<int> (indices.size ()));
00196 
00197     // estimate
00198     b.computeEigen (*bps);
00199     EXPECT_EQ (bps->points.rows (), indices.size ());
00200 
00201     pt = bps->points (0, 0);
00202     EXPECT_EQ (pt, false);
00203     pt = bps->points (indices.size () / 3, 0);
00204     EXPECT_EQ (pt, false);
00205     pt = bps->points (indices.size () / 2, 0);
00206     EXPECT_EQ (pt, false);
00207     pt = bps->points (indices.size () - 1, 0);
00208     EXPECT_EQ (pt, true);
00209   }
00210 #endif
00211 
00212 /* ---[ */
00213 int
00214 main (int argc, char** argv)
00215 {
00216   if (argc < 2)
00217   {
00218     std::cerr << "No test file given. Please download `bun0.pcd` and pass its path to the test." << std::endl;
00219     return (-1);
00220   }
00221 
00222   if (loadPCDFile<PointXYZ> (argv[1], cloud) < 0)
00223   {
00224     std::cerr << "Failed to read test file. Please download `bun0.pcd` and pass its path to the test." << std::endl;
00225     return (-1);
00226   }
00227 
00228   indices.resize (cloud.points.size ());
00229   for (size_t i = 0; i < indices.size (); ++i)
00230     indices[i] = static_cast<int> (i);
00231 
00232   tree.reset (new search::KdTree<PointXYZ> (false));
00233   tree->setInputCloud (cloud.makeShared ());
00234 
00235   testing::InitGoogleTest (&argc, argv);
00236   return (RUN_ALL_TESTS ());
00237 }
00238 /* ]--- */


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