conditional_euclidean_clustering.h
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  */
00037 
00038 #ifndef PCL_SEGMENTATION_CONDITIONAL_EUCLIDEAN_CLUSTERING_H_
00039 #define PCL_SEGMENTATION_CONDITIONAL_EUCLIDEAN_CLUSTERING_H_
00040 
00041 #include <pcl/pcl_base.h>
00042 #include <pcl/search/pcl_search.h>
00043 
00044 namespace pcl
00045 {
00046   typedef std::vector<pcl::PointIndices> IndicesClusters;
00047   typedef boost::shared_ptr<std::vector<pcl::PointIndices> > IndicesClustersPtr;
00048 
00080   template<typename PointT>
00081   class ConditionalEuclideanClustering : public PCLBase<PointT>
00082   {
00083     protected:
00084       typedef typename pcl::search::Search<PointT>::Ptr SearcherPtr;
00085 
00086       using PCLBase<PointT>::input_;
00087       using PCLBase<PointT>::indices_;
00088       using PCLBase<PointT>::initCompute;
00089       using PCLBase<PointT>::deinitCompute;
00090 
00091     public:
00095       ConditionalEuclideanClustering (bool extract_removed_clusters = false) :
00096           searcher_ (),
00097           condition_function_ (),
00098           cluster_tolerance_ (0.0f),
00099           min_cluster_size_ (1),
00100           max_cluster_size_ (std::numeric_limits<int>::max ()),
00101           extract_removed_clusters_ (extract_removed_clusters),
00102           small_clusters_ (new pcl::IndicesClusters),
00103           large_clusters_ (new pcl::IndicesClusters)
00104       {
00105       }
00106 
00124       inline void
00125       setConditionFunction (bool (*condition_function) (const PointT&, const PointT&, float)) 
00126       {
00127         condition_function_ = condition_function;
00128       }
00129 
00135       inline void
00136       setClusterTolerance (float cluster_tolerance)
00137       {
00138         cluster_tolerance_ = cluster_tolerance;
00139       }
00140 
00142       inline float
00143       getClusterTolerance ()
00144       {
00145         return (cluster_tolerance_);
00146       }
00147 
00151       inline void
00152       setMinClusterSize (int min_cluster_size)
00153       {
00154         min_cluster_size_ = min_cluster_size;
00155       }
00156 
00158       inline int
00159       getMinClusterSize ()
00160       {
00161         return (min_cluster_size_);
00162       }
00163 
00167       inline void
00168       setMaxClusterSize (int max_cluster_size)
00169       {
00170         max_cluster_size_ = max_cluster_size;
00171       }
00172 
00174       inline int
00175       getMaxClusterSize ()
00176       {
00177         return (max_cluster_size_);
00178       }
00179 
00189       void
00190       segment (IndicesClusters &clusters);
00191 
00197       inline void
00198       getRemovedClusters (IndicesClustersPtr &small_clusters, IndicesClustersPtr &large_clusters)
00199       {
00200         if (!extract_removed_clusters_)
00201         {
00202           PCL_WARN("[pcl::ConditionalEuclideanClustering::getRemovedClusters] You need to set extract_removed_clusters to true (in this class' constructor) if you want to use this functionality.\n");
00203           return;
00204         }
00205         small_clusters = small_clusters_;
00206         large_clusters = large_clusters_;
00207       }
00208 
00209     private:
00211       SearcherPtr searcher_;
00212 
00214       bool (*condition_function_) (const PointT&, const PointT&, float);
00215 
00217       float cluster_tolerance_;
00218 
00220       int min_cluster_size_;
00221 
00223       int max_cluster_size_;
00224 
00226       bool extract_removed_clusters_;
00227 
00229       pcl::IndicesClustersPtr small_clusters_;
00230 
00232       pcl::IndicesClustersPtr large_clusters_;
00233 
00234     public:
00235       EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00236   };
00237 }
00238 
00239 #ifdef PCL_NO_PRECOMPILE
00240 #include <pcl/segmentation/impl/conditional_euclidean_clustering.hpp>
00241 #endif
00242 
00243 #endif  // PCL_SEGMENTATION_CONDITIONAL_EUCLIDEAN_CLUSTERING_H_
00244 


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