All Classes Namespaces Files Functions Variables Typedefs Enumerations Properties Friends Defines
Public Member Functions | Protected Member Functions | Private Types | Private Attributes
pcl::IterativeClosestPointCorrespondencesCheck< PointSource, PointTarget > Class Template Reference

#include <icp_correspondences_check.h>

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

List of all members.

Public Member Functions

void estimateRigidTransformationSVD (const PointCloudSource &cloud_src, const PointCloudTarget &cloud_tgt, Eigen::Matrix4f &transformation_matrix)
 Estimate a rigid rotation transformation between a source and a target point cloud using SVD.
 IterativeClosestPointCorrespondencesCheck ()
 Empty constructor.
 IterativeClosestPointCorrespondencesCheck (double radius, int max_nn, double epsilon_z, double epsilon_curvature, bool curvature_check)
 Parameterized constructor.
void setParameters (double radius, int max_nn, double epsilon_z, double epsilon_curvature, bool curvature_check, std::string field)
 A simple method to set the parameters.
virtual ~IterativeClosestPointCorrespondencesCheck ()
 Empty destructor.

Protected Member Functions

virtual void computeTransformation (PointCloudSource &output)
 Rigid transformation computation method.

Private Types

typedef
RegistrationCorrespondencesCheck
< PointSource, PointTarget >
::PointCloudSource 
PointCloudSource
typedef PointCloudSource::ConstPtr PointCloudSourceConstPtr
typedef PointCloudSource::Ptr PointCloudSourcePtr
typedef
RegistrationCorrespondencesCheck
< PointSource, PointTarget >
::PointCloudTarget 
PointCloudTarget
typedef PointIndices::ConstPtr PointIndicesConstPtr
typedef PointIndices::Ptr PointIndicesPtr

Private Attributes

bool curvature_check_
time_t end
double epsilon_curvature_
double epsilon_z_
std::string field_
int max_nn_
double radius_
time_t start

Detailed Description

template<typename PointSource, typename PointTarget>
class pcl::IterativeClosestPointCorrespondencesCheck< PointSource, PointTarget >

Definition at line 46 of file icp_correspondences_check.h.


Member Typedef Documentation

template<typename PointSource, typename PointTarget>
typedef RegistrationCorrespondencesCheck<PointSource, PointTarget>::PointCloudSource pcl::IterativeClosestPointCorrespondencesCheck< PointSource, PointTarget >::PointCloudSource [private]
template<typename PointSource, typename PointTarget>
typedef PointCloudSource::ConstPtr pcl::IterativeClosestPointCorrespondencesCheck< PointSource, PointTarget >::PointCloudSourceConstPtr [private]
template<typename PointSource, typename PointTarget>
typedef PointCloudSource::Ptr pcl::IterativeClosestPointCorrespondencesCheck< PointSource, PointTarget >::PointCloudSourcePtr [private]
template<typename PointSource, typename PointTarget>
typedef RegistrationCorrespondencesCheck<PointSource, PointTarget>::PointCloudTarget pcl::IterativeClosestPointCorrespondencesCheck< PointSource, PointTarget >::PointCloudTarget [private]
template<typename PointSource, typename PointTarget>
typedef PointIndices::ConstPtr pcl::IterativeClosestPointCorrespondencesCheck< PointSource, PointTarget >::PointIndicesConstPtr [private]

Reimplemented from pcl::PCLBase< PointSource >.

Definition at line 68 of file icp_correspondences_check.h.

template<typename PointSource, typename PointTarget>
typedef PointIndices::Ptr pcl::IterativeClosestPointCorrespondencesCheck< PointSource, PointTarget >::PointIndicesPtr [private]

Reimplemented from pcl::PCLBase< PointSource >.

Definition at line 67 of file icp_correspondences_check.h.


Constructor & Destructor Documentation

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

Empty constructor.

Definition at line 79 of file icp_correspondences_check.h.

template<typename PointSource, typename PointTarget>
pcl::IterativeClosestPointCorrespondencesCheck< PointSource, PointTarget >::IterativeClosestPointCorrespondencesCheck ( double  radius,
int  max_nn,
double  epsilon_z,
double  epsilon_curvature,
bool  curvature_check 
) [inline]

Parameterized constructor.

Definition at line 81 of file icp_correspondences_check.h.

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

Empty destructor.

Definition at line 90 of file icp_correspondences_check.h.


Member Function Documentation

template<typename PointSource, typename PointTarget>
virtual void pcl::IterativeClosestPointCorrespondencesCheck< PointSource, PointTarget >::computeTransformation ( PointCloudSource output) [inline, protected, virtual]

Rigid transformation computation method.

Parameters:
outputthe transformed input point cloud dataset using the rigid transformation found

Implements pcl::RegistrationCorrespondencesCheck< PointSource, PointTarget >.

Definition at line 98 of file icp_correspondences_check.h.

template<typename PointSource, typename PointTarget>
void pcl::IterativeClosestPointCorrespondencesCheck< PointSource, PointTarget >::estimateRigidTransformationSVD ( const PointCloudSource cloud_src,
const PointCloudTarget cloud_tgt,
Eigen::Matrix4f &  transformation_matrix 
) [inline]

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

Parameters:
cloud_srcthe source point cloud dataset
cloud_tgtthe target point cloud dataset
transformation_matrixthe resultant transformation matrix

Definition at line 264 of file icp_correspondences_check.h.

template<typename PointSource, typename PointTarget>
void pcl::IterativeClosestPointCorrespondencesCheck< PointSource, PointTarget >::setParameters ( double  radius,
int  max_nn,
double  epsilon_z,
double  epsilon_curvature,
bool  curvature_check,
std::string  field 
) [inline]

A simple method to set the parameters.

Definition at line 331 of file icp_correspondences_check.h.


Member Data Documentation

template<typename PointSource, typename PointTarget>
bool pcl::IterativeClosestPointCorrespondencesCheck< PointSource, PointTarget >::curvature_check_ [private]

Definition at line 72 of file icp_correspondences_check.h.

template<typename PointSource, typename PointTarget>
time_t pcl::IterativeClosestPointCorrespondencesCheck< PointSource, PointTarget >::end [private]

Definition at line 73 of file icp_correspondences_check.h.

template<typename PointSource, typename PointTarget>
double pcl::IterativeClosestPointCorrespondencesCheck< PointSource, PointTarget >::epsilon_curvature_ [private]

Definition at line 70 of file icp_correspondences_check.h.

template<typename PointSource, typename PointTarget>
double pcl::IterativeClosestPointCorrespondencesCheck< PointSource, PointTarget >::epsilon_z_ [private]

Definition at line 70 of file icp_correspondences_check.h.

template<typename PointSource, typename PointTarget>
std::string pcl::IterativeClosestPointCorrespondencesCheck< PointSource, PointTarget >::field_ [private]

Definition at line 74 of file icp_correspondences_check.h.

template<typename PointSource, typename PointTarget>
int pcl::IterativeClosestPointCorrespondencesCheck< PointSource, PointTarget >::max_nn_ [private]

Definition at line 71 of file icp_correspondences_check.h.

template<typename PointSource, typename PointTarget>
double pcl::IterativeClosestPointCorrespondencesCheck< PointSource, PointTarget >::radius_ [private]

Definition at line 70 of file icp_correspondences_check.h.

template<typename PointSource, typename PointTarget>
time_t pcl::IterativeClosestPointCorrespondencesCheck< PointSource, PointTarget >::start [private]

Definition at line 73 of file icp_correspondences_check.h.


The documentation for this class was generated from the following file:
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Properties Friends Defines


pointcloud_registration
Author(s): Hozefa Indorewala
autogenerated on Sun Oct 6 2013 11:55:58