OrganizedMultiPlaneSegmentation finds all planes present in the input cloud, and outputs a vector of plane equations, as well as a vector of point clouds corresponding to the inliers of each detected plane. Only planes with more than min_inliers points are detected. Templated on point type, normal type, and label type. More...
#include <organized_multi_plane_segmentation.h>
Public Types | |
typedef pcl::PlaneCoefficientComparator < PointT, PointNT > | PlaneComparator |
typedef PlaneComparator::ConstPtr | PlaneComparatorConstPtr |
typedef PlaneComparator::Ptr | PlaneComparatorPtr |
typedef pcl::PlaneRefinementComparator < PointT, PointNT, PointLT > | PlaneRefinementComparator |
typedef PlaneRefinementComparator::ConstPtr | PlaneRefinementComparatorConstPtr |
typedef PlaneRefinementComparator::Ptr | PlaneRefinementComparatorPtr |
typedef pcl::PointCloud< PointT > | PointCloud |
typedef PointCloud::ConstPtr | PointCloudConstPtr |
typedef pcl::PointCloud< PointLT > | PointCloudL |
typedef PointCloudL::ConstPtr | PointCloudLConstPtr |
typedef PointCloudL::Ptr | PointCloudLPtr |
typedef pcl::PointCloud< PointNT > | PointCloudN |
typedef PointCloudN::ConstPtr | PointCloudNConstPtr |
typedef PointCloudN::Ptr | PointCloudNPtr |
typedef PointCloud::Ptr | PointCloudPtr |
Public Member Functions | |
double | getAngularThreshold () const |
Get the angular threshold in radians for difference in normal direction between neighboring points, to be considered part of the same plane. | |
double | getDistanceThreshold () const |
Get the distance threshold in meters (d component of plane equation) between neighboring points, to be considered part of the same plane. | |
PointCloudNConstPtr | getInputNormals () const |
Get the input normals. | |
double | getMaximumCurvature () const |
Get the maximum curvature allowed for a planar region. | |
unsigned | getMinInliers () const |
Get the minimum number of inliers required per plane. | |
OrganizedMultiPlaneSegmentation () | |
Constructor for OrganizedMultiPlaneSegmentation. | |
void | refine (std::vector< ModelCoefficients > &model_coefficients, std::vector< PointIndices > &inlier_indices, std::vector< Eigen::Vector4f, Eigen::aligned_allocator< Eigen::Vector4f > > ¢roids, std::vector< Eigen::Matrix3f, Eigen::aligned_allocator< Eigen::Matrix3f > > &covariances, PointCloudLPtr &labels, std::vector< pcl::PointIndices > &label_indices) |
Perform a refinement of an initial segmentation, by comparing points to adjacent regions detected by the initial segmentation. | |
void | segment (std::vector< ModelCoefficients > &model_coefficients, std::vector< PointIndices > &inlier_indices, std::vector< Eigen::Vector4f, Eigen::aligned_allocator< Eigen::Vector4f > > ¢roids, std::vector< Eigen::Matrix3f, Eigen::aligned_allocator< Eigen::Matrix3f > > &covariances, pcl::PointCloud< PointLT > &labels, std::vector< pcl::PointIndices > &label_indices) |
Segmentation of all planes in a point cloud given by setInputCloud(), setIndices() | |
void | segment (std::vector< ModelCoefficients > &model_coefficients, std::vector< PointIndices > &inlier_indices) |
Segmentation of all planes in a point cloud given by setInputCloud(), setIndices() | |
void | segment (std::vector< PlanarRegion< PointT >, Eigen::aligned_allocator< PlanarRegion< PointT > > > ®ions) |
Segmentation of all planes in a point cloud given by setInputCloud(), setIndices() | |
void | segmentAndRefine (std::vector< PlanarRegion< PointT >, Eigen::aligned_allocator< PlanarRegion< PointT > > > ®ions) |
Perform a segmentation, as well as an additional refinement step. This helps with including points whose normals may not match neighboring points well, but may match the planar model well. | |
void | segmentAndRefine (std::vector< PlanarRegion< PointT >, Eigen::aligned_allocator< PlanarRegion< PointT > > > ®ions, std::vector< ModelCoefficients > &model_coefficients, std::vector< PointIndices > &inlier_indices, PointCloudLPtr &labels, std::vector< pcl::PointIndices > &label_indices, std::vector< pcl::PointIndices > &boundary_indices) |
Perform a segmentation, as well as additional refinement step. Returns intermediate data structures for use in subsequent processing. | |
void | setAngularThreshold (double angular_threshold) |
Set the tolerance in radians for difference in normal direction between neighboring points, to be considered part of the same plane. | |
void | setComparator (const PlaneComparatorPtr &compare) |
Provide a pointer to the comparator to be used for segmentation. | |
void | setDistanceThreshold (double distance_threshold) |
Set the tolerance in meters for difference in perpendicular distance (d component of plane equation) to the plane between neighboring points, to be considered part of the same plane. | |
void | setInputNormals (const PointCloudNConstPtr &normals) |
Provide a pointer to the input normals. | |
void | setMaximumCurvature (double maximum_curvature) |
Set the maximum curvature allowed for a planar region. | |
void | setMinInliers (unsigned min_inliers) |
Set the minimum number of inliers required for a plane. | |
void | setProjectPoints (bool project_points) |
Set whether or not to project boundary points to the plane, or leave them in the original 3D space. | |
void | setRefinementComparator (const PlaneRefinementComparatorPtr &compare) |
Provide a pointer to the comparator to be used for refinement. | |
virtual | ~OrganizedMultiPlaneSegmentation () |
Destructor for OrganizedMultiPlaneSegmentation. | |
Protected Member Functions | |
virtual std::string | getClassName () const |
Class getName method. | |
Protected Attributes | |
double | angular_threshold_ |
The tolerance in radians for difference in normal direction between neighboring points, to be considered part of the same plane. | |
PlaneComparatorPtr | compare_ |
A comparator for comparing neighboring pixels' plane equations. | |
double | distance_threshold_ |
The tolerance in meters for difference in perpendicular distance (d component of plane equation) to the plane between neighboring points, to be considered part of the same plane. | |
double | maximum_curvature_ |
The tolerance for maximum curvature after fitting a plane. Used to remove smooth, but non-planar regions. | |
unsigned | min_inliers_ |
The minimum number of inliers required for each plane. | |
PointCloudNConstPtr | normals_ |
A pointer to the input normals. | |
bool | project_points_ |
Whether or not points should be projected to the plane, or left in the original 3D space. | |
PlaneRefinementComparatorPtr | refinement_compare_ |
A comparator for use on the refinement step. Compares points to regions segmented in the first pass. |
OrganizedMultiPlaneSegmentation finds all planes present in the input cloud, and outputs a vector of plane equations, as well as a vector of point clouds corresponding to the inliers of each detected plane. Only planes with more than min_inliers points are detected. Templated on point type, normal type, and label type.
Definition at line 62 of file organized_multi_plane_segmentation.h.
typedef pcl::PlaneCoefficientComparator<PointT, PointNT> pcl::OrganizedMultiPlaneSegmentation< PointT, PointNT, PointLT >::PlaneComparator |
Definition at line 82 of file organized_multi_plane_segmentation.h.
typedef PlaneComparator::ConstPtr pcl::OrganizedMultiPlaneSegmentation< PointT, PointNT, PointLT >::PlaneComparatorConstPtr |
Definition at line 84 of file organized_multi_plane_segmentation.h.
typedef PlaneComparator::Ptr pcl::OrganizedMultiPlaneSegmentation< PointT, PointNT, PointLT >::PlaneComparatorPtr |
Definition at line 83 of file organized_multi_plane_segmentation.h.
typedef pcl::PlaneRefinementComparator<PointT, PointNT, PointLT> pcl::OrganizedMultiPlaneSegmentation< PointT, PointNT, PointLT >::PlaneRefinementComparator |
Definition at line 86 of file organized_multi_plane_segmentation.h.
typedef PlaneRefinementComparator::ConstPtr pcl::OrganizedMultiPlaneSegmentation< PointT, PointNT, PointLT >::PlaneRefinementComparatorConstPtr |
Definition at line 88 of file organized_multi_plane_segmentation.h.
typedef PlaneRefinementComparator::Ptr pcl::OrganizedMultiPlaneSegmentation< PointT, PointNT, PointLT >::PlaneRefinementComparatorPtr |
Definition at line 87 of file organized_multi_plane_segmentation.h.
typedef pcl::PointCloud<PointT> pcl::OrganizedMultiPlaneSegmentation< PointT, PointNT, PointLT >::PointCloud |
Reimplemented from pcl::PCLBase< PointT >.
Definition at line 70 of file organized_multi_plane_segmentation.h.
typedef PointCloud::ConstPtr pcl::OrganizedMultiPlaneSegmentation< PointT, PointNT, PointLT >::PointCloudConstPtr |
Reimplemented from pcl::PCLBase< PointT >.
Definition at line 72 of file organized_multi_plane_segmentation.h.
typedef pcl::PointCloud<PointLT> pcl::OrganizedMultiPlaneSegmentation< PointT, PointNT, PointLT >::PointCloudL |
Definition at line 78 of file organized_multi_plane_segmentation.h.
typedef PointCloudL::ConstPtr pcl::OrganizedMultiPlaneSegmentation< PointT, PointNT, PointLT >::PointCloudLConstPtr |
Definition at line 80 of file organized_multi_plane_segmentation.h.
typedef PointCloudL::Ptr pcl::OrganizedMultiPlaneSegmentation< PointT, PointNT, PointLT >::PointCloudLPtr |
Definition at line 79 of file organized_multi_plane_segmentation.h.
typedef pcl::PointCloud<PointNT> pcl::OrganizedMultiPlaneSegmentation< PointT, PointNT, PointLT >::PointCloudN |
Definition at line 74 of file organized_multi_plane_segmentation.h.
typedef PointCloudN::ConstPtr pcl::OrganizedMultiPlaneSegmentation< PointT, PointNT, PointLT >::PointCloudNConstPtr |
Definition at line 76 of file organized_multi_plane_segmentation.h.
typedef PointCloudN::Ptr pcl::OrganizedMultiPlaneSegmentation< PointT, PointNT, PointLT >::PointCloudNPtr |
Definition at line 75 of file organized_multi_plane_segmentation.h.
typedef PointCloud::Ptr pcl::OrganizedMultiPlaneSegmentation< PointT, PointNT, PointLT >::PointCloudPtr |
Reimplemented from pcl::PCLBase< PointT >.
Definition at line 71 of file organized_multi_plane_segmentation.h.
pcl::OrganizedMultiPlaneSegmentation< PointT, PointNT, PointLT >::OrganizedMultiPlaneSegmentation | ( | ) | [inline] |
Constructor for OrganizedMultiPlaneSegmentation.
Definition at line 91 of file organized_multi_plane_segmentation.h.
virtual pcl::OrganizedMultiPlaneSegmentation< PointT, PointNT, PointLT >::~OrganizedMultiPlaneSegmentation | ( | ) | [inline, virtual] |
Destructor for OrganizedMultiPlaneSegmentation.
Definition at line 104 of file organized_multi_plane_segmentation.h.
double pcl::OrganizedMultiPlaneSegmentation< PointT, PointNT, PointLT >::getAngularThreshold | ( | ) | const [inline] |
Get the angular threshold in radians for difference in normal direction between neighboring points, to be considered part of the same plane.
Definition at line 151 of file organized_multi_plane_segmentation.h.
virtual std::string pcl::OrganizedMultiPlaneSegmentation< PointT, PointNT, PointLT >::getClassName | ( | ) | const [inline, protected, virtual] |
Class getName method.
Definition at line 312 of file organized_multi_plane_segmentation.h.
double pcl::OrganizedMultiPlaneSegmentation< PointT, PointNT, PointLT >::getDistanceThreshold | ( | ) | const [inline] |
Get the distance threshold in meters (d component of plane equation) between neighboring points, to be considered part of the same plane.
Definition at line 167 of file organized_multi_plane_segmentation.h.
PointCloudNConstPtr pcl::OrganizedMultiPlaneSegmentation< PointT, PointNT, PointLT >::getInputNormals | ( | ) | const [inline] |
Get the input normals.
Definition at line 119 of file organized_multi_plane_segmentation.h.
double pcl::OrganizedMultiPlaneSegmentation< PointT, PointNT, PointLT >::getMaximumCurvature | ( | ) | const [inline] |
Get the maximum curvature allowed for a planar region.
Definition at line 183 of file organized_multi_plane_segmentation.h.
unsigned pcl::OrganizedMultiPlaneSegmentation< PointT, PointNT, PointLT >::getMinInliers | ( | ) | const [inline] |
Get the minimum number of inliers required per plane.
Definition at line 135 of file organized_multi_plane_segmentation.h.
void pcl::OrganizedMultiPlaneSegmentation< PointT, PointNT, PointLT >::refine | ( | std::vector< ModelCoefficients > & | model_coefficients, |
std::vector< PointIndices > & | inlier_indices, | ||
std::vector< Eigen::Vector4f, Eigen::aligned_allocator< Eigen::Vector4f > > & | centroids, | ||
std::vector< Eigen::Matrix3f, Eigen::aligned_allocator< Eigen::Matrix3f > > & | covariances, | ||
PointCloudLPtr & | labels, | ||
std::vector< pcl::PointIndices > & | label_indices | ||
) |
Perform a refinement of an initial segmentation, by comparing points to adjacent regions detected by the initial segmentation.
[in] | model_coefficients | The list of segmented model coefficients |
[in] | inlier_indices | The list of segmented inlier indices, corresponding to each model |
[in] | centroids | The list of centroids corresponding to each segmented plane |
[in] | covariances | The list of covariances corresponding to each segemented plane |
[in] | labels | The labels produced by the initial segmentation |
[in] | label_indices | The list of indices corresponding to each label |
Definition at line 319 of file organized_multi_plane_segmentation.hpp.
void pcl::OrganizedMultiPlaneSegmentation< PointT, PointNT, PointLT >::segment | ( | std::vector< ModelCoefficients > & | model_coefficients, |
std::vector< PointIndices > & | inlier_indices, | ||
std::vector< Eigen::Vector4f, Eigen::aligned_allocator< Eigen::Vector4f > > & | centroids, | ||
std::vector< Eigen::Matrix3f, Eigen::aligned_allocator< Eigen::Matrix3f > > & | covariances, | ||
pcl::PointCloud< PointLT > & | labels, | ||
std::vector< pcl::PointIndices > & | label_indices | ||
) |
Segmentation of all planes in a point cloud given by setInputCloud(), setIndices()
[out] | model_coefficients | a vector of model_coefficients for each plane found in the input cloud |
[out] | inlier_indices | a vector of inliers for each detected plane |
[out] | centroids | a vector of centroids for each plane |
[out] | covariances | a vector of covariance matricies for the inliers of each plane |
[out] | labels | a point cloud for the connected component labels of each pixel |
[out] | label_indices | a vector of PointIndices for each labeled component |
Definition at line 90 of file organized_multi_plane_segmentation.hpp.
void pcl::OrganizedMultiPlaneSegmentation< PointT, PointNT, PointLT >::segment | ( | std::vector< ModelCoefficients > & | model_coefficients, |
std::vector< PointIndices > & | inlier_indices | ||
) |
Segmentation of all planes in a point cloud given by setInputCloud(), setIndices()
[out] | model_coefficients | a vector of model_coefficients for each plane found in the input cloud |
[out] | inlier_indices | a vector of inliers for each detected plane |
Definition at line 78 of file organized_multi_plane_segmentation.hpp.
void pcl::OrganizedMultiPlaneSegmentation< PointT, PointNT, PointLT >::segment | ( | std::vector< PlanarRegion< PointT >, Eigen::aligned_allocator< PlanarRegion< PointT > > > & | regions | ) |
Segmentation of all planes in a point cloud given by setInputCloud(), setIndices()
[out] | regions | a list of resultant planar polygonal regions |
Definition at line 194 of file organized_multi_plane_segmentation.hpp.
void pcl::OrganizedMultiPlaneSegmentation< PointT, PointNT, PointLT >::segmentAndRefine | ( | std::vector< PlanarRegion< PointT >, Eigen::aligned_allocator< PlanarRegion< PointT > > > & | regions | ) |
Perform a segmentation, as well as an additional refinement step. This helps with including points whose normals may not match neighboring points well, but may match the planar model well.
[out] | regions | A list of regions generated by segmentation and refinement. |
Definition at line 231 of file organized_multi_plane_segmentation.hpp.
void pcl::OrganizedMultiPlaneSegmentation< PointT, PointNT, PointLT >::segmentAndRefine | ( | std::vector< PlanarRegion< PointT >, Eigen::aligned_allocator< PlanarRegion< PointT > > > & | regions, |
std::vector< ModelCoefficients > & | model_coefficients, | ||
std::vector< PointIndices > & | inlier_indices, | ||
PointCloudLPtr & | labels, | ||
std::vector< pcl::PointIndices > & | label_indices, | ||
std::vector< pcl::PointIndices > & | boundary_indices | ||
) |
Perform a segmentation, as well as additional refinement step. Returns intermediate data structures for use in subsequent processing.
[out] | regions | A vector of PlanarRegions generated by segmentation |
[out] | model_coefficients | A vector of model coefficients for each segmented plane |
[out] | inlier_indices | A vector of PointIndices, indicating the inliers to each segmented plane |
[out] | labels | A PointCloud<PointLT> corresponding to the resulting segmentation. |
[out] | label_indices | A vector of PointIndices for each label |
[out] | boundary_indices | A vector of PointIndices corresponding to the outer boundary / contour of each label |
Definition at line 275 of file organized_multi_plane_segmentation.hpp.
void pcl::OrganizedMultiPlaneSegmentation< PointT, PointNT, PointLT >::setAngularThreshold | ( | double | angular_threshold | ) | [inline] |
Set the tolerance in radians for difference in normal direction between neighboring points, to be considered part of the same plane.
[in] | angular_threshold | the tolerance in radians |
Definition at line 144 of file organized_multi_plane_segmentation.h.
void pcl::OrganizedMultiPlaneSegmentation< PointT, PointNT, PointLT >::setComparator | ( | const PlaneComparatorPtr & | compare | ) | [inline] |
Provide a pointer to the comparator to be used for segmentation.
[in] | compare | A pointer to the comparator to be used for segmentation. |
Definition at line 192 of file organized_multi_plane_segmentation.h.
void pcl::OrganizedMultiPlaneSegmentation< PointT, PointNT, PointLT >::setDistanceThreshold | ( | double | distance_threshold | ) | [inline] |
Set the tolerance in meters for difference in perpendicular distance (d component of plane equation) to the plane between neighboring points, to be considered part of the same plane.
[in] | distance_threshold | the tolerance in meters |
Definition at line 160 of file organized_multi_plane_segmentation.h.
void pcl::OrganizedMultiPlaneSegmentation< PointT, PointNT, PointLT >::setInputNormals | ( | const PointCloudNConstPtr & | normals | ) | [inline] |
Provide a pointer to the input normals.
[in] | normals | the input normal cloud |
Definition at line 112 of file organized_multi_plane_segmentation.h.
void pcl::OrganizedMultiPlaneSegmentation< PointT, PointNT, PointLT >::setMaximumCurvature | ( | double | maximum_curvature | ) | [inline] |
Set the maximum curvature allowed for a planar region.
[in] | maximum_curvature | the maximum curvature |
Definition at line 176 of file organized_multi_plane_segmentation.h.
void pcl::OrganizedMultiPlaneSegmentation< PointT, PointNT, PointLT >::setMinInliers | ( | unsigned | min_inliers | ) | [inline] |
Set the minimum number of inliers required for a plane.
[in] | min_inliers | the minimum number of inliers required per plane |
Definition at line 128 of file organized_multi_plane_segmentation.h.
void pcl::OrganizedMultiPlaneSegmentation< PointT, PointNT, PointLT >::setProjectPoints | ( | bool | project_points | ) | [inline] |
Set whether or not to project boundary points to the plane, or leave them in the original 3D space.
[in] | project_points | true if points should be projected, false if not. |
Definition at line 210 of file organized_multi_plane_segmentation.h.
void pcl::OrganizedMultiPlaneSegmentation< PointT, PointNT, PointLT >::setRefinementComparator | ( | const PlaneRefinementComparatorPtr & | compare | ) | [inline] |
Provide a pointer to the comparator to be used for refinement.
[in] | compare | A pointer to the comparator to be used for refinement. |
Definition at line 201 of file organized_multi_plane_segmentation.h.
double pcl::OrganizedMultiPlaneSegmentation< PointT, PointNT, PointLT >::angular_threshold_ [protected] |
The tolerance in radians for difference in normal direction between neighboring points, to be considered part of the same plane.
Definition at line 293 of file organized_multi_plane_segmentation.h.
PlaneComparatorPtr pcl::OrganizedMultiPlaneSegmentation< PointT, PointNT, PointLT >::compare_ [protected] |
A comparator for comparing neighboring pixels' plane equations.
Definition at line 305 of file organized_multi_plane_segmentation.h.
double pcl::OrganizedMultiPlaneSegmentation< PointT, PointNT, PointLT >::distance_threshold_ [protected] |
The tolerance in meters for difference in perpendicular distance (d component of plane equation) to the plane between neighboring points, to be considered part of the same plane.
Definition at line 296 of file organized_multi_plane_segmentation.h.
double pcl::OrganizedMultiPlaneSegmentation< PointT, PointNT, PointLT >::maximum_curvature_ [protected] |
The tolerance for maximum curvature after fitting a plane. Used to remove smooth, but non-planar regions.
Definition at line 299 of file organized_multi_plane_segmentation.h.
unsigned pcl::OrganizedMultiPlaneSegmentation< PointT, PointNT, PointLT >::min_inliers_ [protected] |
The minimum number of inliers required for each plane.
Definition at line 290 of file organized_multi_plane_segmentation.h.
PointCloudNConstPtr pcl::OrganizedMultiPlaneSegmentation< PointT, PointNT, PointLT >::normals_ [protected] |
A pointer to the input normals.
Definition at line 287 of file organized_multi_plane_segmentation.h.
bool pcl::OrganizedMultiPlaneSegmentation< PointT, PointNT, PointLT >::project_points_ [protected] |
Whether or not points should be projected to the plane, or left in the original 3D space.
Definition at line 302 of file organized_multi_plane_segmentation.h.
PlaneRefinementComparatorPtr pcl::OrganizedMultiPlaneSegmentation< PointT, PointNT, PointLT >::refinement_compare_ [protected] |
A comparator for use on the refinement step. Compares points to regions segmented in the first pass.
Definition at line 308 of file organized_multi_plane_segmentation.h.