extract_clusters.hpp
Go to the documentation of this file.
00001 /*
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2009, 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  * $Id$
00035  *
00036  */
00037 
00038 #ifndef PCL_SEGMENTATION_IMPL_EXTRACT_CLUSTERS_H_
00039 #define PCL_SEGMENTATION_IMPL_EXTRACT_CLUSTERS_H_
00040 
00041 #include <pcl/segmentation/extract_clusters.h>
00042 
00044 template <typename PointT> void
00045 pcl::extractEuclideanClusters (const PointCloud<PointT> &cloud, 
00046                                const boost::shared_ptr<search::Search<PointT> > &tree,
00047                                float tolerance, std::vector<PointIndices> &clusters,
00048                                unsigned int min_pts_per_cluster, 
00049                                unsigned int max_pts_per_cluster)
00050 {
00051   if (tree->getInputCloud ()->points.size () != cloud.points.size ())
00052   {
00053     PCL_ERROR ("[pcl::extractEuclideanClusters] Tree built for a different point cloud dataset (%zu) than the input cloud (%zu)!\n", tree->getInputCloud ()->points.size (), cloud.points.size ());
00054     return;
00055   }
00056   // Check if the tree is sorted -- if it is we don't need to check the first element
00057   int nn_start_idx = tree->getSortedResults () ? 1 : 0;
00058   // Create a bool vector of processed point indices, and initialize it to false
00059   std::vector<bool> processed (cloud.points.size (), false);
00060 
00061   std::vector<int> nn_indices;
00062   std::vector<float> nn_distances;
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       if (!tree->radiusSearch (seed_queue[sq_idx], tolerance, nn_indices, nn_distances))
00079       {
00080         sq_idx++;
00081         continue;
00082       }
00083 
00084       for (size_t j = nn_start_idx; j < nn_indices.size (); ++j)             // can't assume sorted (default isn't!)
00085       {
00086         if (nn_indices[j] == -1 || processed[nn_indices[j]])        // Has this point been processed before ?
00087           continue;
00088 
00089         // Perform a simple Euclidean clustering
00090         seed_queue.push_back (nn_indices[j]);
00091         processed[nn_indices[j]] = true;
00092       }
00093 
00094       sq_idx++;
00095     }
00096 
00097     // If this queue is satisfactory, add to the clusters
00098     if (seed_queue.size () >= min_pts_per_cluster && seed_queue.size () <= max_pts_per_cluster)
00099     {
00100       pcl::PointIndices r;
00101       r.indices.resize (seed_queue.size ());
00102       for (size_t j = 0; j < seed_queue.size (); ++j)
00103         r.indices[j] = seed_queue[j];
00104 
00105       // These two lines should not be needed: (can anyone confirm?) -FF
00106       std::sort (r.indices.begin (), r.indices.end ());
00107       r.indices.erase (std::unique (r.indices.begin (), r.indices.end ()), r.indices.end ());
00108 
00109       r.header = cloud.header;
00110       clusters.push_back (r);   // We could avoid a copy by working directly in the vector
00111     }
00112   }
00113 }
00114 
00116 
00117 template <typename PointT> void
00118 pcl::extractEuclideanClusters (const PointCloud<PointT> &cloud, 
00119                                const std::vector<int> &indices,
00120                                const boost::shared_ptr<search::Search<PointT> > &tree,
00121                                float tolerance, std::vector<PointIndices> &clusters,
00122                                unsigned int min_pts_per_cluster, 
00123                                unsigned int max_pts_per_cluster)
00124 {
00125   // \note If the tree was created over <cloud, indices>, we guarantee a 1-1 mapping between what the tree returns
00126   //and indices[i]
00127   if (tree->getInputCloud ()->points.size () != cloud.points.size ())
00128   {
00129     PCL_ERROR ("[pcl::extractEuclideanClusters] Tree built for a different point cloud dataset (%zu) than the input cloud (%zu)!\n", tree->getInputCloud ()->points.size (), cloud.points.size ());
00130     return;
00131   }
00132   if (tree->getIndices ()->size () != indices.size ())
00133   {
00134     PCL_ERROR ("[pcl::extractEuclideanClusters] Tree built for a different set of indices (%zu) than the input set (%zu)!\n", tree->getIndices ()->size (), indices.size ());
00135     return;
00136   }
00137   // Check if the tree is sorted -- if it is we don't need to check the first element
00138   int nn_start_idx = tree->getSortedResults () ? 1 : 0;
00139 
00140   // Create a bool vector of processed point indices, and initialize it to false
00141   std::vector<bool> processed (cloud.points.size (), false);
00142 
00143   std::vector<int> nn_indices;
00144   std::vector<float> nn_distances;
00145   // Process all points in the indices vector
00146   for (int i = 0; i < static_cast<int> (indices.size ()); ++i)
00147   {
00148     if (processed[indices[i]])
00149       continue;
00150 
00151     std::vector<int> seed_queue;
00152     int sq_idx = 0;
00153     seed_queue.push_back (indices[i]);
00154 
00155     processed[indices[i]] = true;
00156 
00157     while (sq_idx < static_cast<int> (seed_queue.size ()))
00158     {
00159       // Search for sq_idx
00160       int ret = tree->radiusSearch (cloud.points[seed_queue[sq_idx]], tolerance, nn_indices, nn_distances);
00161       if( ret == -1)
00162       {
00163         PCL_ERROR("[pcl::extractEuclideanClusters] Received error code -1 from radiusSearch\n");
00164         exit(0);
00165       }
00166       if (!ret)
00167       {
00168         sq_idx++;
00169         continue;
00170       }
00171 
00172       for (size_t j = nn_start_idx; j < nn_indices.size (); ++j)             // can't assume sorted (default isn't!)
00173       {
00174         if (nn_indices[j] == -1 || processed[nn_indices[j]])        // Has this point been processed before ?
00175           continue;
00176 
00177         // Perform a simple Euclidean clustering
00178         seed_queue.push_back (nn_indices[j]);
00179         processed[nn_indices[j]] = true;
00180       }
00181 
00182       sq_idx++;
00183     }
00184 
00185     // If this queue is satisfactory, add to the clusters
00186     if (seed_queue.size () >= min_pts_per_cluster && seed_queue.size () <= max_pts_per_cluster)
00187     {
00188       pcl::PointIndices r;
00189       r.indices.resize (seed_queue.size ());
00190       for (size_t j = 0; j < seed_queue.size (); ++j)
00191         // This is the only place where indices come into play
00192         r.indices[j] = seed_queue[j];
00193 
00194       // These two lines should not be needed: (can anyone confirm?) -FF
00195       //r.indices.assign(seed_queue.begin(), seed_queue.end());
00196       std::sort (r.indices.begin (), r.indices.end ());
00197       r.indices.erase (std::unique (r.indices.begin (), r.indices.end ()), r.indices.end ());
00198 
00199       r.header = cloud.header;
00200       clusters.push_back (r);   // We could avoid a copy by working directly in the vector
00201     }
00202   }
00203 }
00204 
00208 
00209 template <typename PointT> void 
00210 pcl::EuclideanClusterExtraction<PointT>::extract (std::vector<PointIndices> &clusters)
00211 {
00212   if (!initCompute () || 
00213       (input_ != 0   && input_->points.empty ()) ||
00214       (indices_ != 0 && indices_->empty ()))
00215   {
00216     clusters.clear ();
00217     return;
00218   }
00219 
00220   // Initialize the spatial locator
00221   if (!tree_)
00222   {
00223     if (input_->isOrganized ())
00224       tree_.reset (new pcl::search::OrganizedNeighbor<PointT> ());
00225     else
00226       tree_.reset (new pcl::search::KdTree<PointT> (false));
00227   }
00228 
00229   // Send the input dataset to the spatial locator
00230   tree_->setInputCloud (input_, indices_);
00231   extractEuclideanClusters (*input_, *indices_, tree_, static_cast<float> (cluster_tolerance_), clusters, min_pts_per_cluster_, max_pts_per_cluster_);
00232 
00233   //tree_->setInputCloud (input_);
00234   //extractEuclideanClusters (*input_, tree_, cluster_tolerance_, clusters, min_pts_per_cluster_, max_pts_per_cluster_);
00235 
00236   // Sort the clusters based on their size (largest one first)
00237   std::sort (clusters.rbegin (), clusters.rend (), comparePointClusters);
00238 
00239   deinitCompute ();
00240 }
00241 
00242 #define PCL_INSTANTIATE_EuclideanClusterExtraction(T) template class PCL_EXPORTS pcl::EuclideanClusterExtraction<T>;
00243 #define PCL_INSTANTIATE_extractEuclideanClusters(T) template void PCL_EXPORTS pcl::extractEuclideanClusters<T>(const pcl::PointCloud<T> &, const boost::shared_ptr<pcl::search::Search<T> > &, float , std::vector<pcl::PointIndices> &, unsigned int, unsigned int);
00244 #define PCL_INSTANTIATE_extractEuclideanClusters_indices(T) template void PCL_EXPORTS pcl::extractEuclideanClusters<T>(const pcl::PointCloud<T> &, const std::vector<int> &, const boost::shared_ptr<pcl::search::Search<T> > &, float , std::vector<pcl::PointIndices> &, unsigned int, unsigned int);
00245 
00246 #endif        // PCL_EXTRACT_CLUSTERS_IMPL_H_


pcl
Author(s): Open Perception
autogenerated on Wed Aug 26 2015 15:23:42