Public Member Functions | Protected Member Functions | Protected Attributes
pcl::RegionGrowingRGB< PointT, NormalT > Class Template Reference

Implements the well known Region Growing algorithm used for segmentation based on color of points. Description can be found in the article "Color-based segmentation of point clouds" by Qingming Zhan, Yubin Liang, Yinghui Xiao. More...

#include <region_growing_rgb.h>

Inheritance diagram for pcl::RegionGrowingRGB< PointT, NormalT >:
Inheritance graph
[legend]

List of all members.

Public Member Functions

virtual void extract (std::vector< pcl::PointIndices > &clusters)
 This method launches the segmentation algorithm and returns the clusters that were obtained during the segmentation.
float getDistanceThreshold () const
 Returns the distance threshold. If the distance between two points is less or equal to distance threshold value, then those points assumed to be neighbouring points.
bool getNormalTestFlag () const
 Returns the flag that signalize if the smoothness test is turned on/off.
unsigned int getNumberOfRegionNeighbours () const
 Returns the number of nearest neighbours used for searching K nearest segments. Note that here it refers to the segments(not the points).
float getPointColorThreshold () const
 Returns the color threshold value used for testing if points belong to the same region.
float getRegionColorThreshold () const
 Returns the color threshold value used for testing if regions can be merged.
virtual void getSegmentFromPoint (int index, pcl::PointIndices &cluster)
 For a given point this function builds a segment to which it belongs and returns this segment.
 RegionGrowingRGB ()
 Constructor that sets default values for member variables.
virtual void setCurvatureTestFlag (bool value)
 Allows to turn on/off the curvature test.
void setDistanceThreshold (float thresh)
 Allows to set distance threshold.
void setNormalTestFlag (bool value)
 Allows to turn on/off the smoothness test.
void setNumberOfRegionNeighbours (unsigned int nghbr_number)
 This method allows to set the number of neighbours that is used for finding neighbouring segments. Neighbouring segments are needed for the merging process.
void setPointColorThreshold (float thresh)
 This method specifies the threshold value for color test between the points. This kind of testing is made at the first stage of the algorithm(region growing). If the difference between points color is less than threshold value, then they are considered to be in the same region.
void setRegionColorThreshold (float thresh)
 This method specifies the threshold value for color test between the regions. This kind of testing is made at the second stage of the algorithm(region merging). If the difference between segments color is less than threshold value, then they are merged together.
virtual void setResidualTestFlag (bool value)
 Allows to turn on/off the residual test.
virtual ~RegionGrowingRGB ()
 Destructor that frees memory.

Protected Member Functions

void applyRegionMergingAlgorithm ()
 This function implements the merging algorithm described in the article "Color-based segmentation of point clouds" by Qingming Zhan, Yubin Liang, Yinghui Xiao.
void assembleRegions (std::vector< unsigned int > &num_pts_in_region, int num_regions)
 This function simply assembles the regions from list of point labels.
float calculateColorimetricalDifference (std::vector< unsigned int > &first_color, std::vector< unsigned int > &second_color) const
 This method calculates the colorimetrical difference between two points. In this case it simply returns the euclidean distance between two colors.
virtual void findPointNeighbours ()
 This method finds KNN for each point and saves them to the array because the algorithm needs to find KNN a few times.
void findRegionNeighbours (std::vector< std::vector< std::pair< float, int > > > &neighbours_out, std::vector< std::vector< int > > &regions_in)
 This method assembles the array containing neighbours of each homogeneous region. Homogeneous region is the union of some segments. This array is used when the regions with a few points need to be merged with the neighbouring region.
void findRegionsKNN (int index, int nghbr_number, std::vector< int > &nghbrs, std::vector< float > &dist)
 This method finds K nearest neighbours of the given segment.
void findSegmentNeighbours ()
 This method simply calls the findRegionsKNN for each segment and saves the results for later use.
virtual bool prepareForSegmentation ()
 This method simply checks if it is possible to execute the segmentation algorithm with the current settings. If it is possible then it returns true.
virtual bool validatePoint (int initial_seed, int point, int nghbr, bool &is_a_seed) const
 This function is checking if the point with index 'nghbr' belongs to the segment. If so, then it returns true. It also checks if this point can serve as the seed.

Protected Attributes

float color_p2p_threshold_
 Thershold used in color test for points.
float color_r2r_threshold_
 Thershold used in color test for regions.
float distance_threshold_
 Threshold that tells which points we need to assume neighbouring.
std::vector< std::vector< float > > point_distances_
 Stores distances for the point neighbours from point_neighbours_.
unsigned int region_neighbour_number_
 Number of neighbouring segments to find.
std::vector< std::vector< float > > segment_distances_
 Stores distances for the segment neighbours from segment_neighbours_.
std::vector< int > segment_labels_
 Stores new indices for segments that were obtained at the region growing stage.
std::vector< std::vector< int > > segment_neighbours_
 Stores the neighboures for the corresponding segments.

Detailed Description

template<typename PointT, typename NormalT = pcl::Normal>
class pcl::RegionGrowingRGB< PointT, NormalT >

Implements the well known Region Growing algorithm used for segmentation based on color of points. Description can be found in the article "Color-based segmentation of point clouds" by Qingming Zhan, Yubin Liang, Yinghui Xiao.

Definition at line 54 of file region_growing_rgb.h.


Constructor & Destructor Documentation

template<typename PointT , typename NormalT >
pcl::RegionGrowingRGB< PointT, NormalT >::RegionGrowingRGB ( )

Constructor that sets default values for member variables.

Definition at line 51 of file region_growing_rgb.hpp.

template<typename PointT , typename NormalT >
pcl::RegionGrowingRGB< PointT, NormalT >::~RegionGrowingRGB ( ) [virtual]

Destructor that frees memory.

Definition at line 69 of file region_growing_rgb.hpp.


Member Function Documentation

template<typename PointT , typename NormalT >
void pcl::RegionGrowingRGB< PointT, NormalT >::applyRegionMergingAlgorithm ( ) [protected]

This function implements the merging algorithm described in the article "Color-based segmentation of point clouds" by Qingming Zhan, Yubin Liang, Yinghui Xiao.

Definition at line 367 of file region_growing_rgb.hpp.

template<typename PointT , typename NormalT >
void pcl::RegionGrowingRGB< PointT, NormalT >::assembleRegions ( std::vector< unsigned int > &  num_pts_in_region,
int  num_regions 
) [protected]

This function simply assembles the regions from list of point labels.

Parameters:
[in]num_pts_in_regionfor each final region it stores the corresponding number of points in it
[in]num_regionsnumber of regions to assemble

Definition at line 564 of file region_growing_rgb.hpp.

template<typename PointT , typename NormalT >
float pcl::RegionGrowingRGB< PointT, NormalT >::calculateColorimetricalDifference ( std::vector< unsigned int > &  first_color,
std::vector< unsigned int > &  second_color 
) const [protected]

This method calculates the colorimetrical difference between two points. In this case it simply returns the euclidean distance between two colors.

Parameters:
[in]first_colorthe color of the first point
[in]second_colorthe color of the second point

Definition at line 519 of file region_growing_rgb.hpp.

template<typename PointT , typename NormalT >
void pcl::RegionGrowingRGB< PointT, NormalT >::extract ( std::vector< pcl::PointIndices > &  clusters) [virtual]

This method launches the segmentation algorithm and returns the clusters that were obtained during the segmentation.

Parameters:
[out]clustersclusters that were obtained. Each cluster is an array of point indices.

Reimplemented from pcl::RegionGrowing< PointT, NormalT >.

Definition at line 163 of file region_growing_rgb.hpp.

template<typename PointT , typename NormalT >
void pcl::RegionGrowingRGB< PointT, NormalT >::findPointNeighbours ( ) [protected, virtual]

This method finds KNN for each point and saves them to the array because the algorithm needs to find KNN a few times.

Reimplemented from pcl::RegionGrowing< PointT, NormalT >.

Definition at line 271 of file region_growing_rgb.hpp.

template<typename PointT , typename NormalT >
void pcl::RegionGrowingRGB< PointT, NormalT >::findRegionNeighbours ( std::vector< std::vector< std::pair< float, int > > > &  neighbours_out,
std::vector< std::vector< int > > &  regions_in 
) [protected]

This method assembles the array containing neighbours of each homogeneous region. Homogeneous region is the union of some segments. This array is used when the regions with a few points need to be merged with the neighbouring region.

Parameters:
[out]neighbours_outvector of lists of neighbours for every homogeneous region
[in]regions_invector of lists, each list contains indices of segments that belong to the corresponding homogeneous region.

Definition at line 530 of file region_growing_rgb.hpp.

template<typename PointT , typename NormalT >
void pcl::RegionGrowingRGB< PointT, NormalT >::findRegionsKNN ( int  index,
int  nghbr_number,
std::vector< int > &  nghbrs,
std::vector< float > &  dist 
) [protected]

This method finds K nearest neighbours of the given segment.

Parameters:
[in]indexindex of the segment for which neighbours will be found
[in]nghbr_numberthe number of neighbours to find
[out]nghbrsthe array of indices of the neighbours that were found
[out]distthe array of distances to the corresponding neighbours

Definition at line 312 of file region_growing_rgb.hpp.

template<typename PointT , typename NormalT >
void pcl::RegionGrowingRGB< PointT, NormalT >::findSegmentNeighbours ( ) [protected]

This method simply calls the findRegionsKNN for each segment and saves the results for later use.

Definition at line 293 of file region_growing_rgb.hpp.

template<typename PointT , typename NormalT >
float pcl::RegionGrowingRGB< PointT, NormalT >::getDistanceThreshold ( ) const

Returns the distance threshold. If the distance between two points is less or equal to distance threshold value, then those points assumed to be neighbouring points.

Definition at line 107 of file region_growing_rgb.hpp.

template<typename PointT , typename NormalT >
bool pcl::RegionGrowingRGB< PointT, NormalT >::getNormalTestFlag ( ) const

Returns the flag that signalize if the smoothness test is turned on/off.

Definition at line 135 of file region_growing_rgb.hpp.

template<typename PointT , typename NormalT >
unsigned int pcl::RegionGrowingRGB< PointT, NormalT >::getNumberOfRegionNeighbours ( ) const

Returns the number of nearest neighbours used for searching K nearest segments. Note that here it refers to the segments(not the points).

Definition at line 121 of file region_growing_rgb.hpp.

template<typename PointT , typename NormalT >
float pcl::RegionGrowingRGB< PointT, NormalT >::getPointColorThreshold ( ) const

Returns the color threshold value used for testing if points belong to the same region.

Definition at line 79 of file region_growing_rgb.hpp.

template<typename PointT , typename NormalT >
float pcl::RegionGrowingRGB< PointT, NormalT >::getRegionColorThreshold ( ) const

Returns the color threshold value used for testing if regions can be merged.

Definition at line 93 of file region_growing_rgb.hpp.

template<typename PointT , typename NormalT >
void pcl::RegionGrowingRGB< PointT, NormalT >::getSegmentFromPoint ( int  index,
pcl::PointIndices cluster 
) [virtual]

For a given point this function builds a segment to which it belongs and returns this segment.

Parameters:
[in]indexindex of the initial point which will be the seed for growing a segment.

Reimplemented from pcl::RegionGrowing< PointT, NormalT >.

Definition at line 679 of file region_growing_rgb.hpp.

template<typename PointT , typename NormalT >
bool pcl::RegionGrowingRGB< PointT, NormalT >::prepareForSegmentation ( ) [protected, virtual]

This method simply checks if it is possible to execute the segmentation algorithm with the current settings. If it is possible then it returns true.

Reimplemented from pcl::RegionGrowing< PointT, NormalT >.

Definition at line 216 of file region_growing_rgb.hpp.

template<typename PointT , typename NormalT >
void pcl::RegionGrowingRGB< PointT, NormalT >::setCurvatureTestFlag ( bool  value) [virtual]

Allows to turn on/off the curvature test.

Parameters:
[in]valuenew value for curvature test. If set to true then the test will be turned on

Reimplemented from pcl::RegionGrowing< PointT, NormalT >.

Definition at line 149 of file region_growing_rgb.hpp.

template<typename PointT , typename NormalT >
void pcl::RegionGrowingRGB< PointT, NormalT >::setDistanceThreshold ( float  thresh)

Allows to set distance threshold.

Parameters:
[in]threshnew threshold value for neighbour test

Definition at line 114 of file region_growing_rgb.hpp.

template<typename PointT , typename NormalT >
void pcl::RegionGrowingRGB< PointT, NormalT >::setNormalTestFlag ( bool  value)

Allows to turn on/off the smoothness test.

Parameters:
[in]valuenew value for normal/smoothness test. If set to true then the test will be turned on

Definition at line 142 of file region_growing_rgb.hpp.

template<typename PointT , typename NormalT >
void pcl::RegionGrowingRGB< PointT, NormalT >::setNumberOfRegionNeighbours ( unsigned int  nghbr_number)

This method allows to set the number of neighbours that is used for finding neighbouring segments. Neighbouring segments are needed for the merging process.

Parameters:
[in]nghbr_numberthe number of neighbouring segments to find

Definition at line 128 of file region_growing_rgb.hpp.

template<typename PointT , typename NormalT >
void pcl::RegionGrowingRGB< PointT, NormalT >::setPointColorThreshold ( float  thresh)

This method specifies the threshold value for color test between the points. This kind of testing is made at the first stage of the algorithm(region growing). If the difference between points color is less than threshold value, then they are considered to be in the same region.

Parameters:
[in]threshnew threshold value for color test

Definition at line 86 of file region_growing_rgb.hpp.

template<typename PointT , typename NormalT >
void pcl::RegionGrowingRGB< PointT, NormalT >::setRegionColorThreshold ( float  thresh)

This method specifies the threshold value for color test between the regions. This kind of testing is made at the second stage of the algorithm(region merging). If the difference between segments color is less than threshold value, then they are merged together.

Parameters:
[in]threshnew threshold value for color test

Definition at line 100 of file region_growing_rgb.hpp.

template<typename PointT , typename NormalT >
void pcl::RegionGrowingRGB< PointT, NormalT >::setResidualTestFlag ( bool  value) [virtual]

Allows to turn on/off the residual test.

Parameters:
[in]valuenew value for residual test. If set to true then the test will be turned on

Reimplemented from pcl::RegionGrowing< PointT, NormalT >.

Definition at line 156 of file region_growing_rgb.hpp.

template<typename PointT , typename NormalT >
bool pcl::RegionGrowingRGB< PointT, NormalT >::validatePoint ( int  initial_seed,
int  point,
int  nghbr,
bool &  is_a_seed 
) const [protected, virtual]

This function is checking if the point with index 'nghbr' belongs to the segment. If so, then it returns true. It also checks if this point can serve as the seed.

Parameters:
[in]initial_seedindex of the initial point that was passed to the growRegion() function
[in]pointindex of the current seed point
[in]nghbrindex of the point that is neighbour of the current seed
[out]is_a_seedthis value is set to true if the point with index 'nghbr' can serve as the seed

Reimplemented from pcl::RegionGrowing< PointT, NormalT >.

Definition at line 600 of file region_growing_rgb.hpp.


Member Data Documentation

template<typename PointT, typename NormalT = pcl::Normal>
float pcl::RegionGrowingRGB< PointT, NormalT >::color_p2p_threshold_ [protected]

Thershold used in color test for points.

Definition at line 252 of file region_growing_rgb.h.

template<typename PointT, typename NormalT = pcl::Normal>
float pcl::RegionGrowingRGB< PointT, NormalT >::color_r2r_threshold_ [protected]

Thershold used in color test for regions.

Definition at line 255 of file region_growing_rgb.h.

template<typename PointT, typename NormalT = pcl::Normal>
float pcl::RegionGrowingRGB< PointT, NormalT >::distance_threshold_ [protected]

Threshold that tells which points we need to assume neighbouring.

Definition at line 258 of file region_growing_rgb.h.

template<typename PointT, typename NormalT = pcl::Normal>
std::vector< std::vector<float> > pcl::RegionGrowingRGB< PointT, NormalT >::point_distances_ [protected]

Stores distances for the point neighbours from point_neighbours_.

Definition at line 264 of file region_growing_rgb.h.

template<typename PointT, typename NormalT = pcl::Normal>
unsigned int pcl::RegionGrowingRGB< PointT, NormalT >::region_neighbour_number_ [protected]

Number of neighbouring segments to find.

Definition at line 261 of file region_growing_rgb.h.

template<typename PointT, typename NormalT = pcl::Normal>
std::vector< std::vector<float> > pcl::RegionGrowingRGB< PointT, NormalT >::segment_distances_ [protected]

Stores distances for the segment neighbours from segment_neighbours_.

Definition at line 270 of file region_growing_rgb.h.

template<typename PointT, typename NormalT = pcl::Normal>
std::vector<int> pcl::RegionGrowingRGB< PointT, NormalT >::segment_labels_ [protected]

Stores new indices for segments that were obtained at the region growing stage.

Definition at line 273 of file region_growing_rgb.h.

template<typename PointT, typename NormalT = pcl::Normal>
std::vector< std::vector<int> > pcl::RegionGrowingRGB< PointT, NormalT >::segment_neighbours_ [protected]

Stores the neighboures for the corresponding segments.

Definition at line 267 of file region_growing_rgb.h.


The documentation for this class was generated from the following files:


pcl
Author(s): Open Perception
autogenerated on Wed Aug 26 2015 15:43:08