Classes | Functions
pcl::registration Namespace Reference

Classes

class  ConvergenceCriteria
 ConvergenceCriteria represents an abstract base class for different convergence criteria used in registration loops. More...
class  CorrespondenceEstimation
 CorrespondenceEstimation represents the base class for determining correspondences between target and query point sets/features. More...
class  CorrespondenceEstimationBackProjection
 CorrespondenceEstimationBackprojection computes correspondences as points in the target cloud which have minimum More...
class  CorrespondenceEstimationBase
 Abstract CorrespondenceEstimationBase class. All correspondence estimation methods should inherit from this. More...
class  CorrespondenceEstimationNormalShooting
 CorrespondenceEstimationNormalShooting computes correspondences as points in the target cloud which have minimum distance to normals computed on the input cloud More...
class  CorrespondenceEstimationOrganizedProjection
 CorrespondenceEstimationOrganizedProjection computes correspondences by projecting the source point cloud onto the target point cloud using the camera intrinsic and extrinsic parameters. The correspondences can be trimmed by a depth threshold and by a distance threshold. It is not as precise as a nearest neighbor search, but it is much faster, as it avoids the usage of any additional structures (i.e., kd-trees). More...
class  CorrespondenceRejectionOrganizedBoundary
 The CorrespondenceRejectionOrganizedBoundary class implements a simple correspondence rejection measure. For each pair of points in correspondence, it checks whether they are on the boundary of a silhouette. This is done by counting the number of NaN dexels in a window around the points (the threshold and window size can be set by the user). More...
class  CorrespondenceRejector
class  CorrespondenceRejectorDistance
class  CorrespondenceRejectorFeatures
 CorrespondenceRejectorFeatures implements a correspondence rejection method based on a set of feature descriptors. Given an input feature space, the method checks if each feature in the source cloud has a correspondence in the target cloud, either by checking the first K (given) point correspondences, or by defining a tolerance threshold via a radius in feature space. More...
class  CorrespondenceRejectorMedianDistance
 CorrespondenceRejectorMedianDistance implements a simple correspondence rejection method based on thresholding based on the median distance between the correspondences. More...
class  CorrespondenceRejectorOneToOne
 CorrespondenceRejectorOneToOne implements a correspondence rejection method based on eliminating duplicate match indices in the correspondences. Correspondences with the same match index are removed and only the one with smallest distance between query and match are kept. That is, considering match->query 1-m correspondences are removed leaving only 1-1 correspondences. More...
class  CorrespondenceRejectorPoly
 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...
class  CorrespondenceRejectorSampleConsensus
 CorrespondenceRejectorSampleConsensus implements a correspondence rejection using Random Sample Consensus to identify inliers (and reject outliers) More...
class  CorrespondenceRejectorSampleConsensus2D
 CorrespondenceRejectorSampleConsensus2D implements a pixel-based correspondence rejection using Random Sample Consensus to identify inliers (and reject outliers) More...
class  CorrespondenceRejectorSurfaceNormal
class  CorrespondenceRejectorTrimmed
 CorrespondenceRejectorTrimmed implements a correspondence rejection for ICP-like registration algorithms that uses only the best 'k' correspondences where 'k' is some estimate of the overlap between the two point clouds being registered. More...
class  CorrespondenceRejectorVarTrimmed
class  DataContainer
class  DataContainerInterface
class  DefaultConvergenceCriteria
 DefaultConvergenceCriteria represents an instantiation of ConvergenceCriteria, and implements the following criteria for registration loop evaluation: More...
class  ELCH
 ELCH (Explicit Loop Closing Heuristic) class More...
class  GraphHandler
 GraphHandler class is a wrapper for a general SLAM graph The actual graph class must fulfil the following boost::graph concepts: More...
class  GraphOptimizer
 GraphOptimizer class; derive and specialize for each graph type More...
class  LUM
 Globally Consistent Scan Matching based on an algorithm by Lu and Milios. More...
struct  NullEstimate
 NullEstimate struct More...
struct  NullMeasurement
 NullMeasurement struct More...
struct  PoseEstimate
 PoseEstimate struct More...
struct  PoseMeasurement
 PoseMeasurement struct More...
struct  sortCorrespondencesByDistance
struct  sortCorrespondencesByMatchIndex
struct  sortCorrespondencesByMatchIndexAndDistance
struct  sortCorrespondencesByQueryIndex
struct  sortCorrespondencesByQueryIndexAndDistance
class  TransformationEstimation
 TransformationEstimation represents the base class for methods for transformation estimation based on: More...
class  TransformationEstimation2D
class  TransformationEstimationLM
class  TransformationEstimationPointToPlane
class  TransformationEstimationPointToPlaneLLS
 TransformationEstimationPointToPlaneLLS implements a Linear Least Squares (LLS) approximation for minimizing the point-to-plane distance between two clouds of corresponding points with normals. More...
class  TransformationEstimationPointToPlaneLLSWeighted
 TransformationEstimationPointToPlaneLLSWeighted implements a Linear Least Squares (LLS) approximation for minimizing the point-to-plane distance between two clouds of corresponding points with normals, with the possibility of assigning weights to the correspondences. More...
class  TransformationEstimationPointToPlaneWeighted
class  TransformationEstimationSVD
class  TransformationEstimationSVDScale
class  TransformationValidation
 TransformationValidation represents the base class for methods that validate the correctness of a transformation found through TransformationEstimation. More...
class  TransformationValidationEuclidean
 TransformationValidationEuclidean computes an L2SQR norm between a source and target dataset. More...
class  WarpPointRigid
 Base warp point class. More...
class  WarpPointRigid3D
 WarpPointRigid3D enables 3D (1D rotation + 2D translation) transformations for points. More...
class  WarpPointRigid6D
 WarpPointRigid3D enables 6D (3D rotation + 3D translation) transformations for points. More...

Functions

void getCorDistMeanStd (const pcl::Correspondences &correspondences, double &mean, double &stddev)
 calculates the mean and standard deviation of descriptor distances from correspondences
void getMatchIndices (const pcl::Correspondences &correspondences, std::vector< int > &indices)
 extracts the match indices
void getQueryIndices (const pcl::Correspondences &correspondences, std::vector< int > &indices)
 extracts the query indices

Function Documentation

void pcl::registration::getCorDistMeanStd ( const pcl::Correspondences correspondences,
double &  mean,
double &  stddev 
) [inline]

calculates the mean and standard deviation of descriptor distances from correspondences

Parameters:
[in]correspondenceslist of correspondences
[out]meanthe mean descriptor distance of correspondences
[out]stddevthe standard deviation of descriptor distances.
Note:
The sample varaiance is used to determine the standard deviation

Definition at line 48 of file correspondence_types.hpp.

void pcl::registration::getMatchIndices ( const pcl::Correspondences correspondences,
std::vector< int > &  indices 
) [inline]

extracts the match indices

Parameters:
[in]correspondenceslist of correspondences
[out]indicesarray of extracted indices.
Note:
order of indices corresponds to input list of descriptor correspondences

Definition at line 76 of file correspondence_types.hpp.

void pcl::registration::getQueryIndices ( const pcl::Correspondences correspondences,
std::vector< int > &  indices 
) [inline]

extracts the query indices

Parameters:
[in]correspondenceslist of correspondences
[out]indicesarray of extracted indices.
Note:
order of indices corresponds to input list of descriptor correspondences

Definition at line 67 of file correspondence_types.hpp.



pcl
Author(s): Open Perception
autogenerated on Wed Aug 26 2015 15:44:43