test_segmentation.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-2011, 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 
00048 #include <pcl/segmentation/extract_polygonal_prism_data.h>
00049 #include <pcl/segmentation/segment_differences.h>
00050 #include <pcl/segmentation/region_growing.h>
00051 #include <pcl/segmentation/region_growing_rgb.h>
00052 #include <pcl/segmentation/min_cut_segmentation.h>
00053 
00054 using namespace pcl;
00055 using namespace pcl::io;
00056 
00057 PointCloud<PointXYZ>::Ptr cloud_;
00058 PointCloud<PointXYZ>::Ptr cloud_t_;
00059 KdTree<PointXYZ>::Ptr tree_;
00060 
00061 pcl::PointCloud<pcl::PointXYZRGB>::Ptr colored_cloud;
00062 pcl::PointCloud<pcl::PointXYZ>::Ptr another_cloud_;
00063 pcl::PointCloud<pcl::Normal>::Ptr normals_;
00064 pcl::PointCloud<pcl::Normal>::Ptr another_normals_;
00065 
00067 TEST (RegionGrowingRGBTest, Segment)
00068 {
00069   RegionGrowingRGB<pcl::PointXYZRGB> rg;
00070 
00071   rg.setInputCloud (colored_cloud);
00072   rg.setDistanceThreshold (10);
00073   rg.setRegionColorThreshold (5);
00074   rg.setPointColorThreshold (6);
00075   rg.setMinClusterSize (20);
00076 
00077   std::vector <pcl::PointIndices> clusters;
00078   rg.extract (clusters);
00079   int num_of_segments = static_cast<int> (clusters.size ());
00080   EXPECT_NE (0, num_of_segments);
00081 }
00082 
00084 TEST (RegionGrowingTest, Segment)
00085 {
00086   pcl::RegionGrowing<pcl::PointXYZ, pcl::Normal> rg;
00087   rg.setInputCloud (cloud_);
00088   rg.setInputNormals (normals_);
00089 
00090   std::vector <pcl::PointIndices> clusters;
00091   rg.extract (clusters);
00092   int num_of_segments = static_cast<int> (clusters.size ());
00093   EXPECT_NE (0, num_of_segments);
00094 }
00095 
00097 TEST (RegionGrowingTest, SegmentWithoutCloud)
00098 {
00099   pcl::RegionGrowing<pcl::PointXYZ, pcl::Normal> rg;
00100   rg.setInputNormals (normals_);
00101 
00102   std::vector <pcl::PointIndices> clusters;
00103   rg.extract (clusters);
00104   int num_of_segments = static_cast<int> (clusters.size ());
00105   EXPECT_EQ (0, num_of_segments);
00106 }
00107 
00109 TEST (RegionGrowingTest, SegmentWithoutNormals)
00110 {
00111   pcl::RegionGrowing<pcl::PointXYZ, pcl::Normal> rg;
00112   rg.setInputCloud (cloud_);
00113 
00114   std::vector <pcl::PointIndices> clusters;
00115   rg.extract (clusters);
00116   int num_of_segments = static_cast<int> (clusters.size ());
00117   EXPECT_EQ (0, num_of_segments);
00118 }
00119 
00121 TEST (RegionGrowingTest, SegmentEmptyCloud)
00122 {
00123   pcl::PointCloud<pcl::PointXYZ>::Ptr empty_cloud (new pcl::PointCloud<pcl::PointXYZ>);
00124   pcl::PointCloud<pcl::Normal>::Ptr empty_normals (new pcl::PointCloud<pcl::Normal>);
00125 
00126   pcl::RegionGrowing<pcl::PointXYZ, pcl::Normal> rg;
00127   rg.setInputCloud (empty_cloud);
00128   rg.setInputNormals (empty_normals);
00129 
00130   std::vector <pcl::PointIndices> clusters;
00131   rg.extract (clusters);
00132   int num_of_segments = static_cast<int> (clusters.size ());
00133   EXPECT_EQ (0, num_of_segments);
00134 }
00135 
00137 TEST (RegionGrowingTest, SegmentWithDifferentNormalAndCloudSize)
00138 {
00139   pcl::RegionGrowing<pcl::PointXYZ, pcl::Normal> rg;
00140   rg.setInputCloud (another_cloud_);
00141   rg.setInputNormals (normals_);
00142 
00143   int first_cloud_size = static_cast<int> (cloud_->points.size ());
00144   int second_cloud_size = static_cast<int> (another_cloud_->points.size ());
00145   ASSERT_NE (first_cloud_size, second_cloud_size);
00146 
00147   std::vector <pcl::PointIndices> clusters;
00148   rg.extract (clusters);
00149   int num_of_segments = static_cast<int> (clusters.size ());
00150   EXPECT_EQ (0, num_of_segments);
00151 
00152   rg.setInputCloud (cloud_);
00153   rg.setInputNormals (another_normals_);
00154 
00155   rg.extract (clusters);
00156   num_of_segments = static_cast<int> (clusters.size ());
00157   EXPECT_EQ (0, num_of_segments);
00158 }
00159 
00161 TEST (RegionGrowingTest, SegmentWithWrongThresholdParameters)
00162 {
00163   pcl::RegionGrowing<pcl::PointXYZ, pcl::Normal> rg;
00164   rg.setInputCloud (cloud_);
00165   rg.setInputNormals (normals_);
00166 
00167   rg.setNumberOfNeighbours (0);
00168 
00169   std::vector <pcl::PointIndices> clusters;
00170   rg.extract (clusters);
00171   int num_of_segments = static_cast<int> (clusters.size ());
00172   EXPECT_EQ (0, num_of_segments);
00173 
00174   rg.setNumberOfNeighbours (30);
00175   rg.setResidualTestFlag (true);
00176   rg.setResidualThreshold (-10.0);
00177 
00178   rg.extract (clusters);
00179   num_of_segments = static_cast<int> (clusters.size ());
00180   EXPECT_EQ (0, num_of_segments);
00181 
00182   rg.setCurvatureTestFlag (true);
00183   rg.setCurvatureThreshold (-10.0f);
00184 
00185   rg.extract (clusters);
00186   num_of_segments = static_cast<int> (clusters.size ());
00187   EXPECT_EQ (0, num_of_segments);
00188 }
00189 
00191 TEST (RegionGrowingTest, SegmentFromPoint)
00192 {
00193   pcl::RegionGrowing<pcl::PointXYZ, pcl::Normal> rg;
00194 
00195   pcl::PointIndices cluster;
00196   rg.getSegmentFromPoint (0, cluster);
00197   EXPECT_EQ (0, cluster.indices.size ());
00198 
00199   rg.setInputCloud (cloud_);
00200   rg.setInputNormals (normals_);
00201   rg.getSegmentFromPoint(0, cluster);
00202   EXPECT_NE (0, cluster.indices.size());
00203 }
00204 
00205 #if (BOOST_VERSION >= 104400)
00206 
00207 TEST (MinCutSegmentationTest, Segment)
00208 {
00209   pcl::MinCutSegmentation<pcl::PointXYZ> mcSeg;
00210 
00211   pcl::PointXYZ object_center;
00212   double radius = 0.0;
00213   double sigma = 0.0;
00214   double source_weight = 0.0;
00215   unsigned int neighbor_number = 0;
00216 
00217   object_center.x = -36.01f;
00218   object_center.y = -64.73f;
00219   object_center.z = -6.18f;
00220   radius = 3.8003856;
00221   sigma = 0.25;
00222   source_weight = 0.8;
00223   neighbor_number = 14;
00224 
00225   pcl::PointCloud<pcl::PointXYZ>::Ptr foreground_points(new pcl::PointCloud<pcl::PointXYZ> ());
00226   foreground_points->points.push_back (object_center);
00227 
00228   mcSeg.setForegroundPoints (foreground_points);
00229   mcSeg.setInputCloud (another_cloud_);
00230   mcSeg.setRadius (radius);
00231   mcSeg.setSigma (sigma);
00232   mcSeg.setSourceWeight (source_weight);
00233   mcSeg.setNumberOfNeighbours (neighbor_number);
00234 
00235   std::vector <pcl::PointIndices> clusters;
00236   mcSeg.extract (clusters);
00237   int num_of_segments = static_cast<int> (clusters.size ());
00238   EXPECT_EQ (2, num_of_segments);
00239 }
00240 
00242 TEST (MinCutSegmentationTest, SegmentWithoutForegroundPoints)
00243 {
00244   pcl::MinCutSegmentation<pcl::PointXYZ> mcSeg;
00245   mcSeg.setInputCloud (another_cloud_);
00246   mcSeg.setRadius (3.8003856);
00247 
00248   std::vector <pcl::PointIndices> clusters;
00249   mcSeg.extract (clusters);
00250   int num_of_segments = static_cast<int> (clusters.size ());
00251   EXPECT_EQ (0, num_of_segments);
00252 }
00253 
00255 TEST (MinCutSegmentationTest, SegmentWithoutCloud)
00256 {
00257   pcl::MinCutSegmentation<pcl::PointXYZ> mcSeg;
00258 
00259   std::vector <pcl::PointIndices> clusters;
00260   mcSeg.extract (clusters);
00261   int num_of_segments = static_cast<int> (clusters.size ());
00262   EXPECT_EQ (0, num_of_segments);
00263 }
00264 
00266 TEST (MinCutSegmentationTest, SegmentEmptyCloud)
00267 {
00268   pcl::PointCloud<pcl::PointXYZ>::Ptr empty_cloud (new pcl::PointCloud<pcl::PointXYZ>);
00269   pcl::MinCutSegmentation<pcl::PointXYZ> mcSeg;
00270   mcSeg.setInputCloud (empty_cloud);
00271 
00272   std::vector <pcl::PointIndices> clusters;
00273   mcSeg.extract (clusters);
00274   int num_of_segments = static_cast<int> (clusters.size ());
00275   EXPECT_EQ (0, num_of_segments);
00276 }
00277 
00279 TEST (MinCutSegmentationTest, SegmentWithWrongParameters)
00280 {
00281   pcl::MinCutSegmentation<pcl::PointXYZ> mcSeg;
00282   mcSeg.setInputCloud (another_cloud_);
00283   pcl::PointXYZ object_center;
00284   object_center.x = -36.01f;
00285   object_center.y = -64.73f;
00286   object_center.z = -6.18f;
00287   pcl::PointCloud<pcl::PointXYZ>::Ptr foreground_points(new pcl::PointCloud<pcl::PointXYZ> ());
00288   foreground_points->points.push_back (object_center);
00289   mcSeg.setForegroundPoints (foreground_points);
00290 
00291   unsigned int prev_neighbor_number = mcSeg.getNumberOfNeighbours ();
00292   EXPECT_LT (0, prev_neighbor_number);
00293 
00294   mcSeg.setNumberOfNeighbours (0);
00295   unsigned int curr_neighbor_number = mcSeg.getNumberOfNeighbours ();
00296   EXPECT_EQ (prev_neighbor_number, curr_neighbor_number);
00297 
00298   double prev_radius = mcSeg.getRadius ();
00299   EXPECT_LT (0.0, prev_radius);
00300 
00301   mcSeg.setRadius (0.0);
00302   double curr_radius = mcSeg.getRadius ();
00303   EXPECT_EQ (prev_radius, curr_radius);
00304 
00305   mcSeg.setRadius (-10.0);
00306   curr_radius = mcSeg.getRadius ();
00307   EXPECT_EQ (prev_radius, curr_radius);
00308 
00309   double prev_sigma = mcSeg.getSigma ();
00310   EXPECT_LT (0.0, prev_sigma);
00311 
00312   mcSeg.setSigma (0.0);
00313   double curr_sigma = mcSeg.getSigma ();
00314   EXPECT_EQ (prev_sigma, curr_sigma);
00315 
00316   mcSeg.setSigma (-10.0);
00317   curr_sigma = mcSeg.getSigma ();
00318   EXPECT_EQ (prev_sigma, curr_sigma);
00319 
00320   double prev_source_weight = mcSeg.getSourceWeight ();
00321   EXPECT_LT (0.0, prev_source_weight);
00322 
00323   mcSeg.setSourceWeight (0.0);
00324   double curr_source_weight = mcSeg.getSourceWeight ();
00325   EXPECT_EQ (prev_source_weight, curr_source_weight);
00326 
00327   mcSeg.setSourceWeight (-10.0);
00328   curr_source_weight = mcSeg.getSourceWeight ();
00329   EXPECT_EQ (prev_source_weight, curr_source_weight);
00330 
00331   mcSeg.setRadius (3.8003856);
00332 
00333   std::vector <pcl::PointIndices> clusters;
00334   mcSeg.extract (clusters);
00335   int num_of_segments = static_cast<int> (clusters.size ());
00336   EXPECT_EQ (2, num_of_segments);
00337 }
00338 #endif
00339 
00341 TEST (SegmentDifferences, Segmentation)
00342 {
00343   SegmentDifferences<PointXYZ> sd;
00344   sd.setInputCloud (cloud_);
00345   sd.setDistanceThreshold (0.00005);
00346 
00347   // Set the target as itself
00348   sd.setTargetCloud (cloud_);
00349 
00350   PointCloud<PointXYZ> output;
00351   sd.segment (output);
00352 
00353   EXPECT_EQ (static_cast<int> (output.points.size ()), 0);
00354   
00355   // Set a different target
00356   sd.setTargetCloud (cloud_t_);
00357   sd.segment (output);
00358   EXPECT_EQ (static_cast<int> (output.points.size ()), 126);
00359   //savePCDFile ("./test/0-t.pcd", output);
00360 
00361   // Reverse
00362   sd.setInputCloud (cloud_t_);
00363   sd.setTargetCloud (cloud_);
00364   sd.segment (output);
00365   EXPECT_EQ (static_cast<int> (output.points.size ()), 127);
00366   //savePCDFile ("./test/t-0.pcd", output);
00367 }
00368 
00370 TEST (ExtractPolygonalPrism, Segmentation)
00371 {
00372   PointCloud<PointXYZ>::Ptr hull (new PointCloud<PointXYZ>);
00373   hull->points.resize (5);
00374 
00375   for (size_t i = 0; i < hull->points.size (); ++i)
00376   {
00377     hull->points[i].x = hull->points[i].y = static_cast<float> (i);
00378     hull->points[i].z = 0.0f;
00379   }
00380 
00381   ExtractPolygonalPrismData<PointXYZ> ex;
00382   ex.setInputCloud (cloud_);
00383   ex.setInputPlanarHull (hull);
00384 
00385   PointIndices output;
00386   ex.segment (output);
00387 
00388   EXPECT_EQ (static_cast<int> (output.indices.size ()), 0);
00389 }
00390 
00391 /* ---[ */
00392 int
00393 main (int argc, char** argv)
00394 {
00395   if (argc < 4)
00396   {
00397     std::cerr << "This test requires three point clouds. The first one must be 'bun0.pcd'." << std::endl;
00398     std::cerr << "The second must be 'car6.pcd'. The last one must be 'colored_cloud.pcd'." << std::endl;
00399     std::cerr << "Please download and pass them in the specified order(including the path to them)." << std::endl;
00400     return (-1);
00401   }
00402 
00403   // Load a standard PCD file from disk
00404   PointCloud<PointXYZ> cloud, cloud_t, another_cloud;
00405   PointCloud<PointXYZRGB> colored_cloud_1;
00406   if (loadPCDFile (argv[1], cloud) < 0)
00407   {
00408     std::cerr << "Failed to read test file. Please download `bun0.pcd` and pass its path to the test." << std::endl;
00409     return (-1);
00410   }
00411   if (pcl::io::loadPCDFile (argv[2], another_cloud) < 0)
00412   {
00413     std::cerr << "Failed to read test file. Please download `car6.pcd` and pass its path to the test." << std::endl;
00414     return (-1);
00415   }
00416   if (pcl::io::loadPCDFile (argv[3], colored_cloud_1) < 0)
00417   {
00418     std::cerr << "Failed to read test file. Please download `colored_cloud.pcd` and pass its path to the test." << std::endl;
00419     return (-1);
00420   }
00421 
00422   colored_cloud = colored_cloud_1.makeShared();
00423 
00424   // Tranpose the cloud
00425   cloud_t = cloud;
00426   for (size_t i = 0; i < cloud.points.size (); ++i)
00427     cloud_t.points[i].x += 0.01f;
00428 
00429   cloud_   = cloud.makeShared ();
00430   cloud_t_ = cloud_t.makeShared ();
00431 
00432   another_cloud_ = another_cloud.makeShared();
00433   normals_ = (new pcl::PointCloud<pcl::Normal>)->makeShared();
00434   pcl::NormalEstimation<pcl::PointXYZ, pcl::Normal> normal_estimator;
00435   normal_estimator.setInputCloud(cloud_);
00436   normal_estimator.setKSearch(30);
00437   normal_estimator.compute(*normals_);
00438 
00439   another_normals_ = (new pcl::PointCloud<pcl::Normal>)->makeShared();
00440   normal_estimator.setInputCloud(another_cloud_);
00441   normal_estimator.setKSearch(30);
00442   normal_estimator.compute(*another_normals_);
00443 
00444   testing::InitGoogleTest (&argc, argv);
00445   return (RUN_ALL_TESTS ());
00446 }
00447 /* ]--- */


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