Public Types | Public Member Functions | Protected Attributes
pcl::registration::TransformationValidationEuclidean< PointSource, PointTarget > Class Template Reference

TransformationValidationEuclidean computes an L2SQR norm between a source and target dataset. More...

#include <transformation_validation_euclidean.h>

List of all members.

Public Types

typedef boost::shared_ptr
< const
TransformationValidation
< PointSource, PointTarget > > 
ConstPtr
typedef pcl::KdTree< PointTarget > KdTree
typedef pcl::KdTree
< PointTarget >::Ptr 
KdTreePtr
typedef
TransformationValidation
< PointSource, PointTarget >
::PointCloudSourceConstPtr 
PointCloudSourceConstPtr
typedef
TransformationValidation
< PointSource, PointTarget >
::PointCloudTargetConstPtr 
PointCloudTargetConstPtr
typedef
KdTree::PointRepresentationConstPtr 
PointRepresentationConstPtr
typedef boost::shared_ptr
< TransformationValidation
< PointSource, PointTarget > > 
Ptr

Public Member Functions

void setMaxRange (double max_range)
 Set the maximum allowable distance between a point and its correspondence in the target in order for a correspondence to be considered valid. Default: double::max.
 TransformationValidationEuclidean ()
 Constructor. Sets the max_range parameter to double::max, and initializes the internal search tree to a FLANN kd-tree.
double validateTransformation (const PointCloudSourceConstPtr &cloud_src, const PointCloudTargetConstPtr &cloud_tgt, const Eigen::Matrix4f &transformation_matrix)
 Validate the given transformation with respect to the input cloud data, and return a score.
virtual ~TransformationValidationEuclidean ()

Protected Attributes

double max_range_
 The maximum allowable distance between a point and its correspondence in the target in order for a correspondence to be considered valid. Default: double::max.
KdTreePtr tree_
 A pointer to the spatial search object.

Detailed Description

template<typename PointSource, typename PointTarget>
class pcl::registration::TransformationValidationEuclidean< PointSource, PointTarget >

TransformationValidationEuclidean computes an L2SQR norm between a source and target dataset.

To prevent points with bad correspondences to contribute to the overall score, the class also accepts a maximum_range parameter given via setMaxRange that is used as a cutoff value for nearest neighbor distance comparisons.

The output score is normalized with respect to the number of valid correspondences found.

Usage example:

 pcl::TransformationValidationEuclidean<pcl::PointXYZ, pcl::PointXYZ> tve;
 tve.setMaxRange (0.01);  // 1cm
 double score = tve.validateTransformation (source, target, transformation);
Author:
Radu B. Rusu

Definition at line 71 of file transformation_validation_euclidean.h.


Member Typedef Documentation

template<typename PointSource , typename PointTarget >
typedef boost::shared_ptr<const TransformationValidation<PointSource, PointTarget> > pcl::registration::TransformationValidationEuclidean< PointSource, PointTarget >::ConstPtr

Definition at line 75 of file transformation_validation_euclidean.h.

template<typename PointSource , typename PointTarget >
typedef pcl::KdTree<PointTarget> pcl::registration::TransformationValidationEuclidean< PointSource, PointTarget >::KdTree

Definition at line 77 of file transformation_validation_euclidean.h.

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

Definition at line 78 of file transformation_validation_euclidean.h.

template<typename PointSource , typename PointTarget >
typedef TransformationValidation<PointSource, PointTarget>::PointCloudSourceConstPtr pcl::registration::TransformationValidationEuclidean< PointSource, PointTarget >::PointCloudSourceConstPtr

Definition at line 82 of file transformation_validation_euclidean.h.

template<typename PointSource , typename PointTarget >
typedef TransformationValidation<PointSource, PointTarget>::PointCloudTargetConstPtr pcl::registration::TransformationValidationEuclidean< PointSource, PointTarget >::PointCloudTargetConstPtr

Definition at line 83 of file transformation_validation_euclidean.h.

template<typename PointSource , typename PointTarget >
typedef KdTree::PointRepresentationConstPtr pcl::registration::TransformationValidationEuclidean< PointSource, PointTarget >::PointRepresentationConstPtr

Definition at line 80 of file transformation_validation_euclidean.h.

template<typename PointSource , typename PointTarget >
typedef boost::shared_ptr<TransformationValidation<PointSource, PointTarget> > pcl::registration::TransformationValidationEuclidean< PointSource, PointTarget >::Ptr

Definition at line 74 of file transformation_validation_euclidean.h.


Constructor & Destructor Documentation

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

Constructor. Sets the max_range parameter to double::max, and initializes the internal search tree to a FLANN kd-tree.

Definition at line 89 of file transformation_validation_euclidean.h.

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

Definition at line 95 of file transformation_validation_euclidean.h.


Member Function Documentation

template<typename PointSource , typename PointTarget >
void pcl::registration::TransformationValidationEuclidean< PointSource, PointTarget >::setMaxRange ( double  max_range) [inline]

Set the maximum allowable distance between a point and its correspondence in the target in order for a correspondence to be considered valid. Default: double::max.

Parameters:
[in]max_rangethe new maximum allowable distance

Definition at line 102 of file transformation_validation_euclidean.h.

template<typename PointSource , typename PointTarget >
double pcl::registration::TransformationValidationEuclidean< PointSource, PointTarget >::validateTransformation ( const PointCloudSourceConstPtr cloud_src,
const PointCloudTargetConstPtr cloud_tgt,
const Eigen::Matrix4f &  transformation_matrix 
)

Validate the given transformation with respect to the input cloud data, and return a score.

Parameters:
[in]cloud_srcthe source point cloud dataset
[in]cloud_tgtthe target point cloud dataset
[out]transformation_matrixthe resultant transformation matrix
Returns:
the score or confidence measure for the given transformation_matrix with respect to the input data

Definition at line 46 of file transformation_validation_euclidean.hpp.


Member Data Documentation

template<typename PointSource , typename PointTarget >
double pcl::registration::TransformationValidationEuclidean< PointSource, PointTarget >::max_range_ [protected]

The maximum allowable distance between a point and its correspondence in the target in order for a correspondence to be considered valid. Default: double::max.

Definition at line 126 of file transformation_validation_euclidean.h.

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

A pointer to the spatial search object.

Definition at line 129 of file transformation_validation_euclidean.h.


The documentation for this class was generated from the following files:


pcl
Author(s): Open Perception
autogenerated on Mon Oct 6 2014 03:20:23