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

CorrespondenceRejectorMedianDistance implements a simple correspondence rejection method based on thresholding based on the median distance between the correspondences. More...

#include <correspondence_rejection_median_distance.h>

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

List of all members.

Public Types

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

Public Member Functions

 CorrespondenceRejectorMedianDistance ()
 Empty constructor.
double getMedianDistance () const
 Get the median distance used for thresholding in correspondence rejection.
double getMedianFactor () const
 Get the factor 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.
void setMedianFactor (double factor)
 Set the factor for correspondence rejection. Points with distance greater than median times factor will be rejected.
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.

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.
double factor_
 The factor for correspondence rejection. Points with distance greater than median times factor will be rejected.
double median_distance_
 The median distance threshold between two correspondent points in source <-> target.

Detailed Description

CorrespondenceRejectorMedianDistance implements a simple correspondence rejection method based on thresholding based on the median distance 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:
Aravindhan K Krishnan. This code is ported from libpointmatcher (https://github.com/ethz-asl/libpointmatcher)

Definition at line 61 of file correspondence_rejection_median_distance.h.


Member Typedef Documentation

Definition at line 175 of file correspondence_rejection_median_distance.h.


Constructor & Destructor Documentation

Empty constructor.

Definition at line 72 of file correspondence_rejection_median_distance.h.


Member Function Documentation

Apply the rejection algorithm.

Parameters:
[out]correspondencesthe set of resultant correspondences.

Implements pcl::registration::CorrespondenceRejector.

Definition at line 161 of file correspondence_rejection_median_distance.h.

Get the median distance used for thresholding in correspondence rejection.

Definition at line 90 of file correspondence_rejection_median_distance.h.

Get the factor used for thresholding in correspondence rejection.

Definition at line 153 of file correspondence_rejection_median_distance.h.

void pcl::registration::CorrespondenceRejectorMedianDistance::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_median_distance.cpp.

template<typename PointT >
void pcl::registration::CorrespondenceRejectorMedianDistance::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 109 of file correspondence_rejection_median_distance.h.

template<typename PointT >
void pcl::registration::CorrespondenceRejectorMedianDistance::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 97 of file correspondence_rejection_median_distance.h.

template<typename PointT >
void pcl::registration::CorrespondenceRejectorMedianDistance::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 122 of file correspondence_rejection_median_distance.h.

Set the factor for correspondence rejection. Points with distance greater than median times factor will be rejected.

Parameters:
[in]factorvalue

Definition at line 149 of file correspondence_rejection_median_distance.h.

template<typename PointT >
void pcl::registration::CorrespondenceRejectorMedianDistance::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 137 of file correspondence_rejection_median_distance.h.


Member Data Documentation

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

Definition at line 178 of file correspondence_rejection_median_distance.h.

The factor for correspondence rejection. Points with distance greater than median times factor will be rejected.

Definition at line 173 of file correspondence_rejection_median_distance.h.

The median distance threshold between two correspondent points in source <-> target.

Definition at line 168 of file correspondence_rejection_median_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:06