Public Types | Public Member Functions | Protected Attributes
pcl::RGBPlaneCoefficientComparator< PointT, PointNT > Class Template Reference

RGBPlaneCoefficientComparator is a Comparator that operates on plane coefficients, for use in planar segmentation. Also takes into account RGB, so we can segmented different colored co-planar regions. In conjunction with OrganizedConnectedComponentSegmentation, this allows planes to be segmented from organized data. More...

#include <rgb_plane_coefficient_comparator.h>

Inheritance diagram for pcl::RGBPlaneCoefficientComparator< PointT, PointNT >:
Inheritance graph
[legend]

List of all members.

Public Types

typedef boost::shared_ptr
< const
RGBPlaneCoefficientComparator
< PointT, PointNT > > 
ConstPtr
typedef Comparator< PointT >
::PointCloud 
PointCloud
typedef Comparator< PointT >
::PointCloudConstPtr 
PointCloudConstPtr
typedef pcl::PointCloud< PointNT > PointCloudN
typedef PointCloudN::ConstPtr PointCloudNConstPtr
typedef PointCloudN::Ptr PointCloudNPtr
typedef boost::shared_ptr
< RGBPlaneCoefficientComparator
< PointT, PointNT > > 
Ptr

Public Member Functions

bool compare (int idx1, int idx2) const
 Compare two neighboring points, by using normal information, euclidean distance, and color information.
float getColorThreshold () const
 Get the color threshold between neighboring points, to be considered part of the same plane.
 RGBPlaneCoefficientComparator ()
 Empty constructor for RGBPlaneCoefficientComparator.
 RGBPlaneCoefficientComparator (boost::shared_ptr< std::vector< float > > &plane_coeff_d)
 Constructor for RGBPlaneCoefficientComparator.
void setColorThreshold (float color_threshold)
 Set the tolerance in color space between neighboring points, to be considered part of the same plane.
virtual ~RGBPlaneCoefficientComparator ()
 Destructor for RGBPlaneCoefficientComparator.

Protected Attributes

float color_threshold_

Detailed Description

template<typename PointT, typename PointNT>
class pcl::RGBPlaneCoefficientComparator< PointT, PointNT >

RGBPlaneCoefficientComparator is a Comparator that operates on plane coefficients, for use in planar segmentation. Also takes into account RGB, so we can segmented different colored co-planar regions. In conjunction with OrganizedConnectedComponentSegmentation, this allows planes to be segmented from organized data.

Author:
Alex Trevor

Definition at line 55 of file rgb_plane_coefficient_comparator.h.


Member Typedef Documentation

template<typename PointT, typename PointNT>
typedef boost::shared_ptr<const RGBPlaneCoefficientComparator<PointT, PointNT> > pcl::RGBPlaneCoefficientComparator< PointT, PointNT >::ConstPtr
template<typename PointT, typename PointNT>
typedef Comparator<PointT>::PointCloud pcl::RGBPlaneCoefficientComparator< PointT, PointNT >::PointCloud
template<typename PointT, typename PointNT>
typedef Comparator<PointT>::PointCloudConstPtr pcl::RGBPlaneCoefficientComparator< PointT, PointNT >::PointCloudConstPtr
template<typename PointT, typename PointNT>
typedef pcl::PointCloud<PointNT> pcl::RGBPlaneCoefficientComparator< PointT, PointNT >::PointCloudN
template<typename PointT, typename PointNT>
typedef PointCloudN::ConstPtr pcl::RGBPlaneCoefficientComparator< PointT, PointNT >::PointCloudNConstPtr
template<typename PointT, typename PointNT>
typedef PointCloudN::Ptr pcl::RGBPlaneCoefficientComparator< PointT, PointNT >::PointCloudNPtr
template<typename PointT, typename PointNT>
typedef boost::shared_ptr<RGBPlaneCoefficientComparator<PointT, PointNT> > pcl::RGBPlaneCoefficientComparator< PointT, PointNT >::Ptr

Constructor & Destructor Documentation

template<typename PointT, typename PointNT>
pcl::RGBPlaneCoefficientComparator< PointT, PointNT >::RGBPlaneCoefficientComparator ( ) [inline]

Empty constructor for RGBPlaneCoefficientComparator.

Definition at line 74 of file rgb_plane_coefficient_comparator.h.

template<typename PointT, typename PointNT>
pcl::RGBPlaneCoefficientComparator< PointT, PointNT >::RGBPlaneCoefficientComparator ( boost::shared_ptr< std::vector< float > > &  plane_coeff_d) [inline]

Constructor for RGBPlaneCoefficientComparator.

Parameters:
[in]plane_coeff_da reference to a vector of d coefficients of plane equations. Must be the same size as the input cloud and input normals. a, b, and c coefficients are in the input normals.

Definition at line 82 of file rgb_plane_coefficient_comparator.h.

template<typename PointT, typename PointNT>
virtual pcl::RGBPlaneCoefficientComparator< PointT, PointNT >::~RGBPlaneCoefficientComparator ( ) [inline, virtual]

Destructor for RGBPlaneCoefficientComparator.

Definition at line 89 of file rgb_plane_coefficient_comparator.h.


Member Function Documentation

template<typename PointT, typename PointNT>
bool pcl::RGBPlaneCoefficientComparator< PointT, PointNT >::compare ( int  idx1,
int  idx2 
) const [inline, virtual]

Compare two neighboring points, by using normal information, euclidean distance, and color information.

Parameters:
[in]idx1The index of the first point.
[in]idx2The index of the second point.

Reimplemented from pcl::PlaneCoefficientComparator< PointT, PointNT >.

Definition at line 114 of file rgb_plane_coefficient_comparator.h.

template<typename PointT, typename PointNT>
float pcl::RGBPlaneCoefficientComparator< PointT, PointNT >::getColorThreshold ( ) const [inline]

Get the color threshold between neighboring points, to be considered part of the same plane.

Definition at line 104 of file rgb_plane_coefficient_comparator.h.

template<typename PointT, typename PointNT>
void pcl::RGBPlaneCoefficientComparator< PointT, PointNT >::setColorThreshold ( float  color_threshold) [inline]

Set the tolerance in color space between neighboring points, to be considered part of the same plane.

Parameters:
[in]color_thresholdThe distance in color space

Definition at line 97 of file rgb_plane_coefficient_comparator.h.


Member Data Documentation

template<typename PointT, typename PointNT>
float pcl::RGBPlaneCoefficientComparator< PointT, PointNT >::color_threshold_ [protected]

Definition at line 131 of file rgb_plane_coefficient_comparator.h.


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


pcl
Author(s): Open Perception
autogenerated on Mon Oct 6 2014 03:19:59