Public Types | Public Member Functions | Protected Types | Protected Member Functions | Protected Attributes
pcl::registration::CorrespondenceRejectorDistance Class Reference

#include <correspondence_rejection_distance.h>

Inheritance diagram for pcl::registration::CorrespondenceRejectorDistance:
Inheritance graph
[legend]

List of all members.

Public Types

typedef boost::shared_ptr
< const
CorrespondenceRejectorDistance
ConstPtr
typedef boost::shared_ptr
< CorrespondenceRejectorDistance
Ptr

Public Member Functions

 CorrespondenceRejectorDistance ()
 Empty constructor.
float getMaximumDistance ()
 Get the maximum distance used for thresholding in correspondence rejection.
void getRemainingCorrespondences (const pcl::Correspondences &original_correspondences, pcl::Correspondences &remaining_correspondences)
 Get a list of valid correspondences after rejection from the original set of correspondences.
template<typename PointT >
void setInputCloud (const typename pcl::PointCloud< PointT >::ConstPtr &cloud)
 Provide a source point cloud dataset (must contain XYZ data!), used to compute the correspondence distance.
template<typename PointT >
void setInputSource (const typename pcl::PointCloud< PointT >::ConstPtr &cloud)
 Provide a source point cloud dataset (must contain XYZ data!), used to compute the correspondence distance.
template<typename PointT >
void setInputTarget (const typename pcl::PointCloud< PointT >::ConstPtr &target)
 Provide a target point cloud dataset (must contain XYZ data!), used to compute the correspondence distance.
virtual void setMaximumDistance (float distance)
 Set the maximum distance used for thresholding in correspondence rejection.
template<typename PointT >
void setSearchMethodTarget (const boost::shared_ptr< pcl::search::KdTree< PointT > > &tree, bool force_no_recompute=false)
 Provide a pointer to the search object used to find correspondences in the target cloud.
virtual ~CorrespondenceRejectorDistance ()
 Empty destructor.

Protected Types

typedef boost::shared_ptr
< DataContainerInterface
DataContainerPtr

Protected Member Functions

void applyRejection (pcl::Correspondences &correspondences)
 Apply the rejection algorithm.

Protected Attributes

DataContainerPtr data_container_
 A pointer to the DataContainer object containing the input and target point clouds.
float max_distance_
 The maximum distance threshold between two correspondent points in source <-> target. If the distance is larger than this threshold, the points will not be ignored in the alignment process.

Detailed Description

CorrespondenceRejectorDistance implements a simple correspondence rejection method based on thresholding the distances between the correspondences.

Note:
If setInputCloud and setInputTarget are given, then the distances between correspondences will be estimated using the given XYZ data, and not read from the set of input correspondences.
Author:
Dirk Holz, Radu B. Rusu

Definition at line 61 of file correspondence_rejection_distance.h.


Member Typedef Documentation

Reimplemented from pcl::registration::CorrespondenceRejector.

Definition at line 69 of file correspondence_rejection_distance.h.

Definition at line 170 of file correspondence_rejection_distance.h.

Reimplemented from pcl::registration::CorrespondenceRejector.

Definition at line 68 of file correspondence_rejection_distance.h.


Constructor & Destructor Documentation

Empty constructor.

Definition at line 72 of file correspondence_rejection_distance.h.

Empty destructor.

Definition at line 79 of file correspondence_rejection_distance.h.


Member Function Documentation

void pcl::registration::CorrespondenceRejectorDistance::applyRejection ( pcl::Correspondences correspondences) [inline, protected, virtual]

Apply the rejection algorithm.

Parameters:
[out]correspondencesthe set of resultant correspondences.

Implements pcl::registration::CorrespondenceRejector.

Definition at line 160 of file correspondence_rejection_distance.h.

Get the maximum distance used for thresholding in correspondence rejection.

Definition at line 99 of file correspondence_rejection_distance.h.

void pcl::registration::CorrespondenceRejectorDistance::getRemainingCorrespondences ( const pcl::Correspondences original_correspondences,
pcl::Correspondences remaining_correspondences 
) [virtual]

Get a list of valid correspondences after rejection from the original set of correspondences.

Parameters:
[in]original_correspondencesthe set of initial correspondences given
[out]remaining_correspondencesthe resultant filtered set of remaining correspondences

Implements pcl::registration::CorrespondenceRejector.

Definition at line 44 of file correspondence_rejection_distance.cpp.

template<typename PointT >
void pcl::registration::CorrespondenceRejectorDistance::setInputCloud ( const typename pcl::PointCloud< PointT >::ConstPtr cloud) [inline]

Provide a source point cloud dataset (must contain XYZ data!), used to compute the correspondence distance.

Parameters:
[in]clouda cloud containing XYZ data

Definition at line 106 of file correspondence_rejection_distance.h.

template<typename PointT >
void pcl::registration::CorrespondenceRejectorDistance::setInputSource ( const typename pcl::PointCloud< PointT >::ConstPtr cloud) [inline]

Provide a source point cloud dataset (must contain XYZ data!), used to compute the correspondence distance.

Parameters:
[in]clouda cloud containing XYZ data

Definition at line 119 of file correspondence_rejection_distance.h.

template<typename PointT >
void pcl::registration::CorrespondenceRejectorDistance::setInputTarget ( const typename pcl::PointCloud< PointT >::ConstPtr target) [inline]

Provide a target point cloud dataset (must contain XYZ data!), used to compute the correspondence distance.

Parameters:
[in]targeta cloud containing XYZ data

Definition at line 131 of file correspondence_rejection_distance.h.

virtual void pcl::registration::CorrespondenceRejectorDistance::setMaximumDistance ( float  distance) [inline, virtual]

Set the maximum distance used for thresholding in correspondence rejection.

Parameters:
[in]distanceDistance to be used as maximum distance between correspondences. Correspondences with larger distances are rejected.
Note:
Internally, the distance will be stored squared.

Definition at line 95 of file correspondence_rejection_distance.h.

template<typename PointT >
void pcl::registration::CorrespondenceRejectorDistance::setSearchMethodTarget ( const boost::shared_ptr< pcl::search::KdTree< PointT > > &  tree,
bool  force_no_recompute = false 
) [inline]

Provide a pointer to the search object used to find correspondences in the target cloud.

Parameters:
[in]treea pointer to the spatial search object.
[in]force_no_recomputeIf set to true, this tree will NEVER be recomputed, regardless of calls to setInputTarget. Only use if you are confident that the tree will be set correctly.

Definition at line 146 of file correspondence_rejection_distance.h.


Member Data Documentation

A pointer to the DataContainer object containing the input and target point clouds.

Definition at line 173 of file correspondence_rejection_distance.h.

The maximum distance threshold between two correspondent points in source <-> target. If the distance is larger than this threshold, the points will not be ignored in the alignment process.

Definition at line 168 of file correspondence_rejection_distance.h.


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


pcl
Author(s): Open Perception
autogenerated on Wed Aug 26 2015 15:45:03