extract_labeled_clusters.hpp
Go to the documentation of this file.
00001 /*
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2011, 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 Willow Garage, Inc. 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  * $id $
00035  */
00036 
00037 #ifndef PCL_SEGMENTATION_IMPL_EXTRACT_LABELED_CLUSTERS_H_
00038 #define PCL_SEGMENTATION_IMPL_EXTRACT_LABELED_CLUSTERS_H_
00039 
00040 #include <pcl/segmentation/extract_labeled_clusters.h>
00041 
00043 template <typename PointT> void
00044 pcl::extractLabeledEuclideanClusters (const PointCloud<PointT> &cloud, 
00045                                       const boost::shared_ptr<search::Search<PointT> > &tree,
00046                                       float tolerance, 
00047                                       std::vector<std::vector<PointIndices> > &labeled_clusters,
00048                                       unsigned int min_pts_per_cluster, 
00049                                       unsigned int max_pts_per_cluster,
00050                                       unsigned int)
00051 {
00052   if (tree->getInputCloud ()->points.size () != cloud.points.size ())
00053   {
00054     PCL_ERROR ("[pcl::extractLabeledEuclideanClusters] Tree built for a different point cloud dataset (%zu) than the input cloud (%zu)!\n", tree->getInputCloud ()->points.size (), cloud.points.size ());
00055     return;
00056   }
00057   // Create a bool vector of processed point indices, and initialize it to false
00058   std::vector<bool> processed (cloud.points.size (), false);
00059 
00060   std::vector<int> nn_indices;
00061   std::vector<float> nn_distances;
00062 
00063   // Process all points in the indices vector
00064   for (int i = 0; i < static_cast<int> (cloud.points.size ()); ++i)
00065   {
00066     if (processed[i])
00067       continue;
00068 
00069     std::vector<int> seed_queue;
00070     int sq_idx = 0;
00071     seed_queue.push_back (i);
00072 
00073     processed[i] = true;
00074 
00075     while (sq_idx < static_cast<int> (seed_queue.size ()))
00076     {
00077       // Search for sq_idx
00078       int ret = tree->radiusSearch (seed_queue[sq_idx], tolerance, nn_indices, nn_distances, std::numeric_limits<int>::max());
00079       if(ret == -1)
00080         PCL_ERROR("radiusSearch on tree came back with error -1");
00081       if (!ret)
00082       {
00083         sq_idx++;
00084         continue;
00085       }
00086 
00087       for (size_t j = 1; j < nn_indices.size (); ++j)             // nn_indices[0] should be sq_idx
00088       {
00089         if (processed[nn_indices[j]])                             // Has this point been processed before ?
00090           continue;
00091         if (cloud.points[i].label == cloud.points[nn_indices[j]].label)
00092         {
00093           // Perform a simple Euclidean clustering
00094           seed_queue.push_back (nn_indices[j]);
00095           processed[nn_indices[j]] = true;
00096         }
00097       }
00098 
00099       sq_idx++;
00100     }
00101 
00102     // If this queue is satisfactory, add to the clusters
00103     if (seed_queue.size () >= min_pts_per_cluster && seed_queue.size () <= max_pts_per_cluster)
00104     {
00105       pcl::PointIndices r;
00106       r.indices.resize (seed_queue.size ());
00107       for (size_t j = 0; j < seed_queue.size (); ++j)
00108         r.indices[j] = seed_queue[j];
00109 
00110       std::sort (r.indices.begin (), r.indices.end ());
00111       r.indices.erase (std::unique (r.indices.begin (), r.indices.end ()), r.indices.end ());
00112 
00113       r.header = cloud.header;
00114       labeled_clusters[cloud.points[i].label].push_back (r);   // We could avoid a copy by working directly in the vector
00115     }
00116   }
00117 }
00121 
00122 template <typename PointT> void 
00123 pcl::LabeledEuclideanClusterExtraction<PointT>::extract (std::vector<std::vector<PointIndices> > &labeled_clusters)
00124 {
00125   if (!initCompute () || 
00126       (input_ != 0   && input_->points.empty ()) ||
00127       (indices_ != 0 && indices_->empty ()))
00128   {
00129     labeled_clusters.clear ();
00130     return;
00131   }
00132 
00133   // Initialize the spatial locator
00134   if (!tree_)
00135   {
00136     if (input_->isOrganized ())
00137       tree_.reset (new pcl::search::OrganizedNeighbor<PointT> ());
00138     else
00139       tree_.reset (new pcl::search::KdTree<PointT> (false));
00140   }
00141 
00142   // Send the input dataset to the spatial locator
00143   tree_->setInputCloud (input_);
00144   extractLabeledEuclideanClusters (*input_, tree_, static_cast<float> (cluster_tolerance_), labeled_clusters, min_pts_per_cluster_, max_pts_per_cluster_, max_label_);
00145 
00146   // Sort the clusters based on their size (largest one first)
00147   for (int i = 0; i < static_cast<int> (labeled_clusters.size ()); i++)
00148     std::sort (labeled_clusters[i].rbegin (), labeled_clusters[i].rend (), comparePointClusters);
00149 
00150   deinitCompute ();
00151 }
00152 
00153 #define PCL_INSTANTIATE_LabeledEuclideanClusterExtraction(T) template class PCL_EXPORTS pcl::LabeledEuclideanClusterExtraction<T>;
00154 #define PCL_INSTANTIATE_extractLabeledEuclideanClusters(T) template void PCL_EXPORTS pcl::extractLabeledEuclideanClusters<T>(const pcl::PointCloud<T> &, const boost::shared_ptr<pcl::search::Search<T> > &, float , std::vector<std::vector<pcl::PointIndices> > &, unsigned int, unsigned int, unsigned int);
00155 
00156 #endif        // PCL_EXTRACT_CLUSTERS_IMPL_H_


pcl
Author(s): Open Perception
autogenerated on Mon Oct 6 2014 03:15:01