organized_connected_component_segmentation.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-2012, 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 Willow Garage, Inc. 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  */
00039 
00040 #ifndef PCL_SEGMENTATION_ORGANIZED_CONNECTED_COMPONENT_SEGMENTATION_H_
00041 #define PCL_SEGMENTATION_ORGANIZED_CONNECTED_COMPONENT_SEGMENTATION_H_
00042 
00043 #include <pcl/pcl_base.h>
00044 #include <pcl/PointIndices.h>
00045 #include <pcl/segmentation/comparator.h>
00046 
00047 namespace pcl
00048 {
00058   template <typename PointT, typename PointLT>
00059   class OrganizedConnectedComponentSegmentation : public PCLBase<PointT>
00060   {
00061     using PCLBase<PointT>::input_;
00062     using PCLBase<PointT>::indices_;
00063     using PCLBase<PointT>::initCompute;
00064     using PCLBase<PointT>::deinitCompute;
00065 
00066     public:
00067       typedef typename pcl::PointCloud<PointT> PointCloud;
00068       typedef typename PointCloud::Ptr PointCloudPtr;
00069       typedef typename PointCloud::ConstPtr PointCloudConstPtr;
00070       
00071       typedef typename pcl::PointCloud<PointLT> PointCloudL;
00072       typedef typename PointCloudL::Ptr PointCloudLPtr;
00073       typedef typename PointCloudL::ConstPtr PointCloudLConstPtr;
00074 
00075       typedef typename pcl::Comparator<PointT> Comparator;
00076       typedef typename Comparator::Ptr ComparatorPtr;
00077       typedef typename Comparator::ConstPtr ComparatorConstPtr;
00078       
00082       OrganizedConnectedComponentSegmentation (const ComparatorConstPtr& compare)
00083         : compare_ (compare)
00084       {
00085       }
00086 
00088       virtual
00089       ~OrganizedConnectedComponentSegmentation ()
00090       {
00091       }
00092 
00096       void
00097       setComparator (const ComparatorConstPtr& compare)
00098       {
00099         compare_ = compare;
00100       }
00101       
00103       ComparatorConstPtr
00104       getComparator () const { return (compare_); }
00105 
00110       void
00111       segment (pcl::PointCloud<PointLT>& labels, std::vector<pcl::PointIndices>& label_indices) const;
00112       
00118       static void
00119       findLabeledRegionBoundary (int start_idx, PointCloudLPtr labels, pcl::PointIndices& boundary_indices);      
00120       
00121 
00122     protected:
00123       ComparatorConstPtr compare_;
00124       
00125       inline unsigned
00126       findRoot (const std::vector<unsigned>& runs, unsigned index) const
00127       {
00128         register unsigned idx = index;
00129         while (runs[idx] != idx)
00130           idx = runs[idx];
00131 
00132         return (idx);
00133       }
00134 
00135     private:
00136       struct Neighbor
00137       {
00138         Neighbor (int dx, int dy, int didx)
00139         : d_x (dx)
00140         , d_y (dy)
00141         , d_index (didx)
00142         {}
00143         
00144         int d_x;
00145         int d_y;
00146         int d_index; // = dy * width + dx: pre-calculated
00147       };
00148   };
00149 }
00150 
00151 #endif //#ifndef PCL_ORGANIZED_CONNECTED_COMPONENT_SEGMENTATION_H_


pcl
Author(s): Open Perception
autogenerated on Mon Oct 6 2014 03:16:09