OrganizedConnectedComponentSegmentation allows connected components to be found within organized point cloud data, given a comparison function. Given an input cloud and a comparator, it will output a PointCloud of labels, giving each connected component a unique id, along with a vector of PointIndices corresponding to each component. See OrganizedMultiPlaneSegmentation for an example application. More...
#include <organized_connected_component_segmentation.h>
Classes | |
struct | Neighbor |
Public Types | |
typedef pcl::Comparator< PointT > | Comparator |
typedef Comparator::ConstPtr | ComparatorConstPtr |
typedef Comparator::Ptr | ComparatorPtr |
typedef pcl::PointCloud< PointT > | PointCloud |
typedef PointCloud::ConstPtr | PointCloudConstPtr |
typedef pcl::PointCloud< PointLT > | PointCloudL |
typedef PointCloudL::ConstPtr | PointCloudLConstPtr |
typedef PointCloudL::Ptr | PointCloudLPtr |
typedef PointCloud::Ptr | PointCloudPtr |
Public Member Functions | |
ComparatorConstPtr | getComparator () const |
Get the comparator. | |
OrganizedConnectedComponentSegmentation (const ComparatorConstPtr &compare) | |
Constructor for OrganizedConnectedComponentSegmentation. | |
void | segment (pcl::PointCloud< PointLT > &labels, std::vector< pcl::PointIndices > &label_indices) const |
Perform the connected component segmentation. | |
void | setComparator (const ComparatorConstPtr &compare) |
Provide a pointer to the comparator to be used for segmentation. | |
virtual | ~OrganizedConnectedComponentSegmentation () |
Destructor for OrganizedConnectedComponentSegmentation. | |
Static Public Member Functions | |
static void | findLabeledRegionBoundary (int start_idx, PointCloudLPtr labels, pcl::PointIndices &boundary_indices) |
Find the boundary points / contour of a connected component. | |
Protected Member Functions | |
unsigned | findRoot (const std::vector< unsigned > &runs, unsigned index) const |
Protected Attributes | |
ComparatorConstPtr | compare_ |
OrganizedConnectedComponentSegmentation allows connected components to be found within organized point cloud data, given a comparison function. Given an input cloud and a comparator, it will output a PointCloud of labels, giving each connected component a unique id, along with a vector of PointIndices corresponding to each component. See OrganizedMultiPlaneSegmentation for an example application.
Definition at line 59 of file organized_connected_component_segmentation.h.
typedef pcl::Comparator<PointT> pcl::OrganizedConnectedComponentSegmentation< PointT, PointLT >::Comparator |
Definition at line 75 of file organized_connected_component_segmentation.h.
typedef Comparator::ConstPtr pcl::OrganizedConnectedComponentSegmentation< PointT, PointLT >::ComparatorConstPtr |
Definition at line 77 of file organized_connected_component_segmentation.h.
typedef Comparator::Ptr pcl::OrganizedConnectedComponentSegmentation< PointT, PointLT >::ComparatorPtr |
Definition at line 76 of file organized_connected_component_segmentation.h.
typedef pcl::PointCloud<PointT> pcl::OrganizedConnectedComponentSegmentation< PointT, PointLT >::PointCloud |
Reimplemented from pcl::PCLBase< PointT >.
Definition at line 67 of file organized_connected_component_segmentation.h.
typedef PointCloud::ConstPtr pcl::OrganizedConnectedComponentSegmentation< PointT, PointLT >::PointCloudConstPtr |
Reimplemented from pcl::PCLBase< PointT >.
Definition at line 69 of file organized_connected_component_segmentation.h.
typedef pcl::PointCloud<PointLT> pcl::OrganizedConnectedComponentSegmentation< PointT, PointLT >::PointCloudL |
Definition at line 71 of file organized_connected_component_segmentation.h.
typedef PointCloudL::ConstPtr pcl::OrganizedConnectedComponentSegmentation< PointT, PointLT >::PointCloudLConstPtr |
Definition at line 73 of file organized_connected_component_segmentation.h.
typedef PointCloudL::Ptr pcl::OrganizedConnectedComponentSegmentation< PointT, PointLT >::PointCloudLPtr |
Definition at line 72 of file organized_connected_component_segmentation.h.
typedef PointCloud::Ptr pcl::OrganizedConnectedComponentSegmentation< PointT, PointLT >::PointCloudPtr |
Reimplemented from pcl::PCLBase< PointT >.
Definition at line 68 of file organized_connected_component_segmentation.h.
pcl::OrganizedConnectedComponentSegmentation< PointT, PointLT >::OrganizedConnectedComponentSegmentation | ( | const ComparatorConstPtr & | compare | ) | [inline] |
Constructor for OrganizedConnectedComponentSegmentation.
[in] | compare | A pointer to the comparator to be used for segmentation. Must be an instance of pcl::Comparator. |
Definition at line 82 of file organized_connected_component_segmentation.h.
virtual pcl::OrganizedConnectedComponentSegmentation< PointT, PointLT >::~OrganizedConnectedComponentSegmentation | ( | ) | [inline, virtual] |
Destructor for OrganizedConnectedComponentSegmentation.
Definition at line 89 of file organized_connected_component_segmentation.h.
void pcl::OrganizedConnectedComponentSegmentation< PointT, PointLT >::findLabeledRegionBoundary | ( | int | start_idx, |
PointCloudLPtr | labels, | ||
pcl::PointIndices & | boundary_indices | ||
) | [static] |
Find the boundary points / contour of a connected component.
[in] | start_idx | the first (lowest) index of the connected component for which a boundary shoudl be returned |
[in] | labels | the Label cloud produced by segmentation |
[out] | boundary_indices | the indices of the boundary points for the label corresponding to start_idx |
Directions: 1 2 3 0 x 4 7 6 5 e.g. direction y means we came from pixel with label y to the center pixel x
Definition at line 53 of file organized_connected_component_segmentation.hpp.
unsigned pcl::OrganizedConnectedComponentSegmentation< PointT, PointLT >::findRoot | ( | const std::vector< unsigned > & | runs, |
unsigned | index | ||
) | const [inline, protected] |
Definition at line 126 of file organized_connected_component_segmentation.h.
ComparatorConstPtr pcl::OrganizedConnectedComponentSegmentation< PointT, PointLT >::getComparator | ( | ) | const [inline] |
Get the comparator.
Definition at line 104 of file organized_connected_component_segmentation.h.
void pcl::OrganizedConnectedComponentSegmentation< PointT, PointLT >::segment | ( | pcl::PointCloud< PointLT > & | labels, |
std::vector< pcl::PointIndices > & | label_indices | ||
) | const |
Perform the connected component segmentation.
[out] | labels | a PointCloud of labels: each connected component will have a unique id. |
[out] | label_indices | a vector of PointIndices corresponding to each label / component id. |
Definition at line 118 of file organized_connected_component_segmentation.hpp.
void pcl::OrganizedConnectedComponentSegmentation< PointT, PointLT >::setComparator | ( | const ComparatorConstPtr & | compare | ) | [inline] |
Provide a pointer to the comparator to be used for segmentation.
[in] | compare | the comparator |
Definition at line 97 of file organized_connected_component_segmentation.h.
ComparatorConstPtr pcl::OrganizedConnectedComponentSegmentation< PointT, PointLT >::compare_ [protected] |
Definition at line 123 of file organized_connected_component_segmentation.h.