extract_labeled_clusters.h
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  */
00035 
00036 #ifndef PCL_EXTRACT_LABELED_CLUSTERS_H_
00037 #define PCL_EXTRACT_LABELED_CLUSTERS_H_
00038 
00039 #include <pcl/pcl_base.h>
00040 #include <pcl/search/pcl_search.h>
00041 
00042 namespace pcl
00043 {
00045 
00056   template <typename PointT> void 
00057   extractLabeledEuclideanClusters (
00058       const PointCloud<PointT> &cloud, const boost::shared_ptr<search::Search<PointT> > &tree, 
00059       float tolerance, std::vector<std::vector<PointIndices> > &labeled_clusters, 
00060       unsigned int min_pts_per_cluster = 1, unsigned int max_pts_per_cluster = (std::numeric_limits<int>::max) (), 
00061       unsigned int max_label = (std::numeric_limits<int>::max));
00062 
00066 
00070   template <typename PointT>
00071   class LabeledEuclideanClusterExtraction: public PCLBase<PointT>
00072   {
00073     typedef PCLBase<PointT> BasePCLBase;
00074 
00075     public:
00076       typedef pcl::PointCloud<PointT> PointCloud;
00077       typedef typename PointCloud::Ptr PointCloudPtr;
00078       typedef typename PointCloud::ConstPtr PointCloudConstPtr;
00079 
00080       typedef typename pcl::search::Search<PointT> KdTree;
00081       typedef typename pcl::search::Search<PointT>::Ptr KdTreePtr;
00082 
00083       typedef PointIndices::Ptr PointIndicesPtr;
00084       typedef PointIndices::ConstPtr PointIndicesConstPtr;
00085 
00087 
00088       LabeledEuclideanClusterExtraction () : 
00089         tree_ (), 
00090         cluster_tolerance_ (0),
00091         min_pts_per_cluster_ (1), 
00092         max_pts_per_cluster_ (std::numeric_limits<int>::max ()),
00093         max_label_ (std::numeric_limits<int>::max ())
00094       {};
00095 
00099       inline void 
00100       setSearchMethod (const KdTreePtr &tree) { tree_ = tree; }
00101 
00103       inline KdTreePtr 
00104       getSearchMethod () const { return (tree_); }
00105 
00109       inline void 
00110       setClusterTolerance (double tolerance) { cluster_tolerance_ = tolerance; }
00111 
00113       inline double 
00114       getClusterTolerance () const { return (cluster_tolerance_); }
00115 
00119       inline void 
00120       setMinClusterSize (int min_cluster_size) { min_pts_per_cluster_ = min_cluster_size; }
00121 
00123       inline int 
00124       getMinClusterSize () const { return (min_pts_per_cluster_); }
00125 
00129       inline void 
00130       setMaxClusterSize (int max_cluster_size) { max_pts_per_cluster_ = max_cluster_size; }
00131 
00133       inline int 
00134       getMaxClusterSize () const { return (max_pts_per_cluster_); }
00135 
00139       inline void 
00140       setMaxLabels (unsigned int max_label) { max_label_ = max_label; }
00141 
00143       inline unsigned int 
00144       getMaxLabels () const { return (max_label_); }
00145 
00149       void 
00150       extract (std::vector<std::vector<PointIndices> > &labeled_clusters);
00151 
00152     protected:
00153       // Members derived from the base class
00154       using BasePCLBase::input_;
00155       using BasePCLBase::indices_;
00156       using BasePCLBase::initCompute;
00157       using BasePCLBase::deinitCompute;
00158 
00160       KdTreePtr tree_;
00161 
00163       double cluster_tolerance_;
00164 
00166       int min_pts_per_cluster_;
00167 
00169       int max_pts_per_cluster_;
00170 
00172       unsigned int max_label_;
00173 
00175       virtual std::string getClassName () const { return ("LabeledEuclideanClusterExtraction"); }
00176 
00177   };
00178 
00182   inline bool 
00183     compareLabeledPointClusters (const pcl::PointIndices &a, const pcl::PointIndices &b)
00184   {
00185     return (a.indices.size () < b.indices.size ());
00186   }
00187 }
00188 
00189 #endif  //#ifndef PCL_EXTRACT_LABELED_CLUSTERS_H_


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