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

#include <correspondence_rejection_var_trimmed.h>

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

List of all members.

Public Types

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

Public Member Functions

 CorrespondenceRejectorVarTrimmed ()
 Empty constructor.
double getMaxRatio () const
double getMinRatio () const
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.
double getTrimFactor () const
 Get the computed inlier ratio used for thresholding in correspondence rejection.
double getTrimmedDistance () const
 Get the trimmed distance used for thresholding in correspondence rejection.
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 setMaxRatio (double ratio)
void setMinRatio (double ratio)
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. Only factor times the total points sorted based on the correspondence distances will be considered as inliers. Remaining points are rejected. This factor is computed internally.
double lambda_
 part of the term that balances the root mean square difference. This is an internal parameter
double max_ratio_
 The maximum overlap ratio between the input and target clouds.
double min_ratio_
 The minimum overlap ratio between the input and target clouds.
double trimmed_distance_
 The inlier distance threshold (based on the computed trim factor) between two correspondent points in source <-> target.

Private Member Functions

float optimizeInlierRatio (std::vector< double > &dists)
 finds the optimal inlier ratio. This is based on the paper 'Outlier Robust ICP for minimizing Fractional RMSD, J. M. Philips et al'

Detailed Description

CorrespondenceRejectoVarTrimmed implements a simple correspondence rejection method by considering as inliers a certain percentage of correspondences with the least distances. The percentage of inliers is computed internally as mentioned in the paper 'Outlier Robust ICP for minimizing Fractional RMSD, J. M. Philips et al'

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 64 of file correspondence_rejection_var_trimmed.h.


Member Typedef Documentation

Definition at line 209 of file correspondence_rejection_var_trimmed.h.


Constructor & Destructor Documentation

Empty constructor.

Definition at line 75 of file correspondence_rejection_var_trimmed.h.


Member Function Documentation

void pcl::registration::CorrespondenceRejectorVarTrimmed::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 182 of file correspondence_rejection_var_trimmed.h.

brief get the maximum overlap ratio

Definition at line 174 of file correspondence_rejection_var_trimmed.h.

brief get the minimum overlap ratio

Definition at line 163 of file correspondence_rejection_var_trimmed.h.

void pcl::registration::CorrespondenceRejectorVarTrimmed::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_var_trimmed.cpp.

Get the computed inlier ratio used for thresholding in correspondence rejection.

Definition at line 152 of file correspondence_rejection_var_trimmed.h.

Get the trimmed distance used for thresholding in correspondence rejection.

Definition at line 96 of file correspondence_rejection_var_trimmed.h.

float pcl::registration::CorrespondenceRejectorVarTrimmed::optimizeInlierRatio ( std::vector< double > &  dists) [inline, private]

finds the optimal inlier ratio. This is based on the paper 'Outlier Robust ICP for minimizing Fractional RMSD, J. M. Philips et al'

Definition at line 82 of file correspondence_rejection_var_trimmed.cpp.

template<typename PointT >
void pcl::registration::CorrespondenceRejectorVarTrimmed::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 115 of file correspondence_rejection_var_trimmed.h.

template<typename PointT >
void pcl::registration::CorrespondenceRejectorVarTrimmed::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 103 of file correspondence_rejection_var_trimmed.h.

template<typename PointT >
void pcl::registration::CorrespondenceRejectorVarTrimmed::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 128 of file correspondence_rejection_var_trimmed.h.

brief set the maximum overlap ratio

Parameters:
[in]ratiothe overlap ratio [0..1]

Definition at line 169 of file correspondence_rejection_var_trimmed.h.

brief set the minimum overlap ratio

Parameters:
[in]ratiothe overlap ratio [0..1]

Definition at line 158 of file correspondence_rejection_var_trimmed.h.

template<typename PointT >
void pcl::registration::CorrespondenceRejectorVarTrimmed::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 143 of file correspondence_rejection_var_trimmed.h.


Member Data Documentation

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

Definition at line 212 of file correspondence_rejection_var_trimmed.h.

The factor for correspondence rejection. Only factor times the total points sorted based on the correspondence distances will be considered as inliers. Remaining points are rejected. This factor is computed internally.

Definition at line 195 of file correspondence_rejection_var_trimmed.h.

part of the term that balances the root mean square difference. This is an internal parameter

Definition at line 207 of file correspondence_rejection_var_trimmed.h.

The maximum overlap ratio between the input and target clouds.

Definition at line 203 of file correspondence_rejection_var_trimmed.h.

The minimum overlap ratio between the input and target clouds.

Definition at line 199 of file correspondence_rejection_var_trimmed.h.

The inlier distance threshold (based on the computed trim factor) between two correspondent points in source <-> target.

Definition at line 189 of file correspondence_rejection_var_trimmed.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:57