IterativeClosestPointNonLinear is an ICP variant that uses Levenberg-Marquardt optimization backend. The resultant transformation is optimized as a quaternion. More...
#include <icp_nl.h>

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 PointCloudSource * | tmp_src_ |
| Temporary pointer to the source dataset. | |
| const PointCloudTarget * | tmp_tgt_ |
| Temporary pointer to the target dataset. | |
| std::vector< double > | weights_ |
| The vector of residual weights. Used internall in the LM loop. | |
IterativeClosestPointNonLinear is an ICP variant that uses Levenberg-Marquardt optimization backend. The resultant transformation is optimized as a quaternion.
Definition at line 57 of file icp_nl.h.
typedef Registration<PointSource, PointTarget>::PointCloudSource pcl::IterativeClosestPointNonLinear< PointSource, PointTarget >::PointCloudSource [private] |
Reimplemented from pcl::Registration< PointSource, PointTarget >.
typedef PointCloudSource::ConstPtr pcl::IterativeClosestPointNonLinear< PointSource, PointTarget >::PointCloudSourceConstPtr [private] |
Reimplemented from pcl::Registration< PointSource, PointTarget >.
typedef PointCloudSource::Ptr pcl::IterativeClosestPointNonLinear< PointSource, PointTarget >::PointCloudSourcePtr [private] |
Reimplemented from pcl::Registration< PointSource, PointTarget >.
typedef Registration<PointSource, PointTarget>::PointCloudTarget pcl::IterativeClosestPointNonLinear< PointSource, PointTarget >::PointCloudTarget [private] |
Reimplemented from pcl::Registration< PointSource, PointTarget >.
typedef PointIndices::ConstPtr pcl::IterativeClosestPointNonLinear< PointSource, PointTarget >::PointIndicesConstPtr [private] |
Reimplemented from pcl::PCLBase< PointSource >.
typedef PointIndices::Ptr pcl::IterativeClosestPointNonLinear< PointSource, PointTarget >::PointIndicesPtr [private] |
Reimplemented from pcl::PCLBase< PointSource >.
| pcl::IterativeClosestPointNonLinear< PointSource, PointTarget >::IterativeClosestPointNonLinear | ( | ) | [inline] |
| double pcl::IterativeClosestPointNonLinear< PointSource, PointTarget >::computeMedian | ( | double * | fvec, | |
| int | m | |||
| ) | [inline, private] |
Compute the median value from a set of doubles.
| fvec | the set of doubles | |
| m | the number of doubles in the set |
Definition at line 369 of file icp_nl.hpp.
| void pcl::IterativeClosestPointNonLinear< PointSource, PointTarget >::computeTransformation | ( | PointCloudSource & | output | ) | [inline, protected, virtual] |
Rigid transformation computation method.
| 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.
| double pcl::IterativeClosestPointNonLinear< PointSource, PointTarget >::distGedikli | ( | double | val, | |
| double | clipping | |||
| ) | [inline, private] |
| double pcl::IterativeClosestPointNonLinear< PointSource, PointTarget >::distHuber | ( | double | diff, | |
| double | sigma | |||
| ) | [inline, private] |
| double pcl::IterativeClosestPointNonLinear< PointSource, PointTarget >::distHuber | ( | const Eigen::Vector4f & | p_src, | |
| const Eigen::Vector4f & | p_tgt, | |||
| double | sigma | |||
| ) | [inline, private] |
| double pcl::IterativeClosestPointNonLinear< PointSource, PointTarget >::distL1 | ( | const Eigen::Vector4f & | p_src, | |
| const Eigen::Vector4f & | p_tgt | |||
| ) | [inline, private] |
| double pcl::IterativeClosestPointNonLinear< PointSource, PointTarget >::distL2Sqr | ( | const Eigen::Vector4f & | p_src, | |
| const Eigen::Vector4f & | p_tgt | |||
| ) | [inline, private] |
| 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.
| 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.
| 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.
| 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.
| 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.
| 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.
| 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.
| 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.
const std::vector<int>* pcl::IterativeClosestPointNonLinear< PointSource, PointTarget >::tmp_idx_src_ [private] |
const std::vector<int>* pcl::IterativeClosestPointNonLinear< PointSource, PointTarget >::tmp_idx_tgt_ [private] |
boost::mutex pcl::IterativeClosestPointNonLinear< PointSource, PointTarget >::tmp_mutex_ [private] |
const PointCloudSource* pcl::IterativeClosestPointNonLinear< PointSource, PointTarget >::tmp_src_ [private] |
const PointCloudTarget* pcl::IterativeClosestPointNonLinear< PointSource, PointTarget >::tmp_tgt_ [private] |
std::vector<double> pcl::IterativeClosestPointNonLinear< PointSource, PointTarget >::weights_ [private] |