Implements the well known Region Growing algorithm used for segmentation. Description can be found in the article "Segmentation of point clouds using smoothness constraint" by T. Rabbania, F. A. van den Heuvelb, G. Vosselmanc. In addition to residual test, the possibility to test curvature is added. More...
#include <region_growing.h>
Public Types | |
typedef pcl::search::Search < PointT > | KdTree |
typedef KdTree::Ptr | KdTreePtr |
typedef pcl::PointCloud< NormalT > | Normal |
typedef Normal::Ptr | NormalPtr |
typedef pcl::PointCloud< PointT > | PointCloud |
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. | |
pcl::PointCloud < pcl::PointXYZRGB >::Ptr | getColoredCloud () |
If the cloud was successfully segmented, then function returns colored cloud. Otherwise it returns an empty pointer. Points that belong to the same segment have the same color. But this function doesn't guarantee that different segments will have different color(it all depends on RNG). Points that were not listed in the indices array will have red color. | |
pcl::PointCloud < pcl::PointXYZRGBA >::Ptr | getColoredCloudRGBA () |
If the cloud was successfully segmented, then function returns colored cloud. Otherwise it returns an empty pointer. Points that belong to the same segment have the same color. But this function doesn't guarantee that different segments will have different color(it all depends on RNG). Points that were not listed in the indices array will have red color. | |
bool | getCurvatureTestFlag () const |
Returns the flag that signalize if the curvature test is turned on/off. | |
float | getCurvatureThreshold () const |
Returns curvature threshold. | |
NormalPtr | getInputNormals () const |
Returns normals. | |
int | getMaxClusterSize () |
Get the maximum number of points that a cluster needs to contain in order to be considered valid. | |
int | getMinClusterSize () |
Get the minimum number of points that a cluster needs to contain in order to be considered valid. | |
unsigned int | getNumberOfNeighbours () const |
Returns the number of nearest neighbours used for KNN. | |
bool | getResidualTestFlag () const |
Returns the flag that signalize if the residual test is turned on/off. | |
float | getResidualThreshold () const |
Returns residual threshold. | |
KdTreePtr | getSearchMethod () const |
Returns the pointer to the search method that is used for KNN. | |
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. | |
bool | getSmoothModeFlag () const |
Returns the flag value. This flag signalizes which mode of algorithm will be used. If it is set to true than it will work as said in the article. This means that it will be testing the angle between normal of the current point and it's neighbours normal. Otherwise, it will be testing the angle between normal of the current point and normal of the initial point that was chosen for growing new segment. | |
float | getSmoothnessThreshold () const |
Returns smoothness threshold. | |
RegionGrowing () | |
Constructor that sets default values for member variables. | |
virtual void | setCurvatureTestFlag (bool value) |
Allows to turn on/off the curvature test. Note that at least one test (residual or curvature) must be turned on. If you are turning curvature test off then residual test will be turned on automatically. | |
void | setCurvatureThreshold (float curvature) |
Allows to set curvature threshold used for testing the points. | |
void | setInputNormals (const NormalPtr &norm) |
This method sets the normals. They are needed for the algorithm, so if no normals will be set, the algorithm would not be able to segment the points. | |
void | setMaxClusterSize (int max_cluster_size) |
Set the maximum number of points that a cluster needs to contain in order to be considered valid. | |
void | setMinClusterSize (int min_cluster_size) |
Set the minimum number of points that a cluster needs to contain in order to be considered valid. | |
void | setNumberOfNeighbours (unsigned int neighbour_number) |
Allows to set the number of neighbours. For more information check the article. | |
virtual void | setResidualTestFlag (bool value) |
Allows to turn on/off the residual test. Note that at least one test (residual or curvature) must be turned on. If you are turning residual test off then curvature test will be turned on automatically. | |
void | setResidualThreshold (float residual) |
Allows to set residual threshold used for testing the points. | |
void | setSearchMethod (const KdTreePtr &tree) |
Allows to set search method that will be used for finding KNN. | |
void | setSmoothModeFlag (bool value) |
This function allows to turn on/off the smoothness constraint. | |
void | setSmoothnessThreshold (float theta) |
Allows to set smoothness threshold used for testing the points. | |
virtual | ~RegionGrowing () |
This destructor destroys the cloud, normals and search method used for finding KNN. In other words it frees memory. | |
Protected Member Functions | |
void | applySmoothRegionGrowingAlgorithm () |
This function implements the algorithm described in the article "Segmentation of point clouds using smoothness constraint" by T. Rabbania, F. A. van den Heuvelb, G. Vosselmanc. | |
void | assembleRegions () |
This function simply assembles the regions from list of point labels. | |
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. | |
int | growRegion (int initial_seed, int segment_number) |
This method grows a segment for the given seed point. And returns the number of its points. | |
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 | |
std::vector< pcl::PointIndices > | clusters_ |
After the segmentation it will contain the segments. | |
bool | curvature_flag_ |
If set to true then curvature test will be done during segmentation. | |
float | curvature_threshold_ |
Thershold used in curvature test. | |
int | max_pts_per_cluster_ |
Stores the maximum number of points that a cluster needs to contain in order to be considered valid. | |
int | min_pts_per_cluster_ |
Stores the minimum number of points that a cluster needs to contain in order to be considered valid. | |
unsigned int | neighbour_number_ |
Number of neighbours to find. | |
bool | normal_flag_ |
If set to true then normal/smoothness test will be done during segmentation. It is always set to true for the usual region growing algorithm. It is used for turning on/off the test for smoothness in the child class RegionGrowingRGB. | |
NormalPtr | normals_ |
Contains normals of the points that will be segmented. | |
std::vector< int > | num_pts_in_segment_ |
Tells how much points each segment contains. Used for reserving memory. | |
int | number_of_segments_ |
Stores the number of segments. | |
std::vector< int > | point_labels_ |
Point labels that tells to which segment each point belongs. | |
std::vector< std::vector< int > > | point_neighbours_ |
Contains neighbours of each point. | |
bool | residual_flag_ |
If set to true then residual test will be done during segmentation. | |
float | residual_threshold_ |
Thershold used in residual test. | |
KdTreePtr | search_ |
Serch method that will be used for KNN. | |
bool | smooth_mode_flag_ |
Flag that signalizes if the smoothness constraint will be used. | |
float | theta_threshold_ |
Thershold used for testing the smoothness between points. |
Implements the well known Region Growing algorithm used for segmentation. Description can be found in the article "Segmentation of point clouds using smoothness constraint" by T. Rabbania, F. A. van den Heuvelb, G. Vosselmanc. In addition to residual test, the possibility to test curvature is added.
Definition at line 61 of file region_growing.h.
typedef pcl::search::Search<PointT> pcl::RegionGrowing< PointT, NormalT >::KdTree |
Definition at line 65 of file region_growing.h.
typedef KdTree::Ptr pcl::RegionGrowing< PointT, NormalT >::KdTreePtr |
Definition at line 66 of file region_growing.h.
typedef pcl::PointCloud<NormalT> pcl::RegionGrowing< PointT, NormalT >::Normal |
Definition at line 67 of file region_growing.h.
typedef Normal::Ptr pcl::RegionGrowing< PointT, NormalT >::NormalPtr |
Definition at line 68 of file region_growing.h.
typedef pcl::PointCloud<PointT> pcl::RegionGrowing< PointT, NormalT >::PointCloud |
Reimplemented from pcl::PCLBase< PointT >.
Definition at line 69 of file region_growing.h.
pcl::RegionGrowing< PointT, NormalT >::RegionGrowing | ( | ) |
Constructor that sets default values for member variables.
Definition at line 57 of file region_growing.hpp.
pcl::RegionGrowing< PointT, NormalT >::~RegionGrowing | ( | ) | [virtual] |
This destructor destroys the cloud, normals and search method used for finding KNN. In other words it frees memory.
Definition at line 80 of file region_growing.hpp.
void pcl::RegionGrowing< PointT, NormalT >::applySmoothRegionGrowingAlgorithm | ( | ) | [protected] |
This function implements the algorithm described in the article "Segmentation of point clouds using smoothness constraint" by T. Rabbania, F. A. van den Heuvelb, G. Vosselmanc.
Definition at line 372 of file region_growing.hpp.
void pcl::RegionGrowing< PointT, NormalT >::assembleRegions | ( | ) | [protected] |
This function simply assembles the regions from list of point labels.
[out] | clusters | clusters that were obtained during the segmentation process. Each cluster is an array of point indices. |
Definition at line 532 of file region_growing.hpp.
void pcl::RegionGrowing< 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.
[out] | clusters | clusters that were obtained. Each cluster is an array of point indices. |
Reimplemented in pcl::RegionGrowingRGB< PointT, NormalT >.
Definition at line 261 of file region_growing.hpp.
void pcl::RegionGrowing< 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 in pcl::RegionGrowingRGB< PointT, NormalT >.
Definition at line 353 of file region_growing.hpp.
pcl::PointCloud< pcl::PointXYZRGB >::Ptr pcl::RegionGrowing< PointT, NormalT >::getColoredCloud | ( | ) |
If the cloud was successfully segmented, then function returns colored cloud. Otherwise it returns an empty pointer. Points that belong to the same segment have the same color. But this function doesn't guarantee that different segments will have different color(it all depends on RNG). Points that were not listed in the indices array will have red color.
Definition at line 634 of file region_growing.hpp.
pcl::PointCloud< pcl::PointXYZRGBA >::Ptr pcl::RegionGrowing< PointT, NormalT >::getColoredCloudRGBA | ( | ) |
If the cloud was successfully segmented, then function returns colored cloud. Otherwise it returns an empty pointer. Points that belong to the same segment have the same color. But this function doesn't guarantee that different segments will have different color(it all depends on RNG). Points that were not listed in the indices array will have red color.
Definition at line 688 of file region_growing.hpp.
bool pcl::RegionGrowing< PointT, NormalT >::getCurvatureTestFlag | ( | ) | const |
Returns the flag that signalize if the curvature test is turned on/off.
Definition at line 137 of file region_growing.hpp.
float pcl::RegionGrowing< PointT, NormalT >::getCurvatureThreshold | ( | ) | const |
Returns curvature threshold.
Definition at line 199 of file region_growing.hpp.
pcl::RegionGrowing< PointT, NormalT >::NormalPtr pcl::RegionGrowing< PointT, NormalT >::getInputNormals | ( | ) | const |
Returns normals.
Definition at line 244 of file region_growing.hpp.
int pcl::RegionGrowing< PointT, NormalT >::getMaxClusterSize | ( | ) |
Get the maximum number of points that a cluster needs to contain in order to be considered valid.
Definition at line 109 of file region_growing.hpp.
int pcl::RegionGrowing< PointT, NormalT >::getMinClusterSize | ( | ) |
Get the minimum number of points that a cluster needs to contain in order to be considered valid.
Definition at line 95 of file region_growing.hpp.
unsigned int pcl::RegionGrowing< PointT, NormalT >::getNumberOfNeighbours | ( | ) | const |
Returns the number of nearest neighbours used for KNN.
Definition at line 213 of file region_growing.hpp.
bool pcl::RegionGrowing< PointT, NormalT >::getResidualTestFlag | ( | ) | const |
Returns the flag that signalize if the residual test is turned on/off.
Definition at line 154 of file region_growing.hpp.
float pcl::RegionGrowing< PointT, NormalT >::getResidualThreshold | ( | ) | const |
Returns residual threshold.
Definition at line 185 of file region_growing.hpp.
pcl::RegionGrowing< PointT, NormalT >::KdTreePtr pcl::RegionGrowing< PointT, NormalT >::getSearchMethod | ( | ) | const |
Returns the pointer to the search method that is used for KNN.
Definition at line 227 of file region_growing.hpp.
void pcl::RegionGrowing< 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.
[in] | index | index of the initial point which will be the seed for growing a segment. |
[out] | cluster | cluster to which the point belongs. |
Reimplemented in pcl::RegionGrowingRGB< PointT, NormalT >.
Definition at line 564 of file region_growing.hpp.
bool pcl::RegionGrowing< PointT, NormalT >::getSmoothModeFlag | ( | ) | const |
Returns the flag value. This flag signalizes which mode of algorithm will be used. If it is set to true than it will work as said in the article. This means that it will be testing the angle between normal of the current point and it's neighbours normal. Otherwise, it will be testing the angle between normal of the current point and normal of the initial point that was chosen for growing new segment.
Definition at line 123 of file region_growing.hpp.
float pcl::RegionGrowing< PointT, NormalT >::getSmoothnessThreshold | ( | ) | const |
Returns smoothness threshold.
Definition at line 171 of file region_growing.hpp.
int pcl::RegionGrowing< PointT, NormalT >::growRegion | ( | int | initial_seed, |
int | segment_number | ||
) | [protected] |
This method grows a segment for the given seed point. And returns the number of its points.
[in] | initial_seed | index of the point that will serve as the seed point |
[in] | segment_number | indicates which number this segment will have |
Definition at line 428 of file region_growing.hpp.
bool pcl::RegionGrowing< 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 in pcl::RegionGrowingRGB< PointT, NormalT >.
Definition at line 307 of file region_growing.hpp.
void pcl::RegionGrowing< PointT, NormalT >::setCurvatureTestFlag | ( | bool | value | ) | [virtual] |
Allows to turn on/off the curvature test. Note that at least one test (residual or curvature) must be turned on. If you are turning curvature test off then residual test will be turned on automatically.
[in] | value | new value for curvature test. If set to true then the test will be turned on |
Reimplemented in pcl::RegionGrowingRGB< PointT, NormalT >.
Definition at line 144 of file region_growing.hpp.
void pcl::RegionGrowing< PointT, NormalT >::setCurvatureThreshold | ( | float | curvature | ) |
Allows to set curvature threshold used for testing the points.
[in] | curvature | new threshold value for curvature testing |
Definition at line 206 of file region_growing.hpp.
void pcl::RegionGrowing< PointT, NormalT >::setInputNormals | ( | const NormalPtr & | norm | ) |
This method sets the normals. They are needed for the algorithm, so if no normals will be set, the algorithm would not be able to segment the points.
[in] | norm | normals that will be used in the algorithm |
Definition at line 251 of file region_growing.hpp.
void pcl::RegionGrowing< PointT, NormalT >::setMaxClusterSize | ( | int | max_cluster_size | ) |
Set the maximum number of points that a cluster needs to contain in order to be considered valid.
Definition at line 116 of file region_growing.hpp.
void pcl::RegionGrowing< PointT, NormalT >::setMinClusterSize | ( | int | min_cluster_size | ) |
Set the minimum number of points that a cluster needs to contain in order to be considered valid.
Definition at line 102 of file region_growing.hpp.
void pcl::RegionGrowing< PointT, NormalT >::setNumberOfNeighbours | ( | unsigned int | neighbour_number | ) |
Allows to set the number of neighbours. For more information check the article.
[in] | neighbour_number | number of neighbours to use |
Definition at line 220 of file region_growing.hpp.
void pcl::RegionGrowing< PointT, NormalT >::setResidualTestFlag | ( | bool | value | ) | [virtual] |
Allows to turn on/off the residual test. Note that at least one test (residual or curvature) must be turned on. If you are turning residual test off then curvature test will be turned on automatically.
[in] | value | new value for residual test. If set to true then the test will be turned on |
Reimplemented in pcl::RegionGrowingRGB< PointT, NormalT >.
Definition at line 161 of file region_growing.hpp.
void pcl::RegionGrowing< PointT, NormalT >::setResidualThreshold | ( | float | residual | ) |
Allows to set residual threshold used for testing the points.
[in] | residual | new threshold value for residual testing |
Definition at line 192 of file region_growing.hpp.
void pcl::RegionGrowing< PointT, NormalT >::setSearchMethod | ( | const KdTreePtr & | tree | ) |
Allows to set search method that will be used for finding KNN.
[in] | search | search method to use |
Definition at line 234 of file region_growing.hpp.
void pcl::RegionGrowing< PointT, NormalT >::setSmoothModeFlag | ( | bool | value | ) |
This function allows to turn on/off the smoothness constraint.
[in] | value | new mode value, if set to true then the smooth version will be used. |
Definition at line 130 of file region_growing.hpp.
void pcl::RegionGrowing< PointT, NormalT >::setSmoothnessThreshold | ( | float | theta | ) |
Allows to set smoothness threshold used for testing the points.
[in] | theta | new threshold value for the angle between normals |
Definition at line 178 of file region_growing.hpp.
bool pcl::RegionGrowing< 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.
[in] | initial_seed | index of the initial point that was passed to the growRegion() function |
[in] | point | index of the current seed point |
[in] | nghbr | index of the point that is neighbour of the current seed |
[out] | is_a_seed | this value is set to true if the point with index 'nghbr' can serve as the seed |
Reimplemented in pcl::RegionGrowingRGB< PointT, NormalT >.
Definition at line 478 of file region_growing.hpp.
std::vector<pcl::PointIndices> pcl::RegionGrowing< PointT, NormalT >::clusters_ [protected] |
After the segmentation it will contain the segments.
Definition at line 331 of file region_growing.h.
bool pcl::RegionGrowing< PointT, NormalT >::curvature_flag_ [protected] |
If set to true then curvature test will be done during segmentation.
Definition at line 293 of file region_growing.h.
float pcl::RegionGrowing< PointT, NormalT >::curvature_threshold_ [protected] |
Thershold used in curvature test.
Definition at line 305 of file region_growing.h.
int pcl::RegionGrowing< PointT, NormalT >::max_pts_per_cluster_ [protected] |
Stores the maximum number of points that a cluster needs to contain in order to be considered valid.
Definition at line 287 of file region_growing.h.
int pcl::RegionGrowing< PointT, NormalT >::min_pts_per_cluster_ [protected] |
Stores the minimum number of points that a cluster needs to contain in order to be considered valid.
Definition at line 284 of file region_growing.h.
unsigned int pcl::RegionGrowing< PointT, NormalT >::neighbour_number_ [protected] |
Number of neighbours to find.
Definition at line 308 of file region_growing.h.
bool pcl::RegionGrowing< PointT, NormalT >::normal_flag_ [protected] |
If set to true then normal/smoothness test will be done during segmentation. It is always set to true for the usual region growing algorithm. It is used for turning on/off the test for smoothness in the child class RegionGrowingRGB.
Definition at line 325 of file region_growing.h.
NormalPtr pcl::RegionGrowing< PointT, NormalT >::normals_ [protected] |
Contains normals of the points that will be segmented.
Definition at line 314 of file region_growing.h.
std::vector<int> pcl::RegionGrowing< PointT, NormalT >::num_pts_in_segment_ [protected] |
Tells how much points each segment contains. Used for reserving memory.
Definition at line 328 of file region_growing.h.
int pcl::RegionGrowing< PointT, NormalT >::number_of_segments_ [protected] |
Stores the number of segments.
Definition at line 334 of file region_growing.h.
std::vector<int> pcl::RegionGrowing< PointT, NormalT >::point_labels_ [protected] |
Point labels that tells to which segment each point belongs.
Definition at line 320 of file region_growing.h.
std::vector<std::vector<int> > pcl::RegionGrowing< PointT, NormalT >::point_neighbours_ [protected] |
Contains neighbours of each point.
Definition at line 317 of file region_growing.h.
bool pcl::RegionGrowing< PointT, NormalT >::residual_flag_ [protected] |
If set to true then residual test will be done during segmentation.
Definition at line 296 of file region_growing.h.
float pcl::RegionGrowing< PointT, NormalT >::residual_threshold_ [protected] |
Thershold used in residual test.
Definition at line 302 of file region_growing.h.
KdTreePtr pcl::RegionGrowing< PointT, NormalT >::search_ [protected] |
Serch method that will be used for KNN.
Definition at line 311 of file region_growing.h.
bool pcl::RegionGrowing< PointT, NormalT >::smooth_mode_flag_ [protected] |
Flag that signalizes if the smoothness constraint will be used.
Definition at line 290 of file region_growing.h.
float pcl::RegionGrowing< PointT, NormalT >::theta_threshold_ [protected] |
Thershold used for testing the smoothness between points.
Definition at line 299 of file region_growing.h.