region_growing.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  *
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  * Author : Sergey Ushakov
00036  * Email  : mine_all_mine@bk.ru
00037  *
00038  */
00039 
00040 #ifndef PCL_REGION_GROWING_H_
00041 #define PCL_REGION_GROWING_H_
00042 
00043 #include <pcl/pcl_base.h>
00044 #include <pcl/search/search.h>
00045 #include <pcl/point_cloud.h>
00046 #include <pcl/point_types.h>
00047 #include <list>
00048 #include <math.h>
00049 #include <time.h>
00050 
00051 namespace pcl
00052 {
00060   template <typename PointT, typename NormalT>
00061   class PCL_EXPORTS RegionGrowing : public pcl::PCLBase<PointT>
00062   {
00063     public:
00064 
00065       typedef pcl::search::Search <PointT> KdTree;
00066       typedef typename KdTree::Ptr KdTreePtr;
00067       typedef pcl::PointCloud <NormalT> Normal;
00068       typedef typename Normal::Ptr NormalPtr;
00069       typedef pcl::PointCloud <PointT> PointCloud;
00070 
00071       using PCLBase <PointT>::input_;
00072       using PCLBase <PointT>::indices_;
00073       using PCLBase <PointT>::initCompute;
00074       using PCLBase <PointT>::deinitCompute;
00075 
00076     public:
00077 
00079       RegionGrowing ();
00080 
00084       virtual
00085       ~RegionGrowing ();
00086 
00088       int
00089       getMinClusterSize ();
00090 
00092       void
00093       setMinClusterSize (int min_cluster_size);
00094 
00096       int
00097       getMaxClusterSize ();
00098 
00100       void
00101       setMaxClusterSize (int max_cluster_size);
00102 
00109       bool
00110       getSmoothModeFlag () const;
00111 
00115       void
00116       setSmoothModeFlag (bool value);
00117 
00119       bool
00120       getCurvatureTestFlag () const;
00121 
00127       virtual void
00128       setCurvatureTestFlag (bool value);
00129 
00131       bool
00132       getResidualTestFlag () const;
00133 
00140       virtual void
00141       setResidualTestFlag (bool value);
00142 
00144       float
00145       getSmoothnessThreshold () const;
00146 
00150       void
00151       setSmoothnessThreshold (float theta);
00152 
00154       float
00155       getResidualThreshold () const;
00156 
00160       void
00161       setResidualThreshold (float residual);
00162 
00164       float
00165       getCurvatureThreshold () const;
00166 
00170       void
00171       setCurvatureThreshold (float curvature);
00172 
00174       unsigned int
00175       getNumberOfNeighbours () const;
00176 
00180       void
00181       setNumberOfNeighbours (unsigned int neighbour_number);
00182 
00184       KdTreePtr
00185       getSearchMethod () const;
00186 
00190       void
00191       setSearchMethod (const KdTreePtr& tree);
00192 
00194       NormalPtr
00195       getInputNormals () const;
00196 
00201       void
00202       setInputNormals (const NormalPtr& norm);
00203 
00208       virtual void
00209       extract (std::vector <pcl::PointIndices>& clusters);
00210 
00215       virtual void
00216       getSegmentFromPoint (int index, pcl::PointIndices& cluster);
00217 
00224       pcl::PointCloud<pcl::PointXYZRGB>::Ptr
00225       getColoredCloud ();
00226 
00233       pcl::PointCloud<pcl::PointXYZRGBA>::Ptr
00234       getColoredCloudRGBA ();
00235 
00236     protected:
00237 
00241       virtual bool
00242       prepareForSegmentation ();
00243 
00247       virtual void
00248       findPointNeighbours ();
00249 
00254       void
00255       applySmoothRegionGrowingAlgorithm ();
00256 
00261       int
00262       growRegion (int initial_seed, int segment_number);
00263 
00271       virtual bool
00272       validatePoint (int initial_seed, int point, int nghbr, bool& is_a_seed) const;
00273 
00278       void
00279       assembleRegions ();
00280 
00281     protected:
00282 
00284       int min_pts_per_cluster_;
00285 
00287       int max_pts_per_cluster_;
00288 
00290       bool smooth_mode_flag_;
00291 
00293       bool curvature_flag_;
00294 
00296       bool residual_flag_;
00297 
00299       float theta_threshold_;
00300 
00302       float residual_threshold_;
00303 
00305       float curvature_threshold_;
00306 
00308       unsigned int neighbour_number_;
00309 
00311       KdTreePtr search_;
00312 
00314       NormalPtr normals_;
00315 
00317       std::vector<std::vector<int> > point_neighbours_;
00318 
00320       std::vector<int> point_labels_;
00321 
00325       bool normal_flag_;
00326 
00328       std::vector<int> num_pts_in_segment_;
00329 
00331       std::vector <pcl::PointIndices> clusters_;
00332 
00334       int number_of_segments_;
00335 
00336     public:
00337       EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00338   };
00339 
00341   inline bool
00342   comparePair (std::pair<float, int> i, std::pair<float, int> j)
00343   {
00344     return (i.first < j.first);
00345   }
00346 }
00347 
00348 #ifdef PCL_NO_PRECOMPILE
00349 #include <pcl/segmentation/impl/region_growing.hpp>
00350 #endif
00351 
00352 #endif


pcl
Author(s): Open Perception
autogenerated on Wed Aug 26 2015 15:32:02