pcl::IterativeClosestPointNonLinear< PointSource, PointTarget > Class Template Reference

IterativeClosestPointNonLinear is an ICP variant that uses Levenberg-Marquardt optimization backend. The resultant transformation is optimized as a quaternion. More...

#include <icp_nl.h>

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

List of all members.

Public Member Functions

void estimateRigidTransformationLM (const PointCloudSource &cloud_src, const std::vector< int > &indices_src, const PointCloudTarget &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 an iterative non-linear Levenberg-Marquardt approach.
void estimateRigidTransformationLM (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 an iterative non-linear Levenberg-Marquardt approach.
 IterativeClosestPointNonLinear ()
 Empty constructor.

Protected Member Functions

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

Private Types

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

Private Member Functions

double computeMedian (double *fvec, int m)
 Compute the median value from a set of doubles.
double distGedikli (double val, double clipping)
 Use a Gedikli kernel to estimate the distance between two vectors (for more information, see.
double distHuber (double diff, double sigma)
 Use a Huber kernel to estimate the distance between two vectors.
double distHuber (const Eigen::Vector4f &p_src, const Eigen::Vector4f &p_tgt, double sigma)
 Use a Huber kernel to estimate the distance between two vectors.
double distL1 (const Eigen::Vector4f &p_src, const Eigen::Vector4f &p_tgt)
 Compute the Manhattan distance between two eigen vectors.
double distL2Sqr (const Eigen::Vector4f &p_src, const Eigen::Vector4f &p_tgt)
 Compute the squared Euclidean distance between two eigen vectors.

Static Private Member Functions

static int functionToOptimize (void *p, int m, int n, const double *x, double *fvec, int iflag)
 Cost function to be minimized.
static int functionToOptimizeIndices (void *p, int m, int n, const double *x, double *fvec, int iflag)
 Cost function to be minimized.

Private 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.
boost::mutex tmp_mutex_
 Temporary boost mutex for tmp_src_ and tmp_tgt_.
const PointCloudSourcetmp_src_
 Temporary pointer to the source dataset.
const PointCloudTargettmp_tgt_
 Temporary pointer to the target dataset.
std::vector< double > weights_
 The vector of residual weights. Used internall in the LM loop.

Detailed Description

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

IterativeClosestPointNonLinear is an ICP variant that uses Levenberg-Marquardt optimization backend. The resultant transformation is optimized as a quaternion.

Author:
Radu Bogdan Rusu, Michael Dixon

Definition at line 57 of file icp_nl.h.


Member Typedef Documentation

template<typename PointSource, typename PointTarget>
typedef Registration<PointSource, PointTarget>::PointCloudSource pcl::IterativeClosestPointNonLinear< PointSource, PointTarget >::PointCloudSource [private]

Reimplemented from pcl::Registration< PointSource, PointTarget >.

Definition at line 74 of file icp_nl.h.

template<typename PointSource, typename PointTarget>
typedef PointCloudSource::ConstPtr pcl::IterativeClosestPointNonLinear< PointSource, PointTarget >::PointCloudSourceConstPtr [private]

Reimplemented from pcl::Registration< PointSource, PointTarget >.

Definition at line 76 of file icp_nl.h.

template<typename PointSource, typename PointTarget>
typedef PointCloudSource::Ptr pcl::IterativeClosestPointNonLinear< PointSource, PointTarget >::PointCloudSourcePtr [private]

Reimplemented from pcl::Registration< PointSource, PointTarget >.

Definition at line 75 of file icp_nl.h.

template<typename PointSource, typename PointTarget>
typedef Registration<PointSource, PointTarget>::PointCloudTarget pcl::IterativeClosestPointNonLinear< PointSource, PointTarget >::PointCloudTarget [private]

Reimplemented from pcl::Registration< PointSource, PointTarget >.

Definition at line 78 of file icp_nl.h.

template<typename PointSource, typename PointTarget>
typedef PointIndices::ConstPtr pcl::IterativeClosestPointNonLinear< PointSource, PointTarget >::PointIndicesConstPtr [private]

Reimplemented from pcl::PCLBase< PointSource >.

Definition at line 81 of file icp_nl.h.

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

Reimplemented from pcl::PCLBase< PointSource >.

Definition at line 80 of file icp_nl.h.


Constructor & Destructor Documentation

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

Empty constructor.

Definition at line 85 of file icp_nl.h.


Member Function Documentation

template<typename PointSource , typename PointTarget >
double pcl::IterativeClosestPointNonLinear< PointSource, PointTarget >::computeMedian ( double *  fvec,
int  m 
) [inline, private]

Compute the median value from a set of doubles.

Parameters:
fvec the set of doubles
m the number of doubles in the set

Definition at line 369 of file icp_nl.hpp.

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

Rigid transformation computation method.

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

Implements pcl::Registration< PointSource, PointTarget >.

Definition at line 197 of file icp_nl.hpp.

template<typename PointSource, typename PointTarget>
double pcl::IterativeClosestPointNonLinear< PointSource, PointTarget >::distGedikli ( double  val,
double  clipping 
) [inline, private]

Use a Gedikli kernel to estimate the distance between two vectors (for more information, see.

Parameters:
val the norm difference between two vectors
clipping the clipping value

Definition at line 182 of file icp_nl.h.

template<typename PointSource, typename PointTarget>
double pcl::IterativeClosestPointNonLinear< PointSource, PointTarget >::distHuber ( double  diff,
double  sigma 
) [inline, private]

Use a Huber kernel to estimate the distance between two vectors.

Parameters:
diff the norm difference between two vectors
sigma the sigma value

Definition at line 166 of file icp_nl.h.

template<typename PointSource, typename PointTarget>
double pcl::IterativeClosestPointNonLinear< PointSource, PointTarget >::distHuber ( const Eigen::Vector4f &  p_src,
const Eigen::Vector4f &  p_tgt,
double  sigma 
) [inline, private]

Use a Huber kernel to estimate the distance between two vectors.

Parameters:
p_src the first eigen vector
p_tgt the second eigen vector
sigma the sigma value

Definition at line 147 of file icp_nl.h.

template<typename PointSource, typename PointTarget>
double pcl::IterativeClosestPointNonLinear< PointSource, PointTarget >::distL1 ( const Eigen::Vector4f &  p_src,
const Eigen::Vector4f &  p_tgt 
) [inline, private]

Compute the Manhattan distance between two eigen vectors.

Parameters:
p_src the first eigen vector
p_tgt the second eigen vector

Definition at line 193 of file icp_nl.h.

template<typename PointSource, typename PointTarget>
double pcl::IterativeClosestPointNonLinear< PointSource, PointTarget >::distL2Sqr ( const Eigen::Vector4f &  p_src,
const Eigen::Vector4f &  p_tgt 
) [inline, private]

Compute the squared Euclidean distance between two eigen vectors.

Parameters:
p_src the first eigen vector
p_tgt the second eigen vector

Definition at line 203 of file icp_nl.h.

template<typename PointSource , typename PointTarget >
void pcl::IterativeClosestPointNonLinear< PointSource, PointTarget >::estimateRigidTransformationLM ( const PointCloudSource cloud_src,
const std::vector< int > &  indices_src,
const PointCloudTarget cloud_tgt,
const std::vector< int > &  indices_tgt,
Eigen::Matrix4f &  transformation_matrix 
) [inline]

Estimate a rigid rotation transformation between a source and a target point cloud using an iterative non-linear Levenberg-Marquardt approach.

Parameters:
cloud_src the source point cloud dataset
indices_src the vector of indices describing the points of interest in cloud_src
cloud_tgt the target point cloud dataset
indices_tgt the vector of indices describing the correspondences of the interst points from indices_src
transformation_matrix the resultant transformation matrix

Definition at line 123 of file icp_nl.hpp.

template<typename PointSource , typename PointTarget >
void pcl::IterativeClosestPointNonLinear< PointSource, PointTarget >::estimateRigidTransformationLM ( 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 an iterative non-linear Levenberg-Marquardt approach.

Parameters:
cloud_src the source point cloud dataset
cloud_tgt the target point cloud dataset
transformation_matrix the resultant transformation matrix

Definition at line 46 of file icp_nl.hpp.

template<typename PointSource , typename PointTarget >
int pcl::IterativeClosestPointNonLinear< PointSource, PointTarget >::functionToOptimize ( void *  p,
int  m,
int  n,
const double *  x,
double *  fvec,
int  iflag 
) [inline, static, private]

Cost function to be minimized.

Parameters:
p a pointer to our data structure array
m the number of functions
n the number of variables
x a pointer to the variables array
fvec a pointer to the resultant functions evaluations
iflag set to -1 inside the function to terminate execution

Definition at line 328 of file icp_nl.hpp.

template<typename PointSource , typename PointTarget >
int pcl::IterativeClosestPointNonLinear< PointSource, PointTarget >::functionToOptimizeIndices ( void *  p,
int  m,
int  n,
const double *  x,
double *  fvec,
int  iflag 
) [inline, static, private]

Cost function to be minimized.

Parameters:
p a pointer to our data structure array
m the number of functions
n the number of variables
x a pointer to the variables array
fvec a pointer to the resultant functions evaluations
iflag set to -1 inside the function to terminate execution

Definition at line 396 of file icp_nl.hpp.


Member Data Documentation

template<typename PointSource, typename PointTarget>
const std::vector<int>* pcl::IterativeClosestPointNonLinear< PointSource, PointTarget >::tmp_idx_src_ [private]

Temporary pointer to the source dataset indices.

Definition at line 221 of file icp_nl.h.

template<typename PointSource, typename PointTarget>
const std::vector<int>* pcl::IterativeClosestPointNonLinear< PointSource, PointTarget >::tmp_idx_tgt_ [private]

Temporary pointer to the target dataset indices.

Definition at line 224 of file icp_nl.h.

template<typename PointSource, typename PointTarget>
boost::mutex pcl::IterativeClosestPointNonLinear< PointSource, PointTarget >::tmp_mutex_ [private]

Temporary boost mutex for tmp_src_ and tmp_tgt_.

Definition at line 212 of file icp_nl.h.

template<typename PointSource, typename PointTarget>
const PointCloudSource* pcl::IterativeClosestPointNonLinear< PointSource, PointTarget >::tmp_src_ [private]

Temporary pointer to the source dataset.

Definition at line 215 of file icp_nl.h.

template<typename PointSource, typename PointTarget>
const PointCloudTarget* pcl::IterativeClosestPointNonLinear< PointSource, PointTarget >::tmp_tgt_ [private]

Temporary pointer to the target dataset.

Definition at line 218 of file icp_nl.h.

template<typename PointSource, typename PointTarget>
std::vector<double> pcl::IterativeClosestPointNonLinear< PointSource, PointTarget >::weights_ [private]

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

Definition at line 209 of file icp_nl.h.


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


pcl
Author(s): See http://pcl.ros.org/authors for the complete list of authors.
autogenerated on Fri Jan 11 09:57:18 2013