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

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

#include <transformation_validation_euclidean.h>

List of all members.

Classes

class  MyPointRepresentation
 Internal point representation uses only 3D coordinates for L2. More...

Public Types

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

Public Member Functions

double getMaxRange ()
 Get the maximum allowable distance between a point and its correspondence, as set by the user.
double getThreshold ()
 Get the threshold for which a specific transformation is valid.
virtual bool isValid (const PointCloudSourceConstPtr &cloud_src, const PointCloudTargetConstPtr &cloud_tgt, const Matrix4 &transformation_matrix) const
 Check if the score is valid for a specific transformation.
virtual bool operator() (const double &score1, const double &score2) const
 Comparator function for deciding which score is better after running the validation on multiple transforms.
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.
void setSearchMethodTarget (const KdTreePtr &tree, bool force_no_recompute=false)
 Provide a pointer to the search object used to find correspondences in the target cloud.
void setThreshold (double threshold)
 Set a threshold for which a specific transformation is considered valid.
 TransformationValidationEuclidean ()
 Constructor. Sets the max_range parameter to double::max, threshold_ to NaN and initializes the internal search tree to a FLANN kd-tree.
double validateTransformation (const PointCloudSourceConstPtr &cloud_src, const PointCloudTargetConstPtr &cloud_tgt, const Matrix4 &transformation_matrix) const
 Validate the given transformation with respect to the input cloud data, and return a score.
virtual ~TransformationValidationEuclidean ()

Protected Attributes

bool force_no_recompute_
 A flag which, if set, means the tree operating on the target cloud will never be recomputed.
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.
double threshold_
 The threshold for which a specific transformation is valid. Set to NaN by default, as we must require the user to set it.
KdTreePtr tree_
 A pointer to the spatial search object.

Detailed Description

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

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);
Note:
The class is templated on the source and target point types as well as on the output scalar of the transformation matrix (i.e., float or double). Default: float.
Author:
Radu B. Rusu

Definition at line 74 of file transformation_validation_euclidean.h.


Member Typedef Documentation

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

Definition at line 80 of file transformation_validation_euclidean.h.

template<typename PointSource , typename PointTarget , typename Scalar = float>
typedef pcl::search::KdTree<PointTarget> pcl::registration::TransformationValidationEuclidean< PointSource, PointTarget, Scalar >::KdTree

Definition at line 82 of file transformation_validation_euclidean.h.

template<typename PointSource , typename PointTarget , typename Scalar = float>
typedef pcl::search::KdTree<PointTarget>::Ptr pcl::registration::TransformationValidationEuclidean< PointSource, PointTarget, Scalar >::KdTreePtr

Definition at line 83 of file transformation_validation_euclidean.h.

template<typename PointSource , typename PointTarget , typename Scalar = float>
typedef TransformationValidation<PointSource, PointTarget, Scalar>::Matrix4 pcl::registration::TransformationValidationEuclidean< PointSource, PointTarget, Scalar >::Matrix4

Definition at line 77 of file transformation_validation_euclidean.h.

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

Definition at line 87 of file transformation_validation_euclidean.h.

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

Definition at line 88 of file transformation_validation_euclidean.h.

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

Definition at line 85 of file transformation_validation_euclidean.h.

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

Definition at line 79 of file transformation_validation_euclidean.h.


Constructor & Destructor Documentation

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

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

Definition at line 94 of file transformation_validation_euclidean.h.

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

Definition at line 102 of file transformation_validation_euclidean.h.


Member Function Documentation

template<typename PointSource , typename PointTarget , typename Scalar = float>
double pcl::registration::TransformationValidationEuclidean< PointSource, PointTarget, Scalar >::getMaxRange ( ) [inline]

Get the maximum allowable distance between a point and its correspondence, as set by the user.

Definition at line 118 of file transformation_validation_euclidean.h.

template<typename PointSource , typename PointTarget , typename Scalar = float>
double pcl::registration::TransformationValidationEuclidean< PointSource, PointTarget, Scalar >::getThreshold ( ) [inline]

Get the threshold for which a specific transformation is valid.

Definition at line 158 of file transformation_validation_euclidean.h.

template<typename PointSource , typename PointTarget , typename Scalar = float>
virtual bool pcl::registration::TransformationValidationEuclidean< PointSource, PointTarget, Scalar >::isValid ( const PointCloudSourceConstPtr cloud_src,
const PointCloudTargetConstPtr cloud_tgt,
const Matrix4 transformation_matrix 
) const [inline, virtual]

Check if the score is valid for a specific transformation.

Parameters:
[in]cloud_srcthe source point cloud dataset
[in]cloud_tgtthe target point cloud dataset
[out]transformation_matrixthe transformation matrix
Returns:
true if the transformation is valid, false otherwise.

Definition at line 201 of file transformation_validation_euclidean.h.

template<typename PointSource , typename PointTarget , typename Scalar = float>
virtual bool pcl::registration::TransformationValidationEuclidean< PointSource, PointTarget, Scalar >::operator() ( const double &  score1,
const double &  score2 
) const [inline, virtual]

Comparator function for deciding which score is better after running the validation on multiple transforms.

Parameters:
[in]score1the first value
[in]score2the second value
Returns:
true if score1 is better than score2

Definition at line 187 of file transformation_validation_euclidean.h.

template<typename PointSource , typename PointTarget , typename Scalar = float>
void pcl::registration::TransformationValidationEuclidean< PointSource, PointTarget, Scalar >::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 109 of file transformation_validation_euclidean.h.

template<typename PointSource , typename PointTarget , typename Scalar = float>
void pcl::registration::TransformationValidationEuclidean< PointSource, PointTarget, Scalar >::setSearchMethodTarget ( const KdTreePtr 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 132 of file transformation_validation_euclidean.h.

template<typename PointSource , typename PointTarget , typename Scalar = float>
void pcl::registration::TransformationValidationEuclidean< PointSource, PointTarget, Scalar >::setThreshold ( double  threshold) [inline]

Set a threshold for which a specific transformation is considered valid.

Note:
Since we're using MSE (Mean Squared Error) as a metric, the threshold represents the mean Euclidean distance threshold over all nearest neighbors up to max_range.
Parameters:
[in]thresholdthe threshold for which a transformation is vali

Definition at line 151 of file transformation_validation_euclidean.h.

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

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 45 of file transformation_validation_euclidean.hpp.


Member Data Documentation

template<typename PointSource , typename PointTarget , typename Scalar = float>
bool pcl::registration::TransformationValidationEuclidean< PointSource, PointTarget, Scalar >::force_no_recompute_ [protected]

A flag which, if set, means the tree operating on the target cloud will never be recomputed.

Definition at line 231 of file transformation_validation_euclidean.h.

template<typename PointSource , typename PointTarget , typename Scalar = float>
double pcl::registration::TransformationValidationEuclidean< PointSource, PointTarget, Scalar >::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 219 of file transformation_validation_euclidean.h.

template<typename PointSource , typename PointTarget , typename Scalar = float>
double pcl::registration::TransformationValidationEuclidean< PointSource, PointTarget, Scalar >::threshold_ [protected]

The threshold for which a specific transformation is valid. Set to NaN by default, as we must require the user to set it.

Definition at line 224 of file transformation_validation_euclidean.h.

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

A pointer to the spatial search object.

Definition at line 227 of file transformation_validation_euclidean.h.


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


pcl
Author(s): Open Perception
autogenerated on Wed Aug 26 2015 15:46:56