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

#include <transformation_estimation_lm.h>

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

List of all members.

Classes

struct  Functor
struct  OptimizationFunctor
struct  OptimizationFunctorWithIndices

Public Member Functions

void estimateRigidTransformation (const pcl::PointCloud< PointSource > &cloud_src, const pcl::PointCloud< PointTarget > &cloud_tgt, Eigen::Matrix4f &transformation_matrix)
 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, Eigen::Matrix4f &transformation_matrix)
 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, Eigen::Matrix4f &transformation_matrix)
 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, Eigen::Matrix4f &transformation_matrix)
 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 > > &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 double computeDistance (const PointSource &p_src, const PointTarget &p_tgt)
 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
< WarpPointRigid< PointSource,
PointTarget > > 
warp_point_
 The parameterized function used to warp the source to the target.
std::vector< double > weights_
 The vector of residual weights. Used internall in the LM loop.

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>
class pcl::registration::TransformationEstimationLM< PointSource, PointTarget >

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

Author:
Radu B. Rusu

Definition at line 57 of file transformation_estimation_lm.h.


Member Typedef Documentation

template<typename PointSource, typename PointTarget>
typedef pcl::PointCloud<PointSource> pcl::registration::TransformationEstimationLM< PointSource, PointTarget >::PointCloudSource [private]
template<typename PointSource, typename PointTarget>
typedef PointCloudSource::ConstPtr pcl::registration::TransformationEstimationLM< PointSource, PointTarget >::PointCloudSourceConstPtr [private]
template<typename PointSource, typename PointTarget>
typedef PointCloudSource::Ptr pcl::registration::TransformationEstimationLM< PointSource, PointTarget >::PointCloudSourcePtr [private]
template<typename PointSource, typename PointTarget>
typedef pcl::PointCloud<PointTarget> pcl::registration::TransformationEstimationLM< PointSource, PointTarget >::PointCloudTarget [private]
template<typename PointSource, typename PointTarget>
typedef PointIndices::ConstPtr pcl::registration::TransformationEstimationLM< PointSource, PointTarget >::PointIndicesConstPtr [private]
template<typename PointSource, typename PointTarget>
typedef PointIndices::Ptr pcl::registration::TransformationEstimationLM< PointSource, PointTarget >::PointIndicesPtr [private]

Constructor & Destructor Documentation

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

Constructor.

Definition at line 70 of file transformation_estimation_lm.h.

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

Copy constructor.

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

Definition at line 77 of file transformation_estimation_lm.h.

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

Destructor.

Definition at line 101 of file transformation_estimation_lm.h.


Member Function Documentation

template<typename PointSource, typename PointTarget>
virtual double pcl::registration::TransformationEstimationLM< PointSource, PointTarget >::computeDistance ( const PointSource &  p_src,
const PointTarget &  p_tgt 
) [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 >.

Definition at line 175 of file transformation_estimation_lm.h.

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

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

Implements pcl::registration::TransformationEstimation< PointSource, PointTarget >.

Definition at line 48 of file transformation_estimation_lm.hpp.

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

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

Implements pcl::registration::TransformationEstimation< PointSource, PointTarget >.

Definition at line 106 of file transformation_estimation_lm.hpp.

template<typename PointSource , typename PointTarget >
void pcl::registration::TransformationEstimationLM< PointSource, PointTarget >::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,
Eigen::Matrix4f &  transformation_matrix 
) [inline, virtual]

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

Implements pcl::registration::TransformationEstimation< PointSource, PointTarget >.

Definition at line 132 of file transformation_estimation_lm.hpp.

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

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

Implements pcl::registration::TransformationEstimation< PointSource, PointTarget >.

Definition at line 192 of file transformation_estimation_lm.hpp.

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

Copy operator.

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

Definition at line 90 of file transformation_estimation_lm.h.

template<typename PointSource, typename PointTarget>
void pcl::registration::TransformationEstimationLM< PointSource, PointTarget >::setWarpFunction ( const boost::shared_ptr< WarpPointRigid< PointSource, PointTarget > > &  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

Definition at line 160 of file transformation_estimation_lm.h.


Member Data Documentation

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

Temporary pointer to the source dataset indices.

Definition at line 192 of file transformation_estimation_lm.h.

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

Temporary pointer to the target dataset indices.

Definition at line 195 of file transformation_estimation_lm.h.

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

Temporary pointer to the source dataset.

Definition at line 186 of file transformation_estimation_lm.h.

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

Temporary pointer to the target dataset.

Definition at line 189 of file transformation_estimation_lm.h.

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

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

Definition at line 198 of file transformation_estimation_lm.h.

template<typename PointSource, typename PointTarget>
std::vector<double> pcl::registration::TransformationEstimationLM< PointSource, PointTarget >::weights_ [protected]

The vector of residual weights. Used internall in the LM loop.

Definition at line 183 of file transformation_estimation_lm.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