Public Types | Public Member Functions
pcl::registration::TransformationEstimation< PointSource, PointTarget, Scalar > Class Template Reference

TransformationEstimation represents the base class for methods for transformation estimation based on: More...

#include <transformation_estimation.h>

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

List of all members.

Public Types

typedef boost::shared_ptr
< const
TransformationEstimation
< PointSource, PointTarget,
Scalar > > 
ConstPtr
typedef Eigen::Matrix< Scalar, 4, 4 > Matrix4
typedef boost::shared_ptr
< TransformationEstimation
< PointSource, PointTarget,
Scalar > > 
Ptr

Public Member Functions

virtual void estimateRigidTransformation (const pcl::PointCloud< PointSource > &cloud_src, const pcl::PointCloud< PointTarget > &cloud_tgt, Matrix4 &transformation_matrix) const =0
 Estimate a rigid rotation transformation between a source and a target point cloud.
virtual void estimateRigidTransformation (const pcl::PointCloud< PointSource > &cloud_src, const std::vector< int > &indices_src, const pcl::PointCloud< PointTarget > &cloud_tgt, Matrix4 &transformation_matrix) const =0
 Estimate a rigid rotation transformation between a source and a target point cloud.
virtual 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 =0
 Estimate a rigid rotation transformation between a source and a target point cloud.
virtual void estimateRigidTransformation (const pcl::PointCloud< PointSource > &cloud_src, const pcl::PointCloud< PointTarget > &cloud_tgt, const pcl::Correspondences &correspondences, Matrix4 &transformation_matrix) const =0
 Estimate a rigid rotation transformation between a source and a target point cloud.
 TransformationEstimation ()
virtual ~TransformationEstimation ()

Detailed Description

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

TransformationEstimation represents the base class for methods for transformation estimation based on:

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:
Dirk Holz, Radu B. Rusu

Definition at line 62 of file transformation_estimation.h.


Member Typedef Documentation

template<typename PointSource, typename PointTarget, typename Scalar = float>
typedef boost::shared_ptr<const TransformationEstimation<PointSource, PointTarget, Scalar> > pcl::registration::TransformationEstimation< PointSource, PointTarget, Scalar >::ConstPtr
template<typename PointSource, typename PointTarget, typename Scalar = float>
typedef Eigen::Matrix<Scalar, 4, 4> pcl::registration::TransformationEstimation< PointSource, PointTarget, Scalar >::Matrix4
template<typename PointSource, typename PointTarget, typename Scalar = float>
typedef boost::shared_ptr<TransformationEstimation<PointSource, PointTarget, Scalar> > pcl::registration::TransformationEstimation< PointSource, PointTarget, Scalar >::Ptr

Constructor & Destructor Documentation

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

Definition at line 67 of file transformation_estimation.h.

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

Definition at line 68 of file transformation_estimation.h.


Member Function Documentation

template<typename PointSource, typename PointTarget, typename Scalar = float>
virtual void pcl::registration::TransformationEstimation< PointSource, PointTarget, Scalar >::estimateRigidTransformation ( const pcl::PointCloud< PointSource > &  cloud_src,
const pcl::PointCloud< PointTarget > &  cloud_tgt,
Matrix4 transformation_matrix 
) const [pure virtual]
template<typename PointSource, typename PointTarget, typename Scalar = float>
virtual void pcl::registration::TransformationEstimation< PointSource, PointTarget, Scalar >::estimateRigidTransformation ( const pcl::PointCloud< PointSource > &  cloud_src,
const std::vector< int > &  indices_src,
const pcl::PointCloud< PointTarget > &  cloud_tgt,
Matrix4 transformation_matrix 
) const [pure virtual]
template<typename PointSource, typename PointTarget, typename Scalar = float>
virtual void pcl::registration::TransformationEstimation< PointSource, PointTarget, Scalar >::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 [pure virtual]

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

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

Implemented in pcl::registration::TransformationEstimationLM< PointSource, PointTarget, Scalar >, pcl::registration::TransformationEstimationPointToPlaneLLS< PointSource, PointTarget, Scalar >, pcl::registration::TransformationEstimationPointToPlaneLLSWeighted< PointSource, PointTarget, Scalar >, pcl::registration::TransformationEstimationSVD< PointSource, PointTarget, Scalar >, pcl::registration::TransformationEstimationSVD< pcl::PointXYZ, pcl::PointXYZ, float >, pcl::registration::TransformationEstimationSVD< PointT, PointT, Scalar >, and pcl::registration::TransformationEstimation2D< PointSource, PointTarget, Scalar >.

template<typename PointSource, typename PointTarget, typename Scalar = float>
virtual void pcl::registration::TransformationEstimation< PointSource, PointTarget, Scalar >::estimateRigidTransformation ( const pcl::PointCloud< PointSource > &  cloud_src,
const pcl::PointCloud< PointTarget > &  cloud_tgt,
const pcl::Correspondences correspondences,
Matrix4 transformation_matrix 
) const [pure virtual]

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


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