test_recognition_ism.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/kdtree/kdtree_flann.h>
00042 #include <pcl/point_types.h>
00043 #include <pcl/point_cloud.h>
00044 #include <pcl/io/pcd_io.h>
00045 #include <pcl/search/search.h>
00046 #include <pcl/features/normal_3d.h>
00047 #include <pcl/features/feature.h>
00048 #include <pcl/features/fpfh.h>
00049 #include <pcl/features/impl/fpfh.hpp>
00050 #include <pcl/recognition/implicit_shape_model.h>
00051 #include <pcl/recognition/impl/implicit_shape_model.hpp>
00052 
00053 pcl::PointCloud<pcl::PointXYZ>::Ptr training_cloud;
00054 pcl::PointCloud<pcl::PointXYZ>::Ptr testing_cloud;
00055 pcl::PointCloud<pcl::Normal>::Ptr training_normals;
00056 pcl::PointCloud<pcl::Normal>::Ptr testing_normals;
00057 
00059 TEST (ISM, TrainRecognize)
00060 {
00061   std::vector<pcl::PointCloud<pcl::PointXYZ>::Ptr> clouds;
00062   std::vector<pcl::PointCloud<pcl::Normal>::Ptr > normals;
00063   std::vector<unsigned int> classes;
00064 
00065   clouds.push_back (training_cloud);
00066   normals.push_back (training_normals);
00067   classes.push_back (0);
00068 
00069   pcl::FPFHEstimation<pcl::PointXYZ, pcl::Normal, pcl::Histogram<153> >::Ptr fpfh
00070     (new pcl::FPFHEstimation<pcl::PointXYZ, pcl::Normal, pcl::Histogram<153> >);
00071   fpfh->setRadiusSearch (30.0);
00072   pcl::Feature< pcl::PointXYZ, pcl::Histogram<153> >::Ptr feature_estimator(fpfh);
00073 
00074   pcl::ism::ImplicitShapeModelEstimation<153, pcl::PointXYZ, pcl::Normal>::ISMModelPtr model = boost::shared_ptr<pcl::features::ISMModel> (new pcl::features::ISMModel);
00075 
00076   pcl::ism::ImplicitShapeModelEstimation<153, pcl::PointXYZ, pcl::Normal> ism;
00077   ism.setFeatureEstimator(feature_estimator);
00078   ism.setTrainingClouds (clouds);
00079   ism.setTrainingClasses (classes);
00080   ism.setTrainingNormals (normals);
00081   ism.setSamplingSize (2.0f);
00082   ism.trainISM (model);
00083 
00084   int _class = 0;
00085   double radius = model->sigmas_[_class] * 10.0;
00086   double sigma = model->sigmas_[_class];
00087 
00088   boost::shared_ptr<pcl::features::ISMVoteList<pcl::PointXYZ> > vote_list = ism.findObjects (model, testing_cloud, testing_normals, _class);
00089   EXPECT_NE (vote_list->getNumberOfVotes (), 0);
00090   std::vector<pcl::ISMPeak, Eigen::aligned_allocator<pcl::ISMPeak> > strongest_peaks;
00091   vote_list->findStrongestPeaks (strongest_peaks, _class, radius, sigma);
00092 
00093   EXPECT_NE (strongest_peaks.size (), 0);
00094 }
00095 
00097 TEST (ISM, TrainWithWrongParameters)
00098 {
00099   pcl::ism::ImplicitShapeModelEstimation<153, pcl::PointXYZ, pcl::Normal> ism;
00100 
00101   float prev_sampling_size = ism.getSamplingSize ();
00102   EXPECT_NE (prev_sampling_size, 0.0);
00103   ism.setSamplingSize (0.0f);
00104   float curr_sampling_size = ism.getSamplingSize ();
00105   EXPECT_EQ (curr_sampling_size, prev_sampling_size);
00106 
00107   unsigned int prev_number_of_clusters = ism.getNumberOfClusters ();
00108   EXPECT_NE (prev_number_of_clusters, 0);
00109   ism.setNumberOfClusters (0);
00110   unsigned int curr_number_of_clusters = ism.getNumberOfClusters ();
00111   EXPECT_EQ (curr_number_of_clusters, prev_number_of_clusters);
00112 }
00113 
00114 /* ---[ */
00115 int
00116 main (int argc, char** argv)
00117 {
00118   if (argc < 2)
00119   {
00120     std::cerr << "This test requires two point clouds (one for training and one for testing)." << std::endl;
00121     std::cerr << "You can use these two clouds 'ism_train.pcd' and 'ism_test.pcd'." << std::endl;
00122     return (-1);
00123   }
00124 
00125   training_cloud = (new pcl::PointCloud<pcl::PointXYZ>)->makeShared();
00126   if (pcl::io::loadPCDFile (argv[1], *training_cloud) < 0)
00127   {
00128     std::cerr << "Failed to read test file. Please download `ism_train.pcd` and pass its path to the test." << std::endl;
00129     return (-1);
00130   }
00131   testing_cloud = (new pcl::PointCloud<pcl::PointXYZ>)->makeShared();
00132   if (pcl::io::loadPCDFile (argv[2], *testing_cloud) < 0)
00133   {
00134     std::cerr << "Failed to read test file. Please download `ism_test.pcd` and pass its path to the test." << std::endl;
00135     return (-1);
00136   }
00137 
00138   training_normals = (new pcl::PointCloud<pcl::Normal>)->makeShared();
00139   testing_normals = (new pcl::PointCloud<pcl::Normal>)->makeShared();
00140   pcl::NormalEstimation<pcl::PointXYZ, pcl::Normal> normal_estimator;
00141   normal_estimator.setRadiusSearch (25.0);
00142   normal_estimator.setInputCloud(training_cloud);
00143   normal_estimator.compute(*training_normals);
00144   normal_estimator.setInputCloud(testing_cloud);
00145   normal_estimator.compute(*testing_normals);
00146 
00147   testing::InitGoogleTest (&argc, argv);
00148   return (RUN_ALL_TESTS ());
00149 }
00150 /* ]--- */


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