Classes | Public Types | Public Member Functions | Protected Member Functions | Protected Attributes | Private Types
pcl::registration::TransformationEstimationLM< PointSource, PointTarget, MatScalar > Class Template Reference

#include <transformation_estimation_lm.h>

Inheritance diagram for pcl::registration::TransformationEstimationLM< PointSource, PointTarget, MatScalar >:
Inheritance graph
[legend]

List of all members.

Classes

struct  Functor
struct  OptimizationFunctor
struct  OptimizationFunctorWithIndices

Public Types

typedef boost::shared_ptr
< const
TransformationEstimationLM
< PointSource, PointTarget,
MatScalar > > 
ConstPtr
typedef
TransformationEstimation
< PointSource, PointTarget,
MatScalar >::Matrix4 
Matrix4
typedef boost::shared_ptr
< TransformationEstimationLM
< PointSource, PointTarget,
MatScalar > > 
Ptr
typedef Eigen::Matrix
< MatScalar, 4, 1 > 
Vector4
typedef Eigen::Matrix
< MatScalar, Eigen::Dynamic, 1 > 
VectorX

Public Member Functions

void estimateRigidTransformation (const pcl::PointCloud< PointSource > &cloud_src, const pcl::PointCloud< PointTarget > &cloud_tgt, Matrix4 &transformation_matrix) const
 Estimate a rigid rotation transformation between a source and a target point cloud using LM.
void estimateRigidTransformation (const pcl::PointCloud< PointSource > &cloud_src, const std::vector< int > &indices_src, const pcl::PointCloud< PointTarget > &cloud_tgt, Matrix4 &transformation_matrix) const
 Estimate a rigid rotation transformation between a source and a target point cloud using LM.
void estimateRigidTransformation (const pcl::PointCloud< PointSource > &cloud_src, const std::vector< int > &indices_src, const pcl::PointCloud< PointTarget > &cloud_tgt, const std::vector< int > &indices_tgt, Matrix4 &transformation_matrix) const
 Estimate a rigid rotation transformation between a source and a target point cloud using LM.
void estimateRigidTransformation (const pcl::PointCloud< PointSource > &cloud_src, const pcl::PointCloud< PointTarget > &cloud_tgt, const pcl::Correspondences &correspondences, Matrix4 &transformation_matrix) const
 Estimate a rigid rotation transformation between a source and a target point cloud using LM.
TransformationEstimationLMoperator= (const TransformationEstimationLM &src)
 Copy operator.
void setWarpFunction (const boost::shared_ptr< WarpPointRigid< PointSource, PointTarget, MatScalar > > &warp_fcn)
 Set the function we use to warp points. Defaults to rigid 6D warp.
 TransformationEstimationLM ()
 Constructor.
 TransformationEstimationLM (const TransformationEstimationLM &src)
 Copy constructor.
virtual ~TransformationEstimationLM ()
 Destructor.

Protected Member Functions

virtual MatScalar computeDistance (const PointSource &p_src, const PointTarget &p_tgt) const
 Compute the distance between a source point and its corresponding target point.
virtual MatScalar computeDistance (const Vector4 &p_src, const PointTarget &p_tgt) const
 Compute the distance between a source point and its corresponding target point.

Protected Attributes

const std::vector< int > * tmp_idx_src_
 Temporary pointer to the source dataset indices.
const std::vector< int > * tmp_idx_tgt_
 Temporary pointer to the target dataset indices.
const PointCloudSourcetmp_src_
 Temporary pointer to the source dataset.
const PointCloudTargettmp_tgt_
 Temporary pointer to the target dataset.
boost::shared_ptr
< pcl::registration::WarpPointRigid
< PointSource, PointTarget,
MatScalar > > 
warp_point_
 The parameterized function used to warp the source to the target.

Private Types

typedef pcl::PointCloud
< PointSource > 
PointCloudSource
typedef PointCloudSource::ConstPtr PointCloudSourceConstPtr
typedef PointCloudSource::Ptr PointCloudSourcePtr
typedef pcl::PointCloud
< PointTarget > 
PointCloudTarget
typedef PointIndices::ConstPtr PointIndicesConstPtr
typedef PointIndices::Ptr PointIndicesPtr

Detailed Description

template<typename PointSource, typename PointTarget, typename MatScalar = float>
class pcl::registration::TransformationEstimationLM< PointSource, PointTarget, MatScalar >

TransformationEstimationLM implements Levenberg Marquardt-based estimation of the transformation aligning the given correspondences.

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 59 of file transformation_estimation_lm.h.


Member Typedef Documentation

template<typename PointSource, typename PointTarget, typename MatScalar = float>
typedef boost::shared_ptr<const TransformationEstimationLM<PointSource, PointTarget, MatScalar> > pcl::registration::TransformationEstimationLM< PointSource, PointTarget, MatScalar >::ConstPtr
template<typename PointSource, typename PointTarget, typename MatScalar = float>
typedef TransformationEstimation<PointSource, PointTarget, MatScalar>::Matrix4 pcl::registration::TransformationEstimationLM< PointSource, PointTarget, MatScalar >::Matrix4
template<typename PointSource, typename PointTarget, typename MatScalar = float>
typedef pcl::PointCloud<PointSource> pcl::registration::TransformationEstimationLM< PointSource, PointTarget, MatScalar >::PointCloudSource [private]
template<typename PointSource, typename PointTarget, typename MatScalar = float>
typedef PointCloudSource::ConstPtr pcl::registration::TransformationEstimationLM< PointSource, PointTarget, MatScalar >::PointCloudSourceConstPtr [private]
template<typename PointSource, typename PointTarget, typename MatScalar = float>
typedef PointCloudSource::Ptr pcl::registration::TransformationEstimationLM< PointSource, PointTarget, MatScalar >::PointCloudSourcePtr [private]
template<typename PointSource, typename PointTarget, typename MatScalar = float>
typedef pcl::PointCloud<PointTarget> pcl::registration::TransformationEstimationLM< PointSource, PointTarget, MatScalar >::PointCloudTarget [private]
template<typename PointSource, typename PointTarget, typename MatScalar = float>
typedef PointIndices::ConstPtr pcl::registration::TransformationEstimationLM< PointSource, PointTarget, MatScalar >::PointIndicesConstPtr [private]
template<typename PointSource, typename PointTarget, typename MatScalar = float>
typedef PointIndices::Ptr pcl::registration::TransformationEstimationLM< PointSource, PointTarget, MatScalar >::PointIndicesPtr [private]
template<typename PointSource, typename PointTarget, typename MatScalar = float>
typedef boost::shared_ptr<TransformationEstimationLM<PointSource, PointTarget, MatScalar> > pcl::registration::TransformationEstimationLM< PointSource, PointTarget, MatScalar >::Ptr
template<typename PointSource, typename PointTarget, typename MatScalar = float>
typedef Eigen::Matrix<MatScalar, 4, 1> pcl::registration::TransformationEstimationLM< PointSource, PointTarget, MatScalar >::Vector4
template<typename PointSource, typename PointTarget, typename MatScalar = float>
typedef Eigen::Matrix<MatScalar, Eigen::Dynamic, 1> pcl::registration::TransformationEstimationLM< PointSource, PointTarget, MatScalar >::VectorX

Constructor & Destructor Documentation

template<typename PointSource , typename PointTarget , typename MatScalar >
pcl::registration::TransformationEstimationLM< PointSource, PointTarget, MatScalar >::TransformationEstimationLM ( )

Constructor.

Definition at line 51 of file transformation_estimation_lm.hpp.

template<typename PointSource, typename PointTarget, typename MatScalar = float>
pcl::registration::TransformationEstimationLM< PointSource, PointTarget, MatScalar >::TransformationEstimationLM ( const TransformationEstimationLM< PointSource, PointTarget, MatScalar > &  src) [inline]

Copy constructor.

Parameters:
[in]srcthe TransformationEstimationLM object to copy into this

Definition at line 84 of file transformation_estimation_lm.h.

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

Destructor.

Definition at line 106 of file transformation_estimation_lm.h.


Member Function Documentation

template<typename PointSource, typename PointTarget, typename MatScalar = float>
virtual MatScalar pcl::registration::TransformationEstimationLM< PointSource, PointTarget, MatScalar >::computeDistance ( const PointSource &  p_src,
const PointTarget &  p_tgt 
) const [inline, protected, virtual]

Compute the distance between a source point and its corresponding target point.

Parameters:
[in]p_srcThe source point
[in]p_tgtThe target point
Returns:
The distance between p_src and p_tgt
Note:
Older versions of PCL used this method internally for calculating the optimization gradient. Since PCL 1.7, a switch has been made to the computeDistance method using Vector4 types instead. This method is only kept for API compatibility reasons.

Reimplemented in pcl::registration::TransformationEstimationPointToPlane< PointSource, PointTarget, Scalar >, and pcl::registration::TransformationEstimationPointToPlane< PointSource, PointTarget, MatScalar >.

Definition at line 182 of file transformation_estimation_lm.h.

template<typename PointSource, typename PointTarget, typename MatScalar = float>
virtual MatScalar pcl::registration::TransformationEstimationLM< PointSource, PointTarget, MatScalar >::computeDistance ( const Vector4 p_src,
const PointTarget &  p_tgt 
) const [inline, protected, virtual]

Compute the distance between a source point and its corresponding target point.

Parameters:
[in]p_srcThe source point
[in]p_tgtThe target point
Returns:
The distance between p_src and p_tgt
Note:
A different distance function can be defined by creating a subclass of TransformationEstimationLM and overriding this method. (See TransformationEstimationPointToPlane)

Reimplemented in pcl::registration::TransformationEstimationPointToPlane< PointSource, PointTarget, Scalar >, and pcl::registration::TransformationEstimationPointToPlane< PointSource, PointTarget, MatScalar >.

Definition at line 199 of file transformation_estimation_lm.h.

template<typename PointSource, typename PointTarget, typename MatScalar >
void pcl::registration::TransformationEstimationLM< PointSource, PointTarget, MatScalar >::estimateRigidTransformation ( const pcl::PointCloud< PointSource > &  cloud_src,
const pcl::PointCloud< PointTarget > &  cloud_tgt,
Matrix4 transformation_matrix 
) const [inline]

Estimate a rigid rotation transformation between a source and a target point cloud using LM.

Parameters:
[in]cloud_srcthe source point cloud dataset
[in]cloud_tgtthe target point cloud dataset
[out]transformation_matrixthe resultant transformation matrix

Reimplemented in pcl::registration::TransformationEstimationPointToPlaneWeighted< PointSource, PointTarget, MatScalar >.

Definition at line 62 of file transformation_estimation_lm.hpp.

template<typename PointSource, typename PointTarget, typename MatScalar >
void pcl::registration::TransformationEstimationLM< PointSource, PointTarget, MatScalar >::estimateRigidTransformation ( const pcl::PointCloud< PointSource > &  cloud_src,
const std::vector< int > &  indices_src,
const pcl::PointCloud< PointTarget > &  cloud_tgt,
Matrix4 transformation_matrix 
) const [inline]

Estimate a rigid rotation transformation between a source and a target point cloud using LM.

Parameters:
[in]cloud_srcthe source point cloud dataset
[in]indices_srcthe vector of indices describing the points of interest in cloud_src
[in]cloud_tgtthe target point cloud dataset
[out]transformation_matrixthe resultant transformation matrix

Reimplemented in pcl::registration::TransformationEstimationPointToPlaneWeighted< PointSource, PointTarget, MatScalar >.

Definition at line 116 of file transformation_estimation_lm.hpp.

template<typename PointSource, typename PointTarget, typename MatScalar >
void pcl::registration::TransformationEstimationLM< PointSource, PointTarget, MatScalar >::estimateRigidTransformation ( const pcl::PointCloud< PointSource > &  cloud_src,
const std::vector< int > &  indices_src,
const pcl::PointCloud< PointTarget > &  cloud_tgt,
const std::vector< int > &  indices_tgt,
Matrix4 transformation_matrix 
) const [inline]

Estimate a rigid rotation transformation between a source and a target point cloud using LM.

Parameters:
[in]cloud_srcthe source point cloud dataset
[in]indices_srcthe vector of indices describing the points of interest in cloud_src
[in]cloud_tgtthe target point cloud dataset
[in]indices_tgtthe vector of indices describing the correspondences of the interst points from indices_src
[out]transformation_matrixthe resultant transformation matrix

Reimplemented in pcl::registration::TransformationEstimationPointToPlaneWeighted< PointSource, PointTarget, MatScalar >.

Definition at line 142 of file transformation_estimation_lm.hpp.

template<typename PointSource, typename PointTarget, typename MatScalar >
void pcl::registration::TransformationEstimationLM< PointSource, PointTarget, MatScalar >::estimateRigidTransformation ( const pcl::PointCloud< PointSource > &  cloud_src,
const pcl::PointCloud< PointTarget > &  cloud_tgt,
const pcl::Correspondences correspondences,
Matrix4 transformation_matrix 
) const [inline]

Estimate a rigid rotation transformation between a source and a target point cloud using LM.

Parameters:
[in]cloud_srcthe source point cloud dataset
[in]cloud_tgtthe target point cloud dataset
[in]correspondencesthe vector of correspondences between source and target point cloud
[out]transformation_matrixthe resultant transformation matrix

Reimplemented in pcl::registration::TransformationEstimationPointToPlaneWeighted< PointSource, PointTarget, MatScalar >.

Definition at line 197 of file transformation_estimation_lm.hpp.

template<typename PointSource, typename PointTarget, typename MatScalar = float>
TransformationEstimationLM& pcl::registration::TransformationEstimationLM< PointSource, PointTarget, MatScalar >::operator= ( const TransformationEstimationLM< PointSource, PointTarget, MatScalar > &  src) [inline]

Copy operator.

Parameters:
[in]srcthe TransformationEstimationLM object to copy into this

Definition at line 96 of file transformation_estimation_lm.h.

template<typename PointSource, typename PointTarget, typename MatScalar = float>
void pcl::registration::TransformationEstimationLM< PointSource, PointTarget, MatScalar >::setWarpFunction ( const boost::shared_ptr< WarpPointRigid< PointSource, PointTarget, MatScalar > > &  warp_fcn) [inline]

Set the function we use to warp points. Defaults to rigid 6D warp.

Parameters:
[in]warp_fcna shared pointer to an object that warps points

Reimplemented in pcl::registration::TransformationEstimationPointToPlaneWeighted< PointSource, PointTarget, MatScalar >.

Definition at line 165 of file transformation_estimation_lm.h.


Member Data Documentation

template<typename PointSource, typename PointTarget, typename MatScalar = float>
const std::vector<int>* pcl::registration::TransformationEstimationLM< PointSource, PointTarget, MatScalar >::tmp_idx_src_ [mutable, protected]

Temporary pointer to the source dataset indices.

Reimplemented in pcl::registration::TransformationEstimationPointToPlaneWeighted< PointSource, PointTarget, MatScalar >.

Definition at line 212 of file transformation_estimation_lm.h.

template<typename PointSource, typename PointTarget, typename MatScalar = float>
const std::vector<int>* pcl::registration::TransformationEstimationLM< PointSource, PointTarget, MatScalar >::tmp_idx_tgt_ [mutable, protected]

Temporary pointer to the target dataset indices.

Reimplemented in pcl::registration::TransformationEstimationPointToPlaneWeighted< PointSource, PointTarget, MatScalar >.

Definition at line 215 of file transformation_estimation_lm.h.

template<typename PointSource, typename PointTarget, typename MatScalar = float>
const PointCloudSource* pcl::registration::TransformationEstimationLM< PointSource, PointTarget, MatScalar >::tmp_src_ [mutable, protected]

Temporary pointer to the source dataset.

Reimplemented in pcl::registration::TransformationEstimationPointToPlaneWeighted< PointSource, PointTarget, MatScalar >.

Definition at line 206 of file transformation_estimation_lm.h.

template<typename PointSource, typename PointTarget, typename MatScalar = float>
const PointCloudTarget* pcl::registration::TransformationEstimationLM< PointSource, PointTarget, MatScalar >::tmp_tgt_ [mutable, protected]

Temporary pointer to the target dataset.

Reimplemented in pcl::registration::TransformationEstimationPointToPlaneWeighted< PointSource, PointTarget, MatScalar >.

Definition at line 209 of file transformation_estimation_lm.h.

template<typename PointSource, typename PointTarget, typename MatScalar = float>
boost::shared_ptr<pcl::registration::WarpPointRigid<PointSource, PointTarget, MatScalar> > pcl::registration::TransformationEstimationLM< PointSource, PointTarget, MatScalar >::warp_point_ [protected]

The parameterized function used to warp the source to the target.

Reimplemented in pcl::registration::TransformationEstimationPointToPlaneWeighted< PointSource, PointTarget, MatScalar >.

Definition at line 218 of file transformation_estimation_lm.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:54