conditional_euclidean_clustering.hpp
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) 2009, Willow Garage, Inc.
00006  *  All rights reserved.
00007  *
00008  *  Redistribution and use in source and binary forms, with or without
00009  *  modification, are permitted provided that the following conditions
00010  *  are met:
00011  *
00012  *   * Redistributions of source code must retain the above copyright
00013  *     notice, this list of conditions and the following disclaimer.
00014  *   * Redistributions in binary form must reproduce the above
00015  *     copyright notice, this list of conditions and the following
00016  *     disclaimer in the documentation and/or other materials provided
00017  *     with the distribution.
00018  *   * Neither the name of the copyright holder(s) nor the names of its
00019  *     contributors may be used to endorse or promote products derived
00020  *     from this software without specific prior written permission.
00021  *
00022  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00023  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00024  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00025  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00026  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00027  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00028  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00029  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00030  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00031  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00032  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00033  *  POSSIBILITY OF SUCH DAMAGE.
00034  *
00035  */
00036 
00037 #ifndef PCL_SEGMENTATION_IMPL_CONDITIONAL_EUCLIDEAN_CLUSTERING_HPP_
00038 #define PCL_SEGMENTATION_IMPL_CONDITIONAL_EUCLIDEAN_CLUSTERING_HPP_
00039 
00040 #include <pcl/segmentation/conditional_euclidean_clustering.h>
00041 
00042 template<typename PointT> void
00043 pcl::ConditionalEuclideanClustering<PointT>::segment (pcl::IndicesClusters &clusters)
00044 {
00045   // Prepare output (going to use push_back)
00046   clusters.clear ();
00047   if (extract_removed_clusters_)
00048   {
00049     small_clusters_->clear ();
00050     large_clusters_->clear ();
00051   }
00052 
00053   // Validity checks
00054   if (!initCompute () || input_->points.empty () || indices_->empty () || !condition_function_)
00055     return;
00056 
00057   // Initialize the search class
00058   if (!searcher_)
00059   {
00060     if (input_->isOrganized ())
00061       searcher_.reset (new pcl::search::OrganizedNeighbor<PointT> ());
00062     else
00063       searcher_.reset (new pcl::search::KdTree<PointT> ());
00064   }
00065   searcher_->setInputCloud (input_, indices_);
00066 
00067   // Temp variables used by search class
00068   std::vector<int> nn_indices;
00069   std::vector<float> nn_distances;
00070 
00071   // Create a bool vector of processed point indices, and initialize it to false
00072   // Need to have it contain all possible points because radius search can not return indices into indices
00073   std::vector<bool> processed (input_->points.size (), false);
00074 
00075   // Process all points indexed by indices_
00076   for (int iii = 0; iii < static_cast<int> (indices_->size ()); ++iii)  // iii = input indices iterator
00077   {
00078     // Has this point been processed before?
00079     if ((*indices_)[iii] == -1 || processed[(*indices_)[iii]])
00080       continue;
00081 
00082     // Set up a new growing cluster
00083     std::vector<int> current_cluster;
00084     int cii = 0;  // cii = cluster indices iterator
00085 
00086     // Add the point to the cluster
00087     current_cluster.push_back ((*indices_)[iii]);
00088     processed[(*indices_)[iii]] = true;
00089 
00090     // Process the current cluster (it can be growing in size as it is being processed)
00091     while (cii < static_cast<int> (current_cluster.size ()))
00092     {
00093       // Search for neighbors around the current seed point of the current cluster
00094       if (searcher_->radiusSearch (input_->points[current_cluster[cii]], cluster_tolerance_, nn_indices, nn_distances) < 1)
00095       {
00096         cii++;
00097         continue;
00098       }
00099 
00100       // Process the neighbors
00101       for (int nii = 1; nii < static_cast<int> (nn_indices.size ()); ++nii)  // nii = neighbor indices iterator
00102       {
00103         // Has this point been processed before?
00104         if (nn_indices[nii] == -1 || processed[nn_indices[nii]])
00105           continue;
00106 
00107         // Validate if condition holds
00108         if (condition_function_ (input_->points[current_cluster[cii]], input_->points[nn_indices[nii]], nn_distances[nii]))
00109         {
00110           // Add the point to the cluster
00111           current_cluster.push_back (nn_indices[nii]);
00112           processed[nn_indices[nii]] = true;
00113         }
00114       }
00115       cii++;
00116     }
00117 
00118     // If extracting removed clusters, all clusters need to be saved, otherwise only the ones within the given cluster size range
00119     if (extract_removed_clusters_ || (current_cluster.size () >= min_cluster_size_ && current_cluster.size () <= max_cluster_size_))
00120     {
00121       pcl::PointIndices pi;
00122       pi.header = input_->header;
00123       pi.indices.resize (current_cluster.size ());
00124       for (int ii = 0; ii < static_cast<int> (current_cluster.size ()); ++ii)  // ii = indices iterator
00125         pi.indices[ii] = current_cluster[ii];
00126 
00127       if (extract_removed_clusters_ && current_cluster.size () < min_cluster_size_)
00128         small_clusters_->push_back (pi);
00129       else if (extract_removed_clusters_ && current_cluster.size () > max_cluster_size_)
00130         large_clusters_->push_back (pi);
00131       else
00132         clusters.push_back (pi);
00133     }
00134   }
00135 
00136   deinitCompute ();
00137 }
00138 
00139 #define PCL_INSTANTIATE_ConditionalEuclideanClustering(T) template class PCL_EXPORTS pcl::ConditionalEuclideanClustering<T>;
00140 
00141 #endif  // PCL_SEGMENTATION_IMPL_CONDITIONAL_EUCLIDEAN_CLUSTERING_HPP_
00142 


pcl
Author(s): Open Perception
autogenerated on Wed Aug 26 2015 15:22:52