test_cvfh_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 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_pfh_estimation.cpp 4747 2012-02-26 20:51:51Z svn $
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/cvfh.h>
00044 #include <pcl/io/pcd_io.h>
00045 #include <pcl/filters/voxel_grid.h>
00046 
00047 using namespace pcl;
00048 using namespace pcl::io;
00049 using namespace std;
00050 
00051 typedef search::KdTree<PointXYZ>::Ptr KdTreePtr;
00052 typedef PointCloud<PointXYZ>::Ptr CloudPtr;
00053 
00054 PointCloud<PointXYZ> cloud;
00055 vector<int> indices;
00056 KdTreePtr tree;
00057 
00058 CloudPtr cloud_milk;
00059 KdTreePtr tree_milk;
00060 float leaf_size_ = 0.005f;
00061 
00063 TEST (PCL, CVFHEstimation)
00064 {
00065   // Estimate normals first
00066   NormalEstimation<PointXYZ, Normal> n;
00067   PointCloud<Normal>::Ptr normals (new PointCloud<Normal> ());
00068   // set parameters
00069   n.setInputCloud (cloud.makeShared ());
00070   boost::shared_ptr<vector<int> > indicesptr (new vector<int> (indices));
00071   n.setIndices (indicesptr);
00072   n.setSearchMethod (tree);
00073   n.setKSearch (10); // Use 10 nearest neighbors to estimate the normals
00074   // estimate
00075   n.compute (*normals);
00076   CVFHEstimation<PointXYZ, Normal, VFHSignature308> cvfh;
00077   cvfh.setInputNormals (normals);
00078 
00079   // Object
00080   PointCloud<VFHSignature308>::Ptr vfhs (new PointCloud<VFHSignature308> ());
00081 
00082   // set parameters
00083   cvfh.setInputCloud (cloud.makeShared ());
00084   cvfh.setIndices (indicesptr);
00085   cvfh.setSearchMethod (tree);
00086 
00087   // estimate
00088   cvfh.compute (*vfhs);
00089   EXPECT_EQ (static_cast<int>(vfhs->points.size ()), 1);
00090 }
00091 
00093 TEST (PCL, CVFHEstimationMilk)
00094 {
00095 
00096   // Estimate normals first
00097   NormalEstimation<PointXYZ, Normal> n;
00098   PointCloud<Normal>::Ptr normals (new PointCloud<Normal> ());
00099   n.setInputCloud (cloud_milk);
00100   n.setSearchMethod (tree);
00101   n.setRadiusSearch (leaf_size_ * 4); //2cm to estimate normals
00102   n.compute (*normals);
00103 
00104   CVFHEstimation<PointXYZ, Normal, VFHSignature308> cvfh;
00105   cvfh.setInputCloud (cloud_milk);
00106   cvfh.setInputNormals (normals);
00107   cvfh.setSearchMethod (tree_milk);
00108   cvfh.setClusterTolerance (leaf_size_ * 3);
00109   cvfh.setEPSAngleThreshold (0.13f);
00110   cvfh.setCurvatureThreshold (0.025f);
00111   cvfh.setNormalizeBins (false);
00112   cvfh.setRadiusNormals (leaf_size_ * 4);
00113 
00114   // Object
00115   PointCloud<VFHSignature308>::Ptr vfhs (new PointCloud<VFHSignature308> ());
00116 
00117   // estimate
00118   cvfh.compute (*vfhs);
00119   EXPECT_EQ (static_cast<int>(vfhs->points.size ()), 2);
00120 }
00121 
00122 /* ---[ */
00123 int
00124 main (int argc, char** argv)
00125 {
00126   if (argc < 3)
00127   {
00128     std::cerr << "No test file given. Please download `bun0.pcd` and `milk.pcd` pass its path to the test." << std::endl;
00129     return (-1);
00130   }
00131 
00132   if (loadPCDFile<PointXYZ> (argv[1], cloud) < 0)
00133   {
00134     std::cerr << "Failed to read test file. Please download `bun0.pcd` and pass its path to the test." << std::endl;
00135     return (-1);
00136   }
00137 
00138   CloudPtr milk_loaded(new PointCloud<PointXYZ>());
00139   if (loadPCDFile<PointXYZ> (argv[2], *milk_loaded) < 0)
00140   {
00141     std::cerr << "Failed to read test file. Please download `milk.pcd` and pass its path to the test." << std::endl;
00142     return (-1);
00143   }
00144 
00145   indices.resize (cloud.points.size ());
00146   for (size_t i = 0; i < indices.size (); ++i)
00147   {
00148     indices[i] = static_cast<int>(i);
00149   }
00150 
00151   tree.reset (new search::KdTree<PointXYZ> (false));
00152   tree->setInputCloud (cloud.makeShared ());
00153 
00154   cloud_milk.reset(new PointCloud<PointXYZ>());
00155   CloudPtr grid;
00156   pcl::VoxelGrid < pcl::PointXYZ > grid_;
00157   grid_.setInputCloud (milk_loaded);
00158   grid_.setLeafSize (leaf_size_, leaf_size_, leaf_size_);
00159   grid_.filter (*cloud_milk);
00160 
00161   tree_milk.reset (new search::KdTree<PointXYZ> (false));
00162   tree_milk->setInputCloud (cloud_milk);
00163 
00164   testing::InitGoogleTest (&argc, argv);
00165   return (RUN_ALL_TESTS ());
00166 }
00167 /* ]--- */


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