Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037
00038
00039 #ifndef PCL_SEEDED_HUE_SEGMENTATION_H_
00040 #define PCL_SEEDED_HUE_SEGMENTATION_H_
00041
00042 #include <pcl/pcl_base.h>
00043 #include <pcl/point_types_conversion.h>
00044 #include <pcl/search/pcl_search.h>
00045
00046 namespace pcl
00047 {
00049
00060 void
00061 seededHueSegmentation (const PointCloud<PointXYZRGB> &cloud,
00062 const boost::shared_ptr<search::Search<PointXYZRGB> > &tree,
00063 float tolerance,
00064 PointIndices &indices_in,
00065 PointIndices &indices_out,
00066 float delta_hue = 0.0);
00067
00079 void
00080 seededHueSegmentation (const PointCloud<PointXYZRGB> &cloud,
00081 const boost::shared_ptr<search::Search<PointXYZRGBL> > &tree,
00082 float tolerance,
00083 PointIndices &indices_in,
00084 PointIndices &indices_out,
00085 float delta_hue = 0.0);
00086
00090
00094 class SeededHueSegmentation: public PCLBase<PointXYZRGB>
00095 {
00096 typedef PCLBase<PointXYZRGB> BasePCLBase;
00097
00098 public:
00099 typedef pcl::PointCloud<PointXYZRGB> PointCloud;
00100 typedef PointCloud::Ptr PointCloudPtr;
00101 typedef PointCloud::ConstPtr PointCloudConstPtr;
00102
00103 typedef pcl::search::Search<PointXYZRGB> KdTree;
00104 typedef pcl::search::Search<PointXYZRGB>::Ptr KdTreePtr;
00105
00106 typedef PointIndices::Ptr PointIndicesPtr;
00107 typedef PointIndices::ConstPtr PointIndicesConstPtr;
00108
00110
00111 SeededHueSegmentation () : tree_ (), cluster_tolerance_ (0), delta_hue_ (0.0)
00112 {};
00113
00117 inline void
00118 setSearchMethod (const KdTreePtr &tree) { tree_ = tree; }
00119
00121 inline KdTreePtr
00122 getSearchMethod () const { return (tree_); }
00123
00127 inline void
00128 setClusterTolerance (double tolerance) { cluster_tolerance_ = tolerance; }
00129
00131 inline double
00132 getClusterTolerance () const { return (cluster_tolerance_); }
00133
00137 inline void
00138 setDeltaHue (float delta_hue) { delta_hue_ = delta_hue; }
00139
00141 inline float
00142 getDeltaHue () const { return (delta_hue_); }
00143
00148 void
00149 segment (PointIndices &indices_in, PointIndices &indices_out);
00150
00151 protected:
00152
00153 using BasePCLBase::input_;
00154 using BasePCLBase::indices_;
00155 using BasePCLBase::initCompute;
00156 using BasePCLBase::deinitCompute;
00157
00159 KdTreePtr tree_;
00160
00162 double cluster_tolerance_;
00163
00165 float delta_hue_;
00166
00168 virtual std::string getClassName () const { return ("seededHueSegmentation"); }
00169 };
00170 }
00171
00172 #ifdef PCL_NO_PRECOMPILE
00173 #include <pcl/segmentation/impl/seeded_hue_segmentation.hpp>
00174 #endif
00175
00176 #endif //#ifndef PCL_SEEDED_HUE_SEGMENTATION_H_