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

TransformationEstimationPointToPlaneLLS implements a Linear Least Squares (LLS) approximation for minimizing the point-to-plane distance between two clouds of corresponding points with normals. More...

#include <transformation_estimation_point_to_plane_lls.h>

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

List of all members.

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 SVD.
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 SVD.
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 SVD.
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 SVD.
 TransformationEstimationPointToPlaneLLS ()
virtual ~TransformationEstimationPointToPlaneLLS ()

Protected Member Functions

void constructTransformationMatrix (const float &alpha, const float &beta, const float &gamma, const float &tx, const float &ty, const float &tz, Eigen::Matrix4f &transformation_matrix)
 Construct a 4 by 4 tranformation matrix from the provided rotation and translation.

Detailed Description

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

TransformationEstimationPointToPlaneLLS implements a Linear Least Squares (LLS) approximation for minimizing the point-to-plane distance between two clouds of corresponding points with normals.

For additional details, see "Linear Least-Squares Optimization for Point-to-Plane ICP Surface Registration", Kok-Lim Low, 2004

Author:
Michael Dixon

Definition at line 59 of file transformation_estimation_point_to_plane_lls.h.


Constructor & Destructor Documentation

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

Member Function Documentation

template<typename PointSource , typename PointTarget >
void pcl::registration::TransformationEstimationPointToPlaneLLS< PointSource, PointTarget >::constructTransformationMatrix ( const float &  alpha,
const float &  beta,
const float &  gamma,
const float &  tx,
const float &  ty,
const float &  tz,
Eigen::Matrix4f &  transformation_matrix 
) [inline, protected]

Construct a 4 by 4 tranformation matrix from the provided rotation and translation.

Parameters:
[in]alphathe rotation about the x-axis
[in]betathe rotation about the y-axis
[in]gammathe rotation about the z-axis
[in]txthe x translation
[in]tythe y translation
[in]tzthe z translation
[out]transformationthe resultant transformation matrix

Definition at line 222 of file transformation_estimation_point_to_plane_lls.hpp.

template<typename PointSource , typename PointTarget >
void pcl::registration::TransformationEstimationPointToPlaneLLS< 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 SVD.

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 44 of file transformation_estimation_point_to_plane_lls.hpp.

template<typename PointSource , typename PointTarget >
void pcl::registration::TransformationEstimationPointToPlaneLLS< 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 SVD.

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 89 of file transformation_estimation_point_to_plane_lls.hpp.

template<typename PointSource , typename PointTarget >
void pcl::registration::TransformationEstimationPointToPlaneLLS< 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 SVD.

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 135 of file transformation_estimation_point_to_plane_lls.hpp.

template<typename PointSource , typename PointTarget >
void pcl::registration::TransformationEstimationPointToPlaneLLS< 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 SVD.

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 181 of file transformation_estimation_point_to_plane_lls.hpp.


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