EuclideanClusterComparator is a comparator used for finding clusters supported by planar surfaces. This needs to be run as a second pass after extracting planar surfaces, using MultiPlaneSegmentation for example. More...
#include <euclidean_cluster_comparator.h>
Public Types | |
typedef boost::shared_ptr < const EuclideanClusterComparator < PointT, PointNT, PointLT > > | ConstPtr |
typedef Comparator< PointT > ::PointCloud | PointCloud |
typedef Comparator< PointT > ::PointCloudConstPtr | 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 boost::shared_ptr < EuclideanClusterComparator < PointT, PointNT, PointLT > > | Ptr |
Public Member Functions | |
virtual bool | compare (int idx1, int idx2) const |
Compare points at two indices by their plane equations. True if the angle between the normals is less than the angular threshold, and the difference between the d component of the normals is less than distance threshold, else false. | |
EuclideanClusterComparator () | |
Empty constructor for EuclideanClusterComparator. | |
float | getAngularThreshold () const |
Get the angular threshold in radians for difference in normal direction between neighboring points, to be considered part of the same plane. | |
float | 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. | |
virtual void | setAngularThreshold (float angular_threshold) |
Set the tolerance in radians for difference in normal direction between neighboring points, to be considered part of the same plane. | |
void | setDistanceThreshold (float distance_threshold, bool depth_dependent) |
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 | setExcludeLabels (std::vector< bool > &exclude_labels) |
Set labels in the label cloud to exclude. | |
virtual void | setInputCloud (const PointCloudConstPtr &cloud) |
Set the input cloud for the comparator. | |
void | setInputNormals (const PointCloudNConstPtr &normals) |
Provide a pointer to the input normals. | |
void | setLabels (PointCloudLPtr &labels) |
Set label cloud. | |
virtual | ~EuclideanClusterComparator () |
Destructor for EuclideanClusterComparator. | |
Protected Attributes | |
float | angular_threshold_ |
bool | depth_dependent_ |
float | distance_threshold_ |
boost::shared_ptr< std::vector < bool > > | exclude_labels_ |
PointCloudLPtr | labels_ |
PointCloudNConstPtr | normals_ |
Eigen::Vector3f | z_axis_ |
EuclideanClusterComparator is a comparator used for finding clusters supported by planar surfaces. This needs to be run as a second pass after extracting planar surfaces, using MultiPlaneSegmentation for example.
Definition at line 54 of file euclidean_cluster_comparator.h.
typedef boost::shared_ptr<const EuclideanClusterComparator<PointT, PointNT, PointLT> > pcl::EuclideanClusterComparator< PointT, PointNT, PointLT >::ConstPtr |
Reimplemented from pcl::Comparator< PointT >.
Definition at line 69 of file euclidean_cluster_comparator.h.
typedef Comparator<PointT>::PointCloud pcl::EuclideanClusterComparator< PointT, PointNT, PointLT >::PointCloud |
Reimplemented from pcl::Comparator< PointT >.
Definition at line 57 of file euclidean_cluster_comparator.h.
typedef Comparator<PointT>::PointCloudConstPtr pcl::EuclideanClusterComparator< PointT, PointNT, PointLT >::PointCloudConstPtr |
Reimplemented from pcl::Comparator< PointT >.
Definition at line 58 of file euclidean_cluster_comparator.h.
typedef pcl::PointCloud<PointLT> pcl::EuclideanClusterComparator< PointT, PointNT, PointLT >::PointCloudL |
Definition at line 64 of file euclidean_cluster_comparator.h.
typedef PointCloudL::ConstPtr pcl::EuclideanClusterComparator< PointT, PointNT, PointLT >::PointCloudLConstPtr |
Definition at line 66 of file euclidean_cluster_comparator.h.
typedef PointCloudL::Ptr pcl::EuclideanClusterComparator< PointT, PointNT, PointLT >::PointCloudLPtr |
Definition at line 65 of file euclidean_cluster_comparator.h.
typedef pcl::PointCloud<PointNT> pcl::EuclideanClusterComparator< PointT, PointNT, PointLT >::PointCloudN |
Definition at line 60 of file euclidean_cluster_comparator.h.
typedef PointCloudN::ConstPtr pcl::EuclideanClusterComparator< PointT, PointNT, PointLT >::PointCloudNConstPtr |
Definition at line 62 of file euclidean_cluster_comparator.h.
typedef PointCloudN::Ptr pcl::EuclideanClusterComparator< PointT, PointNT, PointLT >::PointCloudNPtr |
Definition at line 61 of file euclidean_cluster_comparator.h.
typedef boost::shared_ptr<EuclideanClusterComparator<PointT, PointNT, PointLT> > pcl::EuclideanClusterComparator< PointT, PointNT, PointLT >::Ptr |
Reimplemented from pcl::Comparator< PointT >.
Definition at line 68 of file euclidean_cluster_comparator.h.
pcl::EuclideanClusterComparator< PointT, PointNT, PointLT >::EuclideanClusterComparator | ( | ) | [inline] |
Empty constructor for EuclideanClusterComparator.
Definition at line 74 of file euclidean_cluster_comparator.h.
virtual pcl::EuclideanClusterComparator< PointT, PointNT, PointLT >::~EuclideanClusterComparator | ( | ) | [inline, virtual] |
Destructor for EuclideanClusterComparator.
Definition at line 85 of file euclidean_cluster_comparator.h.
virtual bool pcl::EuclideanClusterComparator< PointT, PointNT, PointLT >::compare | ( | int | idx1, |
int | idx2 | ||
) | const [inline, virtual] |
Compare points at two indices by their plane equations. True if the angle between the normals is less than the angular threshold, and the difference between the d component of the normals is less than distance threshold, else false.
idx1 | The first index for the comparison |
idx2 | The second index for the comparison |
Implements pcl::Comparator< PointT >.
Definition at line 170 of file euclidean_cluster_comparator.h.
float pcl::EuclideanClusterComparator< 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 124 of file euclidean_cluster_comparator.h.
float pcl::EuclideanClusterComparator< 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 141 of file euclidean_cluster_comparator.h.
PointCloudNConstPtr pcl::EuclideanClusterComparator< PointT, PointNT, PointLT >::getInputNormals | ( | ) | const [inline] |
Get the input normals.
Definition at line 108 of file euclidean_cluster_comparator.h.
virtual void pcl::EuclideanClusterComparator< PointT, PointNT, PointLT >::setAngularThreshold | ( | float | angular_threshold | ) | [inline, virtual] |
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 117 of file euclidean_cluster_comparator.h.
void pcl::EuclideanClusterComparator< PointT, PointNT, PointLT >::setDistanceThreshold | ( | float | distance_threshold, |
bool | depth_dependent | ||
) | [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 133 of file euclidean_cluster_comparator.h.
void pcl::EuclideanClusterComparator< PointT, PointNT, PointLT >::setExcludeLabels | ( | std::vector< bool > & | exclude_labels | ) | [inline] |
Set labels in the label cloud to exclude.
exclude_labels | a vector of bools corresponding to whether or not a given label should be considered |
Definition at line 159 of file euclidean_cluster_comparator.h.
virtual void pcl::EuclideanClusterComparator< PointT, PointNT, PointLT >::setInputCloud | ( | const PointCloudConstPtr & | cloud | ) | [inline, virtual] |
Set the input cloud for the comparator.
[in] | cloud | the point cloud this comparator will operate on |
Reimplemented from pcl::Comparator< PointT >.
Definition at line 90 of file euclidean_cluster_comparator.h.
void pcl::EuclideanClusterComparator< PointT, PointNT, PointLT >::setInputNormals | ( | const PointCloudNConstPtr & | normals | ) | [inline] |
Provide a pointer to the input normals.
[in] | normals | the input normal cloud |
Definition at line 101 of file euclidean_cluster_comparator.h.
void pcl::EuclideanClusterComparator< PointT, PointNT, PointLT >::setLabels | ( | PointCloudLPtr & | labels | ) | [inline] |
Set label cloud.
[in] | labels | The label cloud |
Definition at line 150 of file euclidean_cluster_comparator.h.
float pcl::EuclideanClusterComparator< PointT, PointNT, PointLT >::angular_threshold_ [protected] |
Definition at line 194 of file euclidean_cluster_comparator.h.
bool pcl::EuclideanClusterComparator< PointT, PointNT, PointLT >::depth_dependent_ [protected] |
Definition at line 196 of file euclidean_cluster_comparator.h.
float pcl::EuclideanClusterComparator< PointT, PointNT, PointLT >::distance_threshold_ [protected] |
Definition at line 195 of file euclidean_cluster_comparator.h.
boost::shared_ptr<std::vector<bool> > pcl::EuclideanClusterComparator< PointT, PointNT, PointLT >::exclude_labels_ [protected] |
Definition at line 193 of file euclidean_cluster_comparator.h.
PointCloudLPtr pcl::EuclideanClusterComparator< PointT, PointNT, PointLT >::labels_ [protected] |
Definition at line 191 of file euclidean_cluster_comparator.h.
PointCloudNConstPtr pcl::EuclideanClusterComparator< PointT, PointNT, PointLT >::normals_ [protected] |
Definition at line 190 of file euclidean_cluster_comparator.h.
Eigen::Vector3f pcl::EuclideanClusterComparator< PointT, PointNT, PointLT >::z_axis_ [protected] |
Definition at line 197 of file euclidean_cluster_comparator.h.