All Classes Namespaces Files Functions Variables Typedefs Enumerations Properties Friends Defines
Public Types | Public Member Functions | Protected Member Functions | Protected Attributes | Private Member Functions | Private Attributes
pcl::RegistrationCorrespondencesCheck< PointSource, PointTarget > Class Template Reference

Registration represents the base registration class. All 3D registration methods should inherit from this class. More...

#include <registration_correspondences_check.h>

Inheritance diagram for pcl::RegistrationCorrespondencesCheck< PointSource, PointTarget >:
Inheritance graph
[legend]

List of all members.

Public Types

typedef pcl::KdTree< PointTarget > KdTree
typedef pcl::KdTree
< PointTarget >::Ptr 
KdTreePtr
typedef pcl::PointCloud
< PointSource > 
PointCloudSource
typedef PointCloudSource::ConstPtr PointCloudSourceConstPtr
typedef PointCloudSource::Ptr PointCloudSourcePtr
typedef pcl::PointCloud
< PointTarget > 
PointCloudTarget
typedef PointCloudTarget::ConstPtr PointCloudTargetConstPtr
typedef PointCloudTarget::Ptr PointCloudTargetPtr

Public Member Functions

void align (PointCloudSource &output)
 Call the registration algorithm which estimates the transformation and returns the transformed source (input) as output.
Eigen::Matrix4f getFinalTransformation ()
 Get the final transformation matrix estimated by the registration method.
double getFitnessScore (double max_range=std::numeric_limits< double >::max())
 Obtain the fitness score (e.g., sum of squared distances from the source to the target).
PointCloudTargetConstPtr const getInputTarget ()
 Get a pointer to the input point cloud dataset target target.
Eigen::Matrix4f getLastIncrementalTransformation ()
 Get the last incremental transformation matrix estimated by the registration method.
double getMaxCorrespondenceDistance ()
 Get the maximum distance threshold between two correspondent points in source <-> target. If the distance is larger than this threshold, the points will be ignored in the alignment process.
int getMaximumIterations ()
 Get the maximum number of iterations the internal optimization should run for, as set by the user.
double getTransformationEpsilon ()
 Get the transformation epsilon (maximum allowable difference between two consecutive transformations) as set by the user.
 RegistrationCorrespondencesCheck ()
 Empty constructor.
virtual void setInputTarget (const PointCloudTargetConstPtr &cloud)
 Provide a pointer to the input target target (e.g., the point cloud that we want to align the input source to)
void setMaxCorrespondenceDistance (double distance_threshold)
 Set the maximum distance threshold between two correspondent points in source <-> target. If the distance is larger than this threshold, the points will be ignored in the alignment process.
void setMaximumIterations (int nr_iterations)
 Set the maximum number of iterations the internal optimization should run for.
void setPointRepresentation (const typename KdTree::PointRepresentationConstPtr &point_representation)
 Provide a boost shared pointer to the PointRepresentation to be used when comparing points.
void setTransformationEpsilon (double epsilon)
 Set the transformation epsilon (maximum allowable difference between two consecutive transformations) in order for an optimization to be considered as having converged to the final solution.
virtual ~RegistrationCorrespondencesCheck ()
 Empty destructor.

Protected Member Functions

const std::string & getClassName () const
 Abstract class get name method.
bool searchForNeighbors (const PointCloudSource &cloud, int index, double radius, int max_nn, std::vector< int > &indices, std::vector< float > &distances)
 Search for neigbors of a given point based on radius search.

Protected Attributes

bool converged_
 Holds internal convergence state, given user parameters.
double corr_dist_threshold_
 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 alignement process.
Eigen::Matrix4f final_transformation_
 The final transformation matrix estimated by the registration method after N iterations.
int max_iterations_
 The maximum number of iterations the internal optimization should run for.
int min_number_correspondences_
 The minimum number of correspondences that the algorithm needs before attempting to estimate the transformation.
int nr_iterations_
 The number of iterations the internal optimization ran for (used internally).
Eigen::Matrix4f previous_transformation_
 The previous transformation matrix estimated by the registration method (used internally).
std::string reg_name_
 The registration method name.
PointCloudTargetConstPtr target_
 The input point cloud dataset target.
Eigen::Matrix4f transformation_
 The transformation matrix estimated by the registration method.
double transformation_epsilon_
 The maximum difference between two consecutive transformations in order to consider convergence (user defined).
KdTreePtr tree_
 A pointer to the spatial search object.

Private Member Functions

virtual void computeTransformation (PointCloudSource &output)=0
 Abstract transformation computation method.

Private Attributes

int k_
 The number of K nearest neighbors to use for each point.

Detailed Description

template<typename PointSource, typename PointTarget>
class pcl::RegistrationCorrespondencesCheck< PointSource, PointTarget >

Registration represents the base registration class. All 3D registration methods should inherit from this class.

Definition at line 57 of file registration_correspondences_check.h.


Member Typedef Documentation

template<typename PointSource, typename PointTarget>
typedef pcl::KdTree<PointTarget> pcl::RegistrationCorrespondencesCheck< PointSource, PointTarget >::KdTree

Definition at line 66 of file registration_correspondences_check.h.

template<typename PointSource, typename PointTarget>
typedef pcl::KdTree<PointTarget>::Ptr pcl::RegistrationCorrespondencesCheck< PointSource, PointTarget >::KdTreePtr

Definition at line 67 of file registration_correspondences_check.h.

template<typename PointSource, typename PointTarget>
typedef pcl::PointCloud<PointSource> pcl::RegistrationCorrespondencesCheck< PointSource, PointTarget >::PointCloudSource
template<typename PointSource, typename PointTarget>
typedef PointCloudSource::ConstPtr pcl::RegistrationCorrespondencesCheck< PointSource, PointTarget >::PointCloudSourceConstPtr
template<typename PointSource, typename PointTarget>
typedef PointCloudSource::Ptr pcl::RegistrationCorrespondencesCheck< PointSource, PointTarget >::PointCloudSourcePtr
template<typename PointSource, typename PointTarget>
typedef pcl::PointCloud<PointTarget> pcl::RegistrationCorrespondencesCheck< PointSource, PointTarget >::PointCloudTarget
template<typename PointSource, typename PointTarget>
typedef PointCloudTarget::ConstPtr pcl::RegistrationCorrespondencesCheck< PointSource, PointTarget >::PointCloudTargetConstPtr

Definition at line 75 of file registration_correspondences_check.h.

template<typename PointSource, typename PointTarget>
typedef PointCloudTarget::Ptr pcl::RegistrationCorrespondencesCheck< PointSource, PointTarget >::PointCloudTargetPtr

Definition at line 74 of file registration_correspondences_check.h.


Constructor & Destructor Documentation

template<typename PointSource, typename PointTarget>
pcl::RegistrationCorrespondencesCheck< PointSource, PointTarget >::RegistrationCorrespondencesCheck ( ) [inline]

Empty constructor.

Definition at line 79 of file registration_correspondences_check.h.

template<typename PointSource, typename PointTarget>
virtual pcl::RegistrationCorrespondencesCheck< PointSource, PointTarget >::~RegistrationCorrespondencesCheck ( ) [inline, virtual]

Empty destructor.

Definition at line 91 of file registration_correspondences_check.h.


Member Function Documentation

template<typename PointSource , typename PointTarget >
void pcl::RegistrationCorrespondencesCheck< PointSource, PointTarget >::align ( PointCloudSource output) [inline]

Call the registration algorithm which estimates the transformation and returns the transformed source (input) as output.

Parameters:
outputthe resultant input transfomed point cloud dataset

Definition at line 100 of file registration_correspondences_check.hpp.

template<typename PointSource, typename PointTarget>
virtual void pcl::RegistrationCorrespondencesCheck< PointSource, PointTarget >::computeTransformation ( PointCloudSource output) [private, pure virtual]

Abstract transformation computation method.

Implemented in pcl::IterativeClosestPointCorrespondencesCheck< PointSource, PointTarget >.

template<typename PointSource, typename PointTarget>
const std::string& pcl::RegistrationCorrespondencesCheck< PointSource, PointTarget >::getClassName ( ) const [inline, protected]

Abstract class get name method.

Definition at line 229 of file registration_correspondences_check.h.

template<typename PointSource, typename PointTarget>
Eigen::Matrix4f pcl::RegistrationCorrespondencesCheck< PointSource, PointTarget >::getFinalTransformation ( ) [inline]

Get the final transformation matrix estimated by the registration method.

Definition at line 106 of file registration_correspondences_check.h.

template<typename PointSource , typename PointTarget >
double pcl::RegistrationCorrespondencesCheck< PointSource, PointTarget >::getFitnessScore ( double  max_range = std::numeric_limits<double>::max ()) [inline]

Obtain the fitness score (e.g., sum of squared distances from the source to the target).

Parameters:
max_rangemaximum allowable distance between a point and its correspondent neighbor in the target (default: <double>max)

Definition at line 56 of file registration_correspondences_check.hpp.

template<typename PointSource, typename PointTarget>
PointCloudTargetConstPtr const pcl::RegistrationCorrespondencesCheck< PointSource, PointTarget >::getInputTarget ( ) [inline]

Get a pointer to the input point cloud dataset target target.

Definition at line 102 of file registration_correspondences_check.h.

template<typename PointSource, typename PointTarget>
Eigen::Matrix4f pcl::RegistrationCorrespondencesCheck< PointSource, PointTarget >::getLastIncrementalTransformation ( ) [inline]

Get the last incremental transformation matrix estimated by the registration method.

Definition at line 110 of file registration_correspondences_check.h.

template<typename PointSource, typename PointTarget>
double pcl::RegistrationCorrespondencesCheck< PointSource, PointTarget >::getMaxCorrespondenceDistance ( ) [inline]

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

Definition at line 134 of file registration_correspondences_check.h.

template<typename PointSource, typename PointTarget>
int pcl::RegistrationCorrespondencesCheck< PointSource, PointTarget >::getMaximumIterations ( ) [inline]

Get the maximum number of iterations the internal optimization should run for, as set by the user.

Definition at line 120 of file registration_correspondences_check.h.

template<typename PointSource, typename PointTarget>
double pcl::RegistrationCorrespondencesCheck< PointSource, PointTarget >::getTransformationEpsilon ( ) [inline]

Get the transformation epsilon (maximum allowable difference between two consecutive transformations) as set by the user.

Definition at line 148 of file registration_correspondences_check.h.

template<typename PointSource, typename PointTarget>
bool pcl::RegistrationCorrespondencesCheck< PointSource, PointTarget >::searchForNeighbors ( const PointCloudSource cloud,
int  index,
double  radius,
int  max_nn,
std::vector< int > &  indices,
std::vector< float > &  distances 
) [inline, protected]

Search for neigbors of a given point based on radius search.

Parameters:
cloudthe point cloud dataset to use for neighbor search
indexthe index of the query point
radiusof the radiusSearch
maximumnumber of nearest neigbors
indicesthe resultant vector of indices representing the neighbors
distancesthe resultant distances from the query point to the neighbors

Definition at line 222 of file registration_correspondences_check.h.

template<typename PointSource , typename PointTarget >
void pcl::RegistrationCorrespondencesCheck< PointSource, PointTarget >::setInputTarget ( const PointCloudTargetConstPtr cloud) [inline, virtual]

Provide a pointer to the input target target (e.g., the point cloud that we want to align the input source to)

Provide a pointer to the input model (e.g., the point cloud that we want to align the input source to)

Parameters:
cloudthe input point cloud target
cloudthe input point cloud model

Definition at line 40 of file registration_correspondences_check.hpp.

template<typename PointSource, typename PointTarget>
void pcl::RegistrationCorrespondencesCheck< PointSource, PointTarget >::setMaxCorrespondenceDistance ( double  distance_threshold) [inline]

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

Parameters:
distance_thresholdthe maximum distance threshold between a point and its nearest neighbor correspondent in order to be considered in the alignment process

Definition at line 128 of file registration_correspondences_check.h.

template<typename PointSource, typename PointTarget>
void pcl::RegistrationCorrespondencesCheck< PointSource, PointTarget >::setMaximumIterations ( int  nr_iterations) [inline]

Set the maximum number of iterations the internal optimization should run for.

Parameters:
nr_iterationsthe maximum number of iterations the internal optimization should run for

Definition at line 116 of file registration_correspondences_check.h.

template<typename PointSource, typename PointTarget>
void pcl::RegistrationCorrespondencesCheck< PointSource, PointTarget >::setPointRepresentation ( const typename KdTree::PointRepresentationConstPtr point_representation) [inline]

Provide a boost shared pointer to the PointRepresentation to be used when comparing points.

Parameters:
point_representationthe PointRepresentation to be used by the k-D tree

Definition at line 156 of file registration_correspondences_check.h.

template<typename PointSource, typename PointTarget>
void pcl::RegistrationCorrespondencesCheck< PointSource, PointTarget >::setTransformationEpsilon ( double  epsilon) [inline]

Set the transformation epsilon (maximum allowable difference between two consecutive transformations) in order for an optimization to be considered as having converged to the final solution.

Parameters:
epsilonthe transformation epsilon in order for an optimization to be considered as having converged to the final solution.

Definition at line 142 of file registration_correspondences_check.h.


Member Data Documentation

template<typename PointSource, typename PointTarget>
bool pcl::RegistrationCorrespondencesCheck< PointSource, PointTarget >::converged_ [protected]

Holds internal convergence state, given user parameters.

Definition at line 207 of file registration_correspondences_check.h.

template<typename PointSource, typename PointTarget>
double pcl::RegistrationCorrespondencesCheck< PointSource, PointTarget >::corr_dist_threshold_ [protected]

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 alignement process.

Definition at line 204 of file registration_correspondences_check.h.

template<typename PointSource, typename PointTarget>
Eigen::Matrix4f pcl::RegistrationCorrespondencesCheck< PointSource, PointTarget >::final_transformation_ [protected]

The final transformation matrix estimated by the registration method after N iterations.

Definition at line 190 of file registration_correspondences_check.h.

template<typename PointSource, typename PointTarget>
int pcl::RegistrationCorrespondencesCheck< PointSource, PointTarget >::k_ [private]

The number of K nearest neighbors to use for each point.

Definition at line 237 of file registration_correspondences_check.h.

template<typename PointSource, typename PointTarget>
int pcl::RegistrationCorrespondencesCheck< PointSource, PointTarget >::max_iterations_ [protected]

The maximum number of iterations the internal optimization should run for.

Definition at line 184 of file registration_correspondences_check.h.

template<typename PointSource, typename PointTarget>
int pcl::RegistrationCorrespondencesCheck< PointSource, PointTarget >::min_number_correspondences_ [protected]

The minimum number of correspondences that the algorithm needs before attempting to estimate the transformation.

Definition at line 210 of file registration_correspondences_check.h.

template<typename PointSource, typename PointTarget>
int pcl::RegistrationCorrespondencesCheck< PointSource, PointTarget >::nr_iterations_ [protected]

The number of iterations the internal optimization ran for (used internally).

Definition at line 181 of file registration_correspondences_check.h.

template<typename PointSource, typename PointTarget>
Eigen::Matrix4f pcl::RegistrationCorrespondencesCheck< PointSource, PointTarget >::previous_transformation_ [protected]

The previous transformation matrix estimated by the registration method (used internally).

Definition at line 196 of file registration_correspondences_check.h.

template<typename PointSource, typename PointTarget>
std::string pcl::RegistrationCorrespondencesCheck< PointSource, PointTarget >::reg_name_ [protected]

The registration method name.

Definition at line 175 of file registration_correspondences_check.h.

template<typename PointSource, typename PointTarget>
PointCloudTargetConstPtr pcl::RegistrationCorrespondencesCheck< PointSource, PointTarget >::target_ [protected]

The input point cloud dataset target.

Definition at line 187 of file registration_correspondences_check.h.

template<typename PointSource, typename PointTarget>
Eigen::Matrix4f pcl::RegistrationCorrespondencesCheck< PointSource, PointTarget >::transformation_ [protected]

The transformation matrix estimated by the registration method.

Definition at line 193 of file registration_correspondences_check.h.

template<typename PointSource, typename PointTarget>
double pcl::RegistrationCorrespondencesCheck< PointSource, PointTarget >::transformation_epsilon_ [protected]

The maximum difference between two consecutive transformations in order to consider convergence (user defined).

Definition at line 199 of file registration_correspondences_check.h.

template<typename PointSource, typename PointTarget>
KdTreePtr pcl::RegistrationCorrespondencesCheck< PointSource, PointTarget >::tree_ [protected]

A pointer to the spatial search object.

Definition at line 178 of file registration_correspondences_check.h.


The documentation for this class was generated from the following files:
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Properties Friends Defines


pointcloud_registration
Author(s): Hozefa Indorewala
autogenerated on Sun Oct 6 2013 11:55:58