Public Types | Public Member Functions | Protected Member Functions | Protected Attributes
pcl::registration::CorrespondenceRejectorPoly< SourceT, TargetT > Class Template Reference

CorrespondenceRejectorPoly implements a correspondence rejection method that exploits low-level and pose-invariant geometric constraints between two point sets by forming virtual polygons of a user-specifiable cardinality on each model using the input correspondences. These polygons are then checked in a pose-invariant manner (i.e. the side lengths must be approximately equal), and rejection is performed by thresholding these edge lengths. More...

#include <correspondence_rejection_poly.h>

Inheritance diagram for pcl::registration::CorrespondenceRejectorPoly< SourceT, TargetT >:
Inheritance graph
[legend]

List of all members.

Public Types

typedef boost::shared_ptr
< const
CorrespondenceRejectorPoly
ConstPtr
typedef pcl::PointCloud< SourceT > PointCloudSource
typedef PointCloudSource::ConstPtr PointCloudSourceConstPtr
typedef PointCloudSource::Ptr PointCloudSourcePtr
typedef pcl::PointCloud< TargetT > PointCloudTarget
typedef PointCloudTarget::ConstPtr PointCloudTargetConstPtr
typedef PointCloudTarget::Ptr PointCloudTargetPtr
typedef boost::shared_ptr
< CorrespondenceRejectorPoly
Ptr

Public Member Functions

 CorrespondenceRejectorPoly ()
 Empty constructor.
int getCardinality ()
 Get the polygon cardinality.
int getIterations ()
 Get the number of iterations.
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.
float getSimilarityThreshold ()
 Get the similarity threshold between edge lengths.
void setCardinality (int cardinality)
 Set the polygon cardinality.
void setInputCloud (const PointCloudSourceConstPtr &cloud)
 Provide a source point cloud dataset (must contain XYZ data!), used to compute the correspondence distance.
void setInputSource (const PointCloudSourceConstPtr &cloud)
 Provide a source point cloud dataset (must contain XYZ data!), used to compute the correspondence distance.
void setInputTarget (const PointCloudTargetConstPtr &target)
 Provide a target point cloud dataset (must contain XYZ data!), used to compute the correspondence distance.
void setIterations (int iterations)
 Set the number of iterations.
void setSimilarityThreshold (float similarity_threshold)
 Set the similarity threshold in [0,1[ between edge lengths, where 1 is a perfect match.
bool thresholdPolygon (const pcl::Correspondences &corr, const std::vector< int > &idx)
 Polygonal rejection of a single polygon, indexed by a subset of correspondences.
bool thresholdPolygon (const std::vector< int > &source_indices, const std::vector< int > &target_indices)
 Polygonal rejection of a single polygon, indexed by two point index vectors.

Protected Member Functions

void applyRejection (pcl::Correspondences &correspondences)
 Apply the rejection algorithm.
std::vector< int > computeHistogram (const std::vector< float > &data, float lower, float upper, int bins)
 Compute a linear histogram. This function is equivalent to the MATLAB function histc, with the edges set as follows: lower:(upper-lower)/bins:upper
float computeSquaredDistance (const SourceT &p1, const TargetT &p2)
 Squared Euclidean distance between two points using the members x, y and z.
int findThresholdOtsu (const std::vector< int > &histogram)
 Find the optimal value for binary histogram thresholding using Otsu's method.
std::vector< int > getUniqueRandomIndices (int n, int k)
 Get k unique random indices in range {0,...,n-1} (sampling without replacement)
bool thresholdEdgeLength (int index_query_1, int index_query_2, int index_match_1, int index_match_2, float simsq)
 Edge length similarity thresholding.

Protected Attributes

int cardinality_
 The polygon cardinality used during rejection.
PointCloudSourceConstPtr input_
 The input point cloud dataset.
int iterations_
 Number of iterations to run.
float similarity_threshold_
 Lower edge length threshold in [0,1] used for verifying polygon similarities, where 1 is a perfect match.
float similarity_threshold_squared_
 Squared value if similarity_threshold_, only for internal use.
PointCloudTargetConstPtr target_
 The input point cloud dataset target.

Detailed Description

template<typename SourceT, typename TargetT>
class pcl::registration::CorrespondenceRejectorPoly< SourceT, TargetT >

CorrespondenceRejectorPoly implements a correspondence rejection method that exploits low-level and pose-invariant geometric constraints between two point sets by forming virtual polygons of a user-specifiable cardinality on each model using the input correspondences. These polygons are then checked in a pose-invariant manner (i.e. the side lengths must be approximately equal), and rejection is performed by thresholding these edge lengths.

If you use this in academic work, please cite:

A. G. Buch, D. Kraft, J.-K. Kämäräinen, H. G. Petersen and N. Krüger. Pose Estimation using Local Structure-Specific Shape and Appearance Context. International Conference on Robotics and Automation (ICRA), 2013.

Author:
Anders Glent Buch

Definition at line 64 of file correspondence_rejection_poly.h.


Member Typedef Documentation

template<typename SourceT, typename TargetT>
typedef boost::shared_ptr<const CorrespondenceRejectorPoly> pcl::registration::CorrespondenceRejectorPoly< SourceT, TargetT >::ConstPtr

Reimplemented from pcl::registration::CorrespondenceRejector.

Definition at line 72 of file correspondence_rejection_poly.h.

template<typename SourceT, typename TargetT>
typedef pcl::PointCloud<SourceT> pcl::registration::CorrespondenceRejectorPoly< SourceT, TargetT >::PointCloudSource

Definition at line 74 of file correspondence_rejection_poly.h.

template<typename SourceT, typename TargetT>
typedef PointCloudSource::ConstPtr pcl::registration::CorrespondenceRejectorPoly< SourceT, TargetT >::PointCloudSourceConstPtr

Definition at line 76 of file correspondence_rejection_poly.h.

template<typename SourceT, typename TargetT>
typedef PointCloudSource::Ptr pcl::registration::CorrespondenceRejectorPoly< SourceT, TargetT >::PointCloudSourcePtr

Definition at line 75 of file correspondence_rejection_poly.h.

template<typename SourceT, typename TargetT>
typedef pcl::PointCloud<TargetT> pcl::registration::CorrespondenceRejectorPoly< SourceT, TargetT >::PointCloudTarget

Definition at line 78 of file correspondence_rejection_poly.h.

template<typename SourceT, typename TargetT>
typedef PointCloudTarget::ConstPtr pcl::registration::CorrespondenceRejectorPoly< SourceT, TargetT >::PointCloudTargetConstPtr

Definition at line 80 of file correspondence_rejection_poly.h.

template<typename SourceT, typename TargetT>
typedef PointCloudTarget::Ptr pcl::registration::CorrespondenceRejectorPoly< SourceT, TargetT >::PointCloudTargetPtr

Definition at line 79 of file correspondence_rejection_poly.h.

template<typename SourceT, typename TargetT>
typedef boost::shared_ptr<CorrespondenceRejectorPoly> pcl::registration::CorrespondenceRejectorPoly< SourceT, TargetT >::Ptr

Reimplemented from pcl::registration::CorrespondenceRejector.

Definition at line 71 of file correspondence_rejection_poly.h.


Constructor & Destructor Documentation

template<typename SourceT, typename TargetT>
pcl::registration::CorrespondenceRejectorPoly< SourceT, TargetT >::CorrespondenceRejectorPoly ( ) [inline]

Empty constructor.

Definition at line 83 of file correspondence_rejection_poly.h.


Member Function Documentation

template<typename SourceT, typename TargetT>
void pcl::registration::CorrespondenceRejectorPoly< SourceT, TargetT >::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 237 of file correspondence_rejection_poly.h.

template<typename SourceT , typename TargetT >
std::vector< int > pcl::registration::CorrespondenceRejectorPoly< SourceT, TargetT >::computeHistogram ( const std::vector< float > &  data,
float  lower,
float  upper,
int  bins 
) [protected]

Compute a linear histogram. This function is equivalent to the MATLAB function histc, with the edges set as follows: lower:(upper-lower)/bins:upper

Parameters:
datainput samples
lowerlower bound of input samples
upperupper bound of input samples
binsnumber of bins in output
Returns:
linear histogram

Definition at line 154 of file correspondence_rejection_poly.hpp.

template<typename SourceT, typename TargetT>
float pcl::registration::CorrespondenceRejectorPoly< SourceT, TargetT >::computeSquaredDistance ( const SourceT &  p1,
const TargetT &  p2 
) [inline, protected]

Squared Euclidean distance between two points using the members x, y and z.

Parameters:
p1first point
p2second point
Returns:
squared Euclidean distance

Definition at line 282 of file correspondence_rejection_poly.h.

template<typename SourceT , typename TargetT >
int pcl::registration::CorrespondenceRejectorPoly< SourceT, TargetT >::findThresholdOtsu ( const std::vector< int > &  histogram) [protected]

Find the optimal value for binary histogram thresholding using Otsu's method.

Parameters:
histograminput histogram
Returns:
threshold value according to Otsu's criterion

Definition at line 173 of file correspondence_rejection_poly.hpp.

template<typename SourceT, typename TargetT>
int pcl::registration::CorrespondenceRejectorPoly< SourceT, TargetT >::getCardinality ( ) [inline]

Get the polygon cardinality.

Returns:
polygon cardinality

Definition at line 142 of file correspondence_rejection_poly.h.

template<typename SourceT, typename TargetT>
int pcl::registration::CorrespondenceRejectorPoly< SourceT, TargetT >::getIterations ( ) [inline]

Get the number of iterations.

Returns:
number of iterations

Definition at line 180 of file correspondence_rejection_poly.h.

template<typename SourceT , typename TargetT >
void pcl::registration::CorrespondenceRejectorPoly< SourceT, TargetT >::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 43 of file correspondence_rejection_poly.hpp.

template<typename SourceT, typename TargetT>
float pcl::registration::CorrespondenceRejectorPoly< SourceT, TargetT >::getSimilarityThreshold ( ) [inline]

Get the similarity threshold between edge lengths.

Returns:
similarity threshold

Definition at line 162 of file correspondence_rejection_poly.h.

template<typename SourceT, typename TargetT>
std::vector<int> pcl::registration::CorrespondenceRejectorPoly< SourceT, TargetT >::getUniqueRandomIndices ( int  n,
int  k 
) [inline, protected]

Get k unique random indices in range {0,...,n-1} (sampling without replacement)

Note:
No check is made to ensure that k <= n.
Parameters:
nupper index range, exclusive
knumber of unique indices to sample
Returns:
k unique random indices in range {0,...,n-1}

Definition at line 249 of file correspondence_rejection_poly.h.

template<typename SourceT, typename TargetT>
void pcl::registration::CorrespondenceRejectorPoly< SourceT, TargetT >::setCardinality ( int  cardinality) [inline]

Set the polygon cardinality.

Parameters:
cardinalitypolygon cardinality

Definition at line 133 of file correspondence_rejection_poly.h.

template<typename SourceT, typename TargetT>
void pcl::registration::CorrespondenceRejectorPoly< SourceT, TargetT >::setInputCloud ( const PointCloudSourceConstPtr 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 113 of file correspondence_rejection_poly.h.

template<typename SourceT, typename TargetT>
void pcl::registration::CorrespondenceRejectorPoly< SourceT, TargetT >::setInputSource ( const PointCloudSourceConstPtr 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 104 of file correspondence_rejection_poly.h.

template<typename SourceT, typename TargetT>
void pcl::registration::CorrespondenceRejectorPoly< SourceT, TargetT >::setInputTarget ( const PointCloudTargetConstPtr 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 124 of file correspondence_rejection_poly.h.

template<typename SourceT, typename TargetT>
void pcl::registration::CorrespondenceRejectorPoly< SourceT, TargetT >::setIterations ( int  iterations) [inline]

Set the number of iterations.

Parameters:
iterationsnumber of iterations

Definition at line 171 of file correspondence_rejection_poly.h.

template<typename SourceT, typename TargetT>
void pcl::registration::CorrespondenceRejectorPoly< SourceT, TargetT >::setSimilarityThreshold ( float  similarity_threshold) [inline]

Set the similarity threshold in [0,1[ between edge lengths, where 1 is a perfect match.

Parameters:
similaritysimilarity threshold

Definition at line 152 of file correspondence_rejection_poly.h.

template<typename SourceT, typename TargetT>
bool pcl::registration::CorrespondenceRejectorPoly< SourceT, TargetT >::thresholdEdgeLength ( int  index_query_1,
int  index_query_2,
int  index_match_1,
int  index_match_2,
float  simsq 
) [inline, protected]

Edge length similarity thresholding.

Parameters:
index_query_1index of first source vertex
index_query_2index of second source vertex
index_match_1index of first target vertex
index_match_2index of second target vertex
simsqsquared similarity threshold in [0,1]
Returns:
true if edge length ratio is larger than or equal to threshold

Definition at line 300 of file correspondence_rejection_poly.h.

template<typename SourceT, typename TargetT>
bool pcl::registration::CorrespondenceRejectorPoly< SourceT, TargetT >::thresholdPolygon ( const pcl::Correspondences corr,
const std::vector< int > &  idx 
) [inline]

Polygonal rejection of a single polygon, indexed by a subset of correspondences.

Parameters:
corrall correspondences into input_ and target_
idxsampled indices into correspondences, must have a size equal to cardinality_
Returns:
true if all edge length ratios are larger than or equal to similarity_threshold_

Definition at line 191 of file correspondence_rejection_poly.h.

template<typename SourceT, typename TargetT>
bool pcl::registration::CorrespondenceRejectorPoly< SourceT, TargetT >::thresholdPolygon ( const std::vector< int > &  source_indices,
const std::vector< int > &  target_indices 
) [inline]

Polygonal rejection of a single polygon, indexed by two point index vectors.

Parameters:
source_indicesindices of polygon points in input_, must have a size equal to cardinality_
target_indicescorresponding indices of polygon points in target_, must have a size equal to cardinality_
Returns:
true if all edge length ratios are larger than or equal to similarity_threshold_

Definition at line 217 of file correspondence_rejection_poly.h.


Member Data Documentation

template<typename SourceT, typename TargetT>
int pcl::registration::CorrespondenceRejectorPoly< SourceT, TargetT >::cardinality_ [protected]

The polygon cardinality used during rejection.

Definition at line 344 of file correspondence_rejection_poly.h.

template<typename SourceT, typename TargetT>
PointCloudSourceConstPtr pcl::registration::CorrespondenceRejectorPoly< SourceT, TargetT >::input_ [protected]

The input point cloud dataset.

Definition at line 335 of file correspondence_rejection_poly.h.

template<typename SourceT, typename TargetT>
int pcl::registration::CorrespondenceRejectorPoly< SourceT, TargetT >::iterations_ [protected]

Number of iterations to run.

Definition at line 341 of file correspondence_rejection_poly.h.

template<typename SourceT, typename TargetT>
float pcl::registration::CorrespondenceRejectorPoly< SourceT, TargetT >::similarity_threshold_ [protected]

Lower edge length threshold in [0,1] used for verifying polygon similarities, where 1 is a perfect match.

Definition at line 347 of file correspondence_rejection_poly.h.

template<typename SourceT, typename TargetT>
float pcl::registration::CorrespondenceRejectorPoly< SourceT, TargetT >::similarity_threshold_squared_ [protected]

Squared value if similarity_threshold_, only for internal use.

Definition at line 350 of file correspondence_rejection_poly.h.

template<typename SourceT, typename TargetT>
PointCloudTargetConstPtr pcl::registration::CorrespondenceRejectorPoly< SourceT, TargetT >::target_ [protected]

The input point cloud dataset target.

Definition at line 338 of file correspondence_rejection_poly.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:13