test_iss_3d.cpp
Go to the documentation of this file.
00001 /*
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2010, Willow Garage, Inc.
00005  *  All rights reserved.
00006  *
00007  *  Redistribution and use in source and binary forms, with or without
00008  *  modification, are permitted provided that the following conditions
00009  *  are met:
00010  *
00011  *   * Redistributions of source code must retain the above copyright
00012  *     notice, this list of conditions and the following disclaimer.
00013  *   * Redistributions in binary form must reproduce the above
00014  *     copyright notice, this list of conditions and the following
00015  *     disclaimer in the documentation and/or other materials provided
00016  *     with the distribution.
00017  *   * Neither the name of the copyright holder(s) nor the names of its
00018  *     contributors may be used to endorse or promote products derived
00019  *     from this software without specific prior written permission.
00020  *
00021  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032  *  POSSIBILITY OF SUCH DAMAGE.
00033  */
00034 
00037 #include <gtest/gtest.h>
00038 #include <pcl/pcl_tests.h>
00039 
00040 #include <pcl/io/pcd_io.h>
00041 #include <pcl/keypoints/iss_3d.h>
00042 
00043 using namespace pcl;
00044 using namespace pcl::io;
00045 
00046 //
00047 // Main variables
00048 //
00049 double cloud_resolution (0.0058329);
00050 PointCloud<PointXYZ>::Ptr cloud (new PointCloud<PointXYZ> ());
00051 search::KdTree<PointXYZ>::Ptr tree (new search::KdTree<PointXYZ> ());
00052 
00053 
00055 TEST (PCL, ISSKeypoint3D_WBE)
00056 {
00057   PointCloud<PointXYZ> keypoints;
00058 
00059   //
00060   // Compute the ISS 3D keypoints - Without Boundary Estimation
00061   //
00062   ISSKeypoint3D<PointXYZ, PointXYZ> iss_detector;
00063   iss_detector.setSearchMethod (tree);
00064   iss_detector.setSalientRadius (6 * cloud_resolution);
00065   iss_detector.setNonMaxRadius (4 * cloud_resolution);
00066 
00067   iss_detector.setThreshold21 (0.975);
00068   iss_detector.setThreshold32 (0.975);
00069   iss_detector.setMinNeighbors (5);
00070   iss_detector.setNumberOfThreads (1);
00071   iss_detector.setInputCloud (cloud);
00072   iss_detector.compute (keypoints);
00073 
00074   //
00075   // Compare to previously validated output
00076   //
00077   const size_t correct_nr_keypoints = 6;
00078   const float correct_keypoints[correct_nr_keypoints][3] =
00079     {
00080       // { x,  y,  z}
00081       {-0.071112f,  0.137670f,  0.047518f},
00082       {-0.041733f,  0.127960f,  0.016650f},
00083       {-0.011943f,  0.086771f,  0.057009f},
00084       { 0.031733f,  0.099372f,  0.038505f},
00085       {-0.062116f,  0.045145f,  0.037802f},
00086       {-0.048250f,  0.167480f, -0.000152f}
00087     };
00088 
00089 
00090   ASSERT_EQ (keypoints.points.size (), correct_nr_keypoints);
00091 
00092   for (size_t i = 0; i < correct_nr_keypoints; ++i)
00093   {
00094     EXPECT_NEAR (keypoints.points[i].x, correct_keypoints[i][0], 1e-6);
00095     EXPECT_NEAR (keypoints.points[i].y, correct_keypoints[i][1], 1e-6);
00096     EXPECT_NEAR (keypoints.points[i].z, correct_keypoints[i][2], 1e-6);
00097   }
00098 
00099   tree.reset (new search::KdTree<PointXYZ> ());
00100 }
00101 
00103 TEST (PCL, ISSKeypoint3D_BE)
00104 {
00105   PointCloud<PointXYZ> keypoints;
00106 
00107   //
00108   // Compute the ISS 3D keypoints - By first performing the Boundary Estimation
00109   //
00110 
00111   ISSKeypoint3D<PointXYZ, PointXYZ> iss_detector;
00112 
00113   iss_detector.setSearchMethod (tree);
00114   iss_detector.setSalientRadius (6 * cloud_resolution);
00115   iss_detector.setNonMaxRadius (4 * cloud_resolution);
00116 
00117   iss_detector.setNormalRadius (4 * cloud_resolution);
00118   iss_detector.setBorderRadius (4 * cloud_resolution);
00119 
00120   iss_detector.setThreshold21 (0.975);
00121   iss_detector.setThreshold32 (0.975);
00122   iss_detector.setMinNeighbors (5);
00123   iss_detector.setAngleThreshold (static_cast<float> (M_PI) / 3.0);
00124   iss_detector.setNumberOfThreads (1);
00125 
00126   iss_detector.setInputCloud (cloud);
00127   iss_detector.compute (keypoints);
00128 
00129 
00130   //
00131   // Compare to previously validated output
00132   //
00133   const size_t correct_nr_keypoints = 5;
00134   const float correct_keypoints[correct_nr_keypoints][3] =
00135     {
00136       // { x,  y,  z}
00137       {-0.052037f,  0.116800f,  0.034582f},
00138       { 0.027420f,  0.096386f,  0.043312f},
00139       {-0.011943f,  0.086771f,  0.057009f},
00140       {-0.070344f,  0.087352f,  0.041908f},
00141       {-0.030035f,  0.066130f,  0.038942f}
00142     };
00143 
00144   ASSERT_EQ (keypoints.points.size (), correct_nr_keypoints);
00145 
00146   for (size_t i = 0; i < correct_nr_keypoints; ++i)
00147   {
00148     EXPECT_NEAR (keypoints.points[i].x, correct_keypoints[i][0], 1e-6);
00149     EXPECT_NEAR (keypoints.points[i].y, correct_keypoints[i][1], 1e-6);
00150     EXPECT_NEAR (keypoints.points[i].z, correct_keypoints[i][2], 1e-6);
00151   }
00152 
00153   tree.reset (new search::KdTree<PointXYZ> ());
00154 }
00155 
00156 //* ---[ */
00157 int
00158 main (int argc, char** argv)
00159 {
00160   if (argc < 2)
00161   {
00162     std::cerr << "No test file given. Please download `bun0.pcd` and pass its path to the test." << std::endl;
00163     return (-1);
00164   }
00165 
00166   // Load a sample point cloud
00167   if (io::loadPCDFile (argv[1], *cloud) < 0)
00168   {
00169     std::cerr << "Failed to read test file. Please download `bun0.pcd` and pass its path to the test." << std::endl;
00170     return (-1);
00171   }
00172 
00173   testing::InitGoogleTest (&argc, argv);
00174   return (RUN_ALL_TESTS ());
00175 }
00176 /* ]--- */


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