SegmentDifferences obtains the difference between two spatially aligned point clouds and returns the difference between them for a maximum given distance threshold. More...
#include <segment_differences.h>

Public Types | |
| typedef pcl::KdTree< PointT > | KdTree |
| typedef pcl::KdTree< PointT >::Ptr | KdTreePtr |
| typedef pcl::PointCloud< PointT > | PointCloud |
| typedef PointCloud::ConstPtr | PointCloudConstPtr |
| typedef PointCloud::Ptr | PointCloudPtr |
| typedef PointIndices::ConstPtr | PointIndicesConstPtr |
| typedef PointIndices::Ptr | PointIndicesPtr |
Public Member Functions | |
| double | getDistanceThreshold () |
| Get the distance tolerance between corresponding points as a measure in the L2 Euclidean space. | |
| KdTreePtr | getSearchMethod () |
| Get a pointer to the search method used. | |
| PointCloudConstPtr const | getTargetCloud () |
| Get a pointer to the input target point cloud dataset. | |
| void | segment (PointCloud &output) |
| Segment differences between two input point clouds. | |
| SegmentDifferences () | |
| Empty constructor. | |
| void | setDistanceThreshold (double threshold) |
| Set the maximum distance tolerance between corresponding points in the two input datasets. | |
| void | setSearchMethod (const KdTreePtr &tree) |
| Provide a pointer to the search object. | |
| void | setTargetCloud (const PointCloudConstPtr &cloud) |
| Provide a pointer to the target dataset against which we compare the input cloud given in setInputCloud. | |
Protected Member Functions | |
| virtual std::string | getClassName () const |
| Class getName method. | |
Protected Attributes | |
| double | distance_threshold_ |
| The distance tolerance as a measure in the L2 Euclidean space between corresponding points. | |
| int | spatial_locator_ |
| Parameter for the spatial locator tree. By convention, the values represent: 0: ANN (Approximate Nearest Neigbor library) kd-tree 1: FLANN (Fast Library for Approximate Nearest Neighbors) kd-tree 2: Organized spatial dataset index. | |
| PointCloudConstPtr | target_ |
| The input target point cloud dataset. | |
| KdTreePtr | tree_ |
| A pointer to the spatial search object. | |
Private Types | |
| typedef PCLBase< PointT > | BasePCLBase |
SegmentDifferences obtains the difference between two spatially aligned point clouds and returns the difference between them for a maximum given distance threshold.
Definition at line 71 of file segment_differences.h.
typedef PCLBase<PointT> pcl::SegmentDifferences< PointT >::BasePCLBase [private] |
Definition at line 73 of file segment_differences.h.
| typedef pcl::KdTree<PointT> pcl::SegmentDifferences< PointT >::KdTree |
Definition at line 80 of file segment_differences.h.
| typedef pcl::KdTree<PointT>::Ptr pcl::SegmentDifferences< PointT >::KdTreePtr |
Definition at line 81 of file segment_differences.h.
| typedef pcl::PointCloud<PointT> pcl::SegmentDifferences< PointT >::PointCloud |
Reimplemented from pcl::PCLBase< PointT >.
Definition at line 76 of file segment_differences.h.
| typedef PointCloud::ConstPtr pcl::SegmentDifferences< PointT >::PointCloudConstPtr |
Reimplemented from pcl::PCLBase< PointT >.
Definition at line 78 of file segment_differences.h.
| typedef PointCloud::Ptr pcl::SegmentDifferences< PointT >::PointCloudPtr |
Reimplemented from pcl::PCLBase< PointT >.
Definition at line 77 of file segment_differences.h.
| typedef PointIndices::ConstPtr pcl::SegmentDifferences< PointT >::PointIndicesConstPtr |
Reimplemented from pcl::PCLBase< PointT >.
Definition at line 84 of file segment_differences.h.
| typedef PointIndices::Ptr pcl::SegmentDifferences< PointT >::PointIndicesPtr |
Reimplemented from pcl::PCLBase< PointT >.
Definition at line 83 of file segment_differences.h.
| pcl::SegmentDifferences< PointT >::SegmentDifferences | ( | ) | [inline] |
Empty constructor.
Definition at line 88 of file segment_differences.h.
| virtual std::string pcl::SegmentDifferences< PointT >::getClassName | ( | ) | const [inline, protected, virtual] |
Class getName method.
Definition at line 152 of file segment_differences.h.
| double pcl::SegmentDifferences< PointT >::getDistanceThreshold | ( | ) | [inline] |
Get the distance tolerance between corresponding points as a measure in the L2 Euclidean space.
Definition at line 119 of file segment_differences.h.
| KdTreePtr pcl::SegmentDifferences< PointT >::getSearchMethod | ( | ) | [inline] |
Get a pointer to the search method used.
Definition at line 109 of file segment_differences.h.
| PointCloudConstPtr const pcl::SegmentDifferences< PointT >::getTargetCloud | ( | ) | [inline] |
Get a pointer to the input target point cloud dataset.
Definition at line 99 of file segment_differences.h.
| void pcl::SegmentDifferences< PointT >::segment | ( | PointCloud & | output | ) | [inline] |
Segment differences between two input point clouds.
| output | the resultant difference between the two point clouds as a PointCloud |
Definition at line 80 of file segment_differences.hpp.
| void pcl::SegmentDifferences< PointT >::setDistanceThreshold | ( | double | threshold | ) | [inline] |
Set the maximum distance tolerance between corresponding points in the two input datasets.
| threshold | the distance tolerance as a measure in the L2 Euclidean space |
Definition at line 115 of file segment_differences.h.
| void pcl::SegmentDifferences< PointT >::setSearchMethod | ( | const KdTreePtr & | tree | ) | [inline] |
Provide a pointer to the search object.
| tree | a pointer to the spatial search object. |
Definition at line 105 of file segment_differences.h.
| void pcl::SegmentDifferences< PointT >::setTargetCloud | ( | const PointCloudConstPtr & | cloud | ) | [inline] |
Provide a pointer to the target dataset against which we compare the input cloud given in setInputCloud.
| cloud | the target PointCloud dataset |
Definition at line 95 of file segment_differences.h.
double pcl::SegmentDifferences< PointT >::distance_threshold_ [protected] |
The distance tolerance as a measure in the L2 Euclidean space between corresponding points.
Definition at line 148 of file segment_differences.h.
int pcl::SegmentDifferences< PointT >::spatial_locator_ [protected] |
Parameter for the spatial locator tree. By convention, the values represent: 0: ANN (Approximate Nearest Neigbor library) kd-tree 1: FLANN (Fast Library for Approximate Nearest Neighbors) kd-tree 2: Organized spatial dataset index.
Definition at line 145 of file segment_differences.h.
PointCloudConstPtr pcl::SegmentDifferences< PointT >::target_ [protected] |
The input target point cloud dataset.
Definition at line 138 of file segment_differences.h.
KdTreePtr pcl::SegmentDifferences< PointT >::tree_ [protected] |
A pointer to the spatial search object.
Definition at line 135 of file segment_differences.h.