Point Cloud Library (PCL)  1.14.0-dev
List of all members | Public Types | Public Member Functions | Protected Member Functions | Protected Attributes
pcl::OrganizedMultiPlaneSegmentation< PointT, PointNT, PointLT > Class Template Reference

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. More...

#include <pcl/segmentation/organized_multi_plane_segmentation.h>

+ Inheritance diagram for pcl::OrganizedMultiPlaneSegmentation< PointT, PointNT, PointLT >:
+ Collaboration diagram for pcl::OrganizedMultiPlaneSegmentation< PointT, PointNT, PointLT >:

Public Types

using PointCloud = pcl::PointCloud< PointT >
 
using PointCloudPtr = typename PointCloud::Ptr
 
using PointCloudConstPtr = typename PointCloud::ConstPtr
 
using PointCloudN = pcl::PointCloud< PointNT >
 
using PointCloudNPtr = typename PointCloudN::Ptr
 
using PointCloudNConstPtr = typename PointCloudN::ConstPtr
 
using PointCloudL = pcl::PointCloud< PointLT >
 
using PointCloudLPtr = typename PointCloudL::Ptr
 
using PointCloudLConstPtr = typename PointCloudL::ConstPtr
 
using PlaneComparator = pcl::PlaneCoefficientComparator< PointT, PointNT >
 
using PlaneComparatorPtr = typename PlaneComparator::Ptr
 
using PlaneComparatorConstPtr = typename PlaneComparator::ConstPtr
 
using PlaneRefinementComparator = pcl::PlaneRefinementComparator< PointT, PointNT, PointLT >
 
using PlaneRefinementComparatorPtr = typename PlaneRefinementComparator::Ptr
 
using PlaneRefinementComparatorConstPtr = typename PlaneRefinementComparator::ConstPtr
 
- Public Types inherited from pcl::PCLBase< PointT >
using PointCloud = pcl::PointCloud< PointT >
 
using PointCloudPtr = typename PointCloud::Ptr
 
using PointCloudConstPtr = typename PointCloud::ConstPtr
 
using PointIndicesPtr = PointIndices::Ptr
 
using PointIndicesConstPtr = PointIndices::ConstPtr
 

Public Member Functions

 OrganizedMultiPlaneSegmentation ()=default
 Constructor for OrganizedMultiPlaneSegmentation. More...
 
 ~OrganizedMultiPlaneSegmentation () override=default
 Destructor for OrganizedMultiPlaneSegmentation. More...
 
void setInputNormals (const PointCloudNConstPtr &normals)
 Provide a pointer to the input normals. More...
 
PointCloudNConstPtr getInputNormals () const
 Get the input normals. More...
 
void setMinInliers (unsigned min_inliers)
 Set the minimum number of inliers required for a plane. More...
 
unsigned getMinInliers () const
 Get the minimum number of inliers required per plane. More...
 
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. More...
 
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. More...
 
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. More...
 
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. More...
 
void setMaximumCurvature (double maximum_curvature)
 Set the maximum curvature allowed for a planar region. More...
 
double getMaximumCurvature () const
 Get the maximum curvature allowed for a planar region. More...
 
void setComparator (const PlaneComparatorPtr &compare)
 Provide a pointer to the comparator to be used for segmentation. More...
 
void setRefinementComparator (const PlaneRefinementComparatorPtr &compare)
 Provide a pointer to the comparator to be used for refinement. More...
 
void setProjectPoints (bool project_points)
 Set whether or not to project boundary points to the plane, or leave them in the original 3D space. More...
 
void 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() More...
 
void segment (std::vector< ModelCoefficients > &model_coefficients, std::vector< PointIndices > &inlier_indices)
 Segmentation of all planes in a point cloud given by setInputCloud(), setIndices() More...
 
void segment (std::vector< PlanarRegion< PointT >, Eigen::aligned_allocator< PlanarRegion< PointT > > > &regions)
 Segmentation of all planes in a point cloud given by setInputCloud(), setIndices() More...
 
void segmentAndRefine (std::vector< PlanarRegion< PointT >, Eigen::aligned_allocator< PlanarRegion< PointT > > > &regions)
 Perform a segmentation, as well as an additional refinement step. More...
 
void 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. More...
 
void refine (std::vector< ModelCoefficients > &model_coefficients, std::vector< PointIndices > &inlier_indices, 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. More...
 
- Public Member Functions inherited from pcl::PCLBase< PointT >
 PCLBase ()
 Empty constructor. More...
 
 PCLBase (const PCLBase &base)
 Copy constructor. More...
 
virtual ~PCLBase ()=default
 Destructor. More...
 
virtual void setInputCloud (const PointCloudConstPtr &cloud)
 Provide a pointer to the input dataset. More...
 
PointCloudConstPtr const getInputCloud () const
 Get a pointer to the input point cloud dataset. More...
 
virtual void setIndices (const IndicesPtr &indices)
 Provide a pointer to the vector of indices that represents the input data. More...
 
virtual void setIndices (const IndicesConstPtr &indices)
 Provide a pointer to the vector of indices that represents the input data. More...
 
virtual void setIndices (const PointIndicesConstPtr &indices)
 Provide a pointer to the vector of indices that represents the input data. More...
 
virtual void setIndices (std::size_t row_start, std::size_t col_start, std::size_t nb_rows, std::size_t nb_cols)
 Set the indices for the points laying within an interest region of the point cloud. More...
 
IndicesPtr getIndices ()
 Get a pointer to the vector of indices used. More...
 
IndicesConstPtr const getIndices () const
 Get a pointer to the vector of indices used. More...
 
const PointToperator[] (std::size_t pos) const
 Override PointCloud operator[] to shorten code. More...
 

Protected Member Functions

virtual std::string getClassName () const
 Class getName method. More...
 
- Protected Member Functions inherited from pcl::PCLBase< PointT >
bool initCompute ()
 This method should get called before starting the actual computation. More...
 
bool deinitCompute ()
 This method should get called after finishing the actual computation. More...
 

Protected Attributes

PointCloudNConstPtr normals_ {nullptr}
 A pointer to the input normals. More...
 
unsigned min_inliers_ {1000}
 The minimum number of inliers required for each plane. More...
 
double angular_threshold_ {pcl::deg2rad (3.0)}
 The tolerance in radians for difference in normal direction between neighboring points, to be considered part of the same plane. More...
 
double distance_threshold_ {0.02}
 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. More...
 
double maximum_curvature_ {0.001}
 The tolerance for maximum curvature after fitting a plane. More...
 
bool project_points_ {false}
 Whether or not points should be projected to the plane, or left in the original 3D space. More...
 
PlaneComparatorPtr compare_ {new PlaneComparator}
 A comparator for comparing neighboring pixels' plane equations. More...
 
PlaneRefinementComparatorPtr refinement_compare_ {new PlaneRefinementComparator}
 A comparator for use on the refinement step. More...
 
- Protected Attributes inherited from pcl::PCLBase< PointT >
PointCloudConstPtr input_
 The input point cloud dataset. More...
 
IndicesPtr indices_
 A pointer to the vector of point indices to use. More...
 
bool use_indices_
 Set to true if point indices are used. More...
 
bool fake_indices_
 If no set of indices are given, we construct a set of fake indices that mimic the input PointCloud. More...
 

Detailed Description

template<typename PointT, typename PointNT, typename PointLT>
class pcl::OrganizedMultiPlaneSegmentation< PointT, PointNT, PointLT >

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

Author
Alex Trevor, Suat Gedikli

Definition at line 63 of file organized_multi_plane_segmentation.h.

Member Typedef Documentation

◆ PlaneComparator

template<typename PointT , typename PointNT , typename PointLT >
using pcl::OrganizedMultiPlaneSegmentation< PointT, PointNT, PointLT >::PlaneComparator = pcl::PlaneCoefficientComparator<PointT, PointNT>

Definition at line 83 of file organized_multi_plane_segmentation.h.

◆ PlaneComparatorConstPtr

template<typename PointT , typename PointNT , typename PointLT >
using pcl::OrganizedMultiPlaneSegmentation< PointT, PointNT, PointLT >::PlaneComparatorConstPtr = typename PlaneComparator::ConstPtr

Definition at line 85 of file organized_multi_plane_segmentation.h.

◆ PlaneComparatorPtr

template<typename PointT , typename PointNT , typename PointLT >
using pcl::OrganizedMultiPlaneSegmentation< PointT, PointNT, PointLT >::PlaneComparatorPtr = typename PlaneComparator::Ptr

Definition at line 84 of file organized_multi_plane_segmentation.h.

◆ PlaneRefinementComparator

template<typename PointT , typename PointNT , typename PointLT >
using pcl::OrganizedMultiPlaneSegmentation< PointT, PointNT, PointLT >::PlaneRefinementComparator = pcl::PlaneRefinementComparator<PointT, PointNT, PointLT>

Definition at line 87 of file organized_multi_plane_segmentation.h.

◆ PlaneRefinementComparatorConstPtr

template<typename PointT , typename PointNT , typename PointLT >
using pcl::OrganizedMultiPlaneSegmentation< PointT, PointNT, PointLT >::PlaneRefinementComparatorConstPtr = typename PlaneRefinementComparator::ConstPtr

Definition at line 89 of file organized_multi_plane_segmentation.h.

◆ PlaneRefinementComparatorPtr

template<typename PointT , typename PointNT , typename PointLT >
using pcl::OrganizedMultiPlaneSegmentation< PointT, PointNT, PointLT >::PlaneRefinementComparatorPtr = typename PlaneRefinementComparator::Ptr

Definition at line 88 of file organized_multi_plane_segmentation.h.

◆ PointCloud

template<typename PointT , typename PointNT , typename PointLT >
using pcl::OrganizedMultiPlaneSegmentation< PointT, PointNT, PointLT >::PointCloud = pcl::PointCloud<PointT>

Definition at line 71 of file organized_multi_plane_segmentation.h.

◆ PointCloudConstPtr

template<typename PointT , typename PointNT , typename PointLT >
using pcl::OrganizedMultiPlaneSegmentation< PointT, PointNT, PointLT >::PointCloudConstPtr = typename PointCloud::ConstPtr

Definition at line 73 of file organized_multi_plane_segmentation.h.

◆ PointCloudL

template<typename PointT , typename PointNT , typename PointLT >
using pcl::OrganizedMultiPlaneSegmentation< PointT, PointNT, PointLT >::PointCloudL = pcl::PointCloud<PointLT>

Definition at line 79 of file organized_multi_plane_segmentation.h.

◆ PointCloudLConstPtr

template<typename PointT , typename PointNT , typename PointLT >
using pcl::OrganizedMultiPlaneSegmentation< PointT, PointNT, PointLT >::PointCloudLConstPtr = typename PointCloudL::ConstPtr

Definition at line 81 of file organized_multi_plane_segmentation.h.

◆ PointCloudLPtr

template<typename PointT , typename PointNT , typename PointLT >
using pcl::OrganizedMultiPlaneSegmentation< PointT, PointNT, PointLT >::PointCloudLPtr = typename PointCloudL::Ptr

Definition at line 80 of file organized_multi_plane_segmentation.h.

◆ PointCloudN

template<typename PointT , typename PointNT , typename PointLT >
using pcl::OrganizedMultiPlaneSegmentation< PointT, PointNT, PointLT >::PointCloudN = pcl::PointCloud<PointNT>

Definition at line 75 of file organized_multi_plane_segmentation.h.

◆ PointCloudNConstPtr

template<typename PointT , typename PointNT , typename PointLT >
using pcl::OrganizedMultiPlaneSegmentation< PointT, PointNT, PointLT >::PointCloudNConstPtr = typename PointCloudN::ConstPtr

Definition at line 77 of file organized_multi_plane_segmentation.h.

◆ PointCloudNPtr

template<typename PointT , typename PointNT , typename PointLT >
using pcl::OrganizedMultiPlaneSegmentation< PointT, PointNT, PointLT >::PointCloudNPtr = typename PointCloudN::Ptr

Definition at line 76 of file organized_multi_plane_segmentation.h.

◆ PointCloudPtr

template<typename PointT , typename PointNT , typename PointLT >
using pcl::OrganizedMultiPlaneSegmentation< PointT, PointNT, PointLT >::PointCloudPtr = typename PointCloud::Ptr

Definition at line 72 of file organized_multi_plane_segmentation.h.

Constructor & Destructor Documentation

◆ OrganizedMultiPlaneSegmentation()

template<typename PointT , typename PointNT , typename PointLT >
pcl::OrganizedMultiPlaneSegmentation< PointT, PointNT, PointLT >::OrganizedMultiPlaneSegmentation ( )
default

◆ ~OrganizedMultiPlaneSegmentation()

template<typename PointT , typename PointNT , typename PointLT >
pcl::OrganizedMultiPlaneSegmentation< PointT, PointNT, PointLT >::~OrganizedMultiPlaneSegmentation ( )
overridedefault

Member Function Documentation

◆ getAngularThreshold()

template<typename PointT , typename PointNT , typename PointLT >
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 141 of file organized_multi_plane_segmentation.h.

References pcl::OrganizedMultiPlaneSegmentation< PointT, PointNT, PointLT >::angular_threshold_.

◆ getClassName()

template<typename PointT , typename PointNT , typename PointLT >
virtual std::string pcl::OrganizedMultiPlaneSegmentation< PointT, PointNT, PointLT >::getClassName ( ) const
inlineprotectedvirtual

Class getName method.

Definition at line 298 of file organized_multi_plane_segmentation.h.

◆ getDistanceThreshold()

template<typename PointT , typename PointNT , typename PointLT >
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 157 of file organized_multi_plane_segmentation.h.

References pcl::OrganizedMultiPlaneSegmentation< PointT, PointNT, PointLT >::distance_threshold_.

◆ getInputNormals()

template<typename PointT , typename PointNT , typename PointLT >
PointCloudNConstPtr pcl::OrganizedMultiPlaneSegmentation< PointT, PointNT, PointLT >::getInputNormals ( ) const
inline

◆ getMaximumCurvature()

template<typename PointT , typename PointNT , typename PointLT >
double pcl::OrganizedMultiPlaneSegmentation< PointT, PointNT, PointLT >::getMaximumCurvature ( ) const
inline

Get the maximum curvature allowed for a planar region.

Definition at line 173 of file organized_multi_plane_segmentation.h.

References pcl::OrganizedMultiPlaneSegmentation< PointT, PointNT, PointLT >::maximum_curvature_.

◆ getMinInliers()

template<typename PointT , typename PointNT , typename PointLT >
unsigned pcl::OrganizedMultiPlaneSegmentation< PointT, PointNT, PointLT >::getMinInliers ( ) const
inline

Get the minimum number of inliers required per plane.

Definition at line 125 of file organized_multi_plane_segmentation.h.

References pcl::OrganizedMultiPlaneSegmentation< PointT, PointNT, PointLT >::min_inliers_.

◆ refine()

template<typename PointT , typename PointNT , typename PointLT >
void pcl::OrganizedMultiPlaneSegmentation< PointT, PointNT, PointLT >::refine ( std::vector< ModelCoefficients > &  model_coefficients,
std::vector< PointIndices > &  inlier_indices,
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.

Parameters
[in]model_coefficientsThe list of segmented model coefficients
[in]inlier_indicesThe list of segmented inlier indices, corresponding to each model
[in]labelsThe labels produced by the initial segmentation
[in]label_indicesThe list of indices corresponding to each label

Definition at line 321 of file organized_multi_plane_segmentation.hpp.

◆ segment() [1/3]

template<typename PointT , typename PointNT , typename PointLT >
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()

Parameters
[out]model_coefficientsa vector of model_coefficients for each plane found in the input cloud
[out]inlier_indicesa vector of inliers for each detected plane

Definition at line 71 of file organized_multi_plane_segmentation.hpp.

◆ segment() [2/3]

template<typename PointT , typename PointNT , typename PointLT >
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()

Parameters
[out]model_coefficientsa vector of model_coefficients for each plane found in the input cloud
[out]inlier_indicesa vector of inliers for each detected plane
[out]centroidsa vector of centroids for each plane
[out]covariancesa vector of covariance matrices for the inliers of each plane
[out]labelsa point cloud for the connected component labels of each pixel
[out]label_indicesa vector of PointIndices for each labeled component

Definition at line 83 of file organized_multi_plane_segmentation.hpp.

References pcl::computeMeanAndCovarianceMatrix(), pcl::eigen33(), pcl::OrganizedConnectedComponentSegmentation< PointT, PointLT >::segment(), pcl::PCLBase< PointT >::setInputCloud(), and pcl::ModelCoefficients::values.

◆ segment() [3/3]

template<typename PointT , typename PointNT , typename PointLT >
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()

Parameters
[out]regionsa list of resultant planar polygonal regions

Definition at line 196 of file organized_multi_plane_segmentation.hpp.

References pcl::OrganizedConnectedComponentSegmentation< PointT, PointLT >::findLabeledRegionBoundary(), and pcl::PointCloud< PointT >::resize().

◆ segmentAndRefine() [1/2]

template<typename PointT , typename PointNT , typename PointLT >
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.

Parameters
[out]regionsA list of regions generated by segmentation and refinement.

Definition at line 233 of file organized_multi_plane_segmentation.hpp.

◆ segmentAndRefine() [2/2]

template<typename PointT , typename PointNT , typename PointLT >
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.

Parameters
[out]regionsA vector of PlanarRegions generated by segmentation
[out]model_coefficientsA vector of model coefficients for each segmented plane
[out]inlier_indicesA vector of PointIndices, indicating the inliers to each segmented plane
[out]labelsA PointCloud<PointLT> corresponding to the resulting segmentation.
[out]label_indicesA vector of PointIndices for each label
[out]boundary_indicesA vector of PointIndices corresponding to the outer boundary / contour of each label

Definition at line 277 of file organized_multi_plane_segmentation.hpp.

References pcl::PointCloud< PointT >::empty(), pcl::OrganizedConnectedComponentSegmentation< PointT, PointLT >::findLabeledRegionBoundary(), pcl::PointCloud< PointT >::points, and pcl::PointCloud< PointT >::resize().

◆ setAngularThreshold()

template<typename PointT , typename PointNT , typename PointLT >
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.

Parameters
[in]angular_thresholdthe tolerance in radians

Definition at line 134 of file organized_multi_plane_segmentation.h.

References pcl::OrganizedMultiPlaneSegmentation< PointT, PointNT, PointLT >::angular_threshold_.

◆ setComparator()

template<typename PointT , typename PointNT , typename PointLT >
void pcl::OrganizedMultiPlaneSegmentation< PointT, PointNT, PointLT >::setComparator ( const PlaneComparatorPtr compare)
inline

Provide a pointer to the comparator to be used for segmentation.

Parameters
[in]compareA pointer to the comparator to be used for segmentation.

Definition at line 182 of file organized_multi_plane_segmentation.h.

References pcl::OrganizedMultiPlaneSegmentation< PointT, PointNT, PointLT >::compare_.

◆ setDistanceThreshold()

template<typename PointT , typename PointNT , typename PointLT >
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.

Parameters
[in]distance_thresholdthe tolerance in meters

Definition at line 150 of file organized_multi_plane_segmentation.h.

References pcl::OrganizedMultiPlaneSegmentation< PointT, PointNT, PointLT >::distance_threshold_.

◆ setInputNormals()

template<typename PointT , typename PointNT , typename PointLT >
void pcl::OrganizedMultiPlaneSegmentation< PointT, PointNT, PointLT >::setInputNormals ( const PointCloudNConstPtr normals)
inline

Provide a pointer to the input normals.

Parameters
[in]normalsthe input normal cloud

Definition at line 102 of file organized_multi_plane_segmentation.h.

References pcl::OrganizedMultiPlaneSegmentation< PointT, PointNT, PointLT >::normals_.

◆ setMaximumCurvature()

template<typename PointT , typename PointNT , typename PointLT >
void pcl::OrganizedMultiPlaneSegmentation< PointT, PointNT, PointLT >::setMaximumCurvature ( double  maximum_curvature)
inline

Set the maximum curvature allowed for a planar region.

Parameters
[in]maximum_curvaturethe maximum curvature

Definition at line 166 of file organized_multi_plane_segmentation.h.

References pcl::OrganizedMultiPlaneSegmentation< PointT, PointNT, PointLT >::maximum_curvature_.

◆ setMinInliers()

template<typename PointT , typename PointNT , typename PointLT >
void pcl::OrganizedMultiPlaneSegmentation< PointT, PointNT, PointLT >::setMinInliers ( unsigned  min_inliers)
inline

Set the minimum number of inliers required for a plane.

Parameters
[in]min_inliersthe minimum number of inliers required per plane

Definition at line 118 of file organized_multi_plane_segmentation.h.

References pcl::OrganizedMultiPlaneSegmentation< PointT, PointNT, PointLT >::min_inliers_.

◆ setProjectPoints()

template<typename PointT , typename PointNT , typename PointLT >
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.

Parameters
[in]project_pointstrue if points should be projected, false if not.

Definition at line 200 of file organized_multi_plane_segmentation.h.

References pcl::OrganizedMultiPlaneSegmentation< PointT, PointNT, PointLT >::project_points_.

◆ setRefinementComparator()

template<typename PointT , typename PointNT , typename PointLT >
void pcl::OrganizedMultiPlaneSegmentation< PointT, PointNT, PointLT >::setRefinementComparator ( const PlaneRefinementComparatorPtr compare)
inline

Provide a pointer to the comparator to be used for refinement.

Parameters
[in]compareA pointer to the comparator to be used for refinement.

Definition at line 191 of file organized_multi_plane_segmentation.h.

References pcl::OrganizedMultiPlaneSegmentation< PointT, PointNT, PointLT >::refinement_compare_.

Member Data Documentation

◆ angular_threshold_

template<typename PointT , typename PointNT , typename PointLT >
double pcl::OrganizedMultiPlaneSegmentation< PointT, PointNT, PointLT >::angular_threshold_ {pcl::deg2rad (3.0)}
protected

The tolerance in radians for difference in normal direction between neighboring points, to be considered part of the same plane.

Definition at line 279 of file organized_multi_plane_segmentation.h.

Referenced by pcl::OrganizedMultiPlaneSegmentation< PointT, PointNT, PointLT >::getAngularThreshold(), and pcl::OrganizedMultiPlaneSegmentation< PointT, PointNT, PointLT >::setAngularThreshold().

◆ compare_

template<typename PointT , typename PointNT , typename PointLT >
PlaneComparatorPtr pcl::OrganizedMultiPlaneSegmentation< PointT, PointNT, PointLT >::compare_ {new PlaneComparator}
protected

A comparator for comparing neighboring pixels' plane equations.

Definition at line 291 of file organized_multi_plane_segmentation.h.

Referenced by pcl::OrganizedMultiPlaneSegmentation< PointT, PointNT, PointLT >::setComparator().

◆ distance_threshold_

template<typename PointT , typename PointNT , typename PointLT >
double pcl::OrganizedMultiPlaneSegmentation< PointT, PointNT, PointLT >::distance_threshold_ {0.02}
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 282 of file organized_multi_plane_segmentation.h.

Referenced by pcl::OrganizedMultiPlaneSegmentation< PointT, PointNT, PointLT >::getDistanceThreshold(), and pcl::OrganizedMultiPlaneSegmentation< PointT, PointNT, PointLT >::setDistanceThreshold().

◆ maximum_curvature_

template<typename PointT , typename PointNT , typename PointLT >
double pcl::OrganizedMultiPlaneSegmentation< PointT, PointNT, PointLT >::maximum_curvature_ {0.001}
protected

The tolerance for maximum curvature after fitting a plane.

Used to remove smooth, but non-planar regions.

Definition at line 285 of file organized_multi_plane_segmentation.h.

Referenced by pcl::OrganizedMultiPlaneSegmentation< PointT, PointNT, PointLT >::getMaximumCurvature(), and pcl::OrganizedMultiPlaneSegmentation< PointT, PointNT, PointLT >::setMaximumCurvature().

◆ min_inliers_

template<typename PointT , typename PointNT , typename PointLT >
unsigned pcl::OrganizedMultiPlaneSegmentation< PointT, PointNT, PointLT >::min_inliers_ {1000}
protected

◆ normals_

template<typename PointT , typename PointNT , typename PointLT >
PointCloudNConstPtr pcl::OrganizedMultiPlaneSegmentation< PointT, PointNT, PointLT >::normals_ {nullptr}
protected

◆ project_points_

template<typename PointT , typename PointNT , typename PointLT >
bool pcl::OrganizedMultiPlaneSegmentation< PointT, PointNT, PointLT >::project_points_ {false}
protected

Whether or not points should be projected to the plane, or left in the original 3D space.

Definition at line 288 of file organized_multi_plane_segmentation.h.

Referenced by pcl::OrganizedMultiPlaneSegmentation< PointT, PointNT, PointLT >::setProjectPoints().

◆ refinement_compare_

template<typename PointT , typename PointNT , typename PointLT >
PlaneRefinementComparatorPtr pcl::OrganizedMultiPlaneSegmentation< PointT, PointNT, PointLT >::refinement_compare_ {new PlaneRefinementComparator}
protected

A comparator for use on the refinement step.

Compares points to regions segmented in the first pass.

Definition at line 294 of file organized_multi_plane_segmentation.h.

Referenced by pcl::OrganizedMultiPlaneSegmentation< PointT, PointNT, PointLT >::setRefinementComparator().


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