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
00040 #ifndef PCL_REGION_GROWING_RGB_H_
00041 #define PCL_REGION_GROWING_RGB_H_
00042
00043 #include <pcl/segmentation/region_growing.h>
00044
00045 namespace pcl
00046 {
00053 template <typename PointT, typename NormalT = pcl::Normal>
00054 class PCL_EXPORTS RegionGrowingRGB : public RegionGrowing<PointT, NormalT>
00055 {
00056 public:
00057
00058 using RegionGrowing<PointT, NormalT>::input_;
00059 using RegionGrowing<PointT, NormalT>::indices_;
00060 using RegionGrowing<PointT, NormalT>::initCompute;
00061 using RegionGrowing<PointT, NormalT>::deinitCompute;
00062 using RegionGrowing<PointT, NormalT>::normals_;
00063 using RegionGrowing<PointT, NormalT>::normal_flag_;
00064 using RegionGrowing<PointT, NormalT>::curvature_flag_;
00065 using RegionGrowing<PointT, NormalT>::residual_flag_;
00066 using RegionGrowing<PointT, NormalT>::residual_threshold_;
00067 using RegionGrowing<PointT, NormalT>::neighbour_number_;
00068 using RegionGrowing<PointT, NormalT>::search_;
00069 using RegionGrowing<PointT, NormalT>::min_pts_per_cluster_;
00070 using RegionGrowing<PointT, NormalT>::max_pts_per_cluster_;
00071 using RegionGrowing<PointT, NormalT>::smooth_mode_flag_;
00072 using RegionGrowing<PointT, NormalT>::theta_threshold_;
00073 using RegionGrowing<PointT, NormalT>::curvature_threshold_;
00074 using RegionGrowing<PointT, NormalT>::point_neighbours_;
00075 using RegionGrowing<PointT, NormalT>::point_labels_;
00076 using RegionGrowing<PointT, NormalT>::num_pts_in_segment_;
00077 using RegionGrowing<PointT, NormalT>::clusters_;
00078 using RegionGrowing<PointT, NormalT>::number_of_segments_;
00079 using RegionGrowing<PointT, NormalT>::applySmoothRegionGrowingAlgorithm;
00080 using RegionGrowing<PointT, NormalT>::assembleRegions;
00081
00082 public:
00083
00085 RegionGrowingRGB ();
00086
00088 virtual
00089 ~RegionGrowingRGB ();
00090
00092 float
00093 getPointColorThreshold () const;
00094
00101 void
00102 setPointColorThreshold (float thresh);
00103
00105 float
00106 getRegionColorThreshold () const;
00107
00113 void
00114 setRegionColorThreshold (float thresh);
00115
00119 float
00120 getDistanceThreshold () const;
00121
00125 void
00126 setDistanceThreshold (float thresh);
00127
00131 unsigned int
00132 getNumberOfRegionNeighbours () const;
00133
00138 void
00139 setNumberOfRegionNeighbours (unsigned int nghbr_number);
00140
00142 bool
00143 getNormalTestFlag () const;
00144
00149 void
00150 setNormalTestFlag (bool value);
00151
00155 virtual void
00156 setCurvatureTestFlag (bool value);
00157
00162 virtual void
00163 setResidualTestFlag (bool value);
00164
00169 virtual void
00170 extract (std::vector <pcl::PointIndices>& clusters);
00171
00175 virtual void
00176 getSegmentFromPoint (int index, pcl::PointIndices& cluster);
00177
00178 protected:
00179
00183 virtual bool
00184 prepareForSegmentation ();
00185
00189 virtual void
00190 findPointNeighbours ();
00191
00195 void
00196 findSegmentNeighbours ();
00197
00204 void
00205 findRegionsKNN (int index, int nghbr_number, std::vector<int>& nghbrs, std::vector<float>& dist);
00206
00211 void
00212 applyRegionMergingAlgorithm ();
00213
00219 float
00220 calculateColorimetricalDifference (std::vector<unsigned int>& first_color, std::vector<unsigned int>& second_color) const;
00221
00229 void
00230 findRegionNeighbours (std::vector< std::vector< std::pair<float, int> > >& neighbours_out, std::vector< std::vector<int> >& regions_in);
00231
00236 void
00237 assembleRegions (std::vector<unsigned int>& num_pts_in_region, int num_regions);
00238
00246 virtual bool
00247 validatePoint (int initial_seed, int point, int nghbr, bool& is_a_seed) const;
00248
00249 protected:
00250
00252 float color_p2p_threshold_;
00253
00255 float color_r2r_threshold_;
00256
00258 float distance_threshold_;
00259
00261 unsigned int region_neighbour_number_;
00262
00264 std::vector< std::vector<float> > point_distances_;
00265
00267 std::vector< std::vector<int> > segment_neighbours_;
00268
00270 std::vector< std::vector<float> > segment_distances_;
00271
00273 std::vector<int> segment_labels_;
00274
00275 public:
00276 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00277 };
00278 }
00279
00280 #ifdef PCL_NO_PRECOMPILE
00281 #include <pcl/segmentation/impl/region_growing_rgb.hpp>
00282 #endif
00283
00284 #endif