Classes | Public Member Functions | Public Attributes | Private Member Functions | Private Attributes
lslgeneric::NDTMatcherP2D< PointSource, PointTarget > Class Template Reference

#include <ndt_matcher_p2d.h>

List of all members.

Classes

struct  MoreThuente

Public Member Functions

bool covariance (pcl::PointCloud< PointTarget > &target, pcl::PointCloud< PointSource > &source, Eigen::Transform< double, 3, Eigen::Affine, Eigen::ColMajor > &T, Eigen::Matrix< double, 6, 6 > &cov)
void derivativesPointCloud (pcl::PointCloud< PointSource > &source, NDTMap< PointTarget > &target, Eigen::Transform< double, 3, Eigen::Affine, Eigen::ColMajor > &transform, Eigen::Matrix< double, 6, 1 > &score_gradient, Eigen::Matrix< double, 6, 6 > &Hessian, bool computeHessian)
void generateScoreDebug (const char *out, pcl::PointCloud< PointTarget > &target, pcl::PointCloud< PointSource > &source)
bool match (pcl::PointCloud< PointTarget > &target, pcl::PointCloud< PointSource > &source, Eigen::Transform< double, 3, Eigen::Affine, Eigen::ColMajor > &T)
bool match (NDTMap< PointTarget > &target, pcl::PointCloud< PointSource > &source, Eigen::Transform< double, 3, Eigen::Affine, Eigen::ColMajor > &T)
 NDTMatcherP2D (std::vector< double > _resolutions)
 NDTMatcherP2D ()
 NDTMatcherP2D (const NDTMatcherP2D< PointSource, PointTarget > &other)
double scorePointCloud (pcl::PointCloud< PointSource > &source, NDTMap< PointTarget > &target)

Public Attributes

double finalscore

Private Member Functions

void computeDerivatives (PointSource &pt)
void init (bool useDefaultGridResolutions, std::vector< double > _resolutions)
double lineSearch (double score_here, Eigen::Matrix< double, 6, 1 > &score_gradient, Eigen::Matrix< double, 6, 1 > &increment, pcl::PointCloud< PointSource > &source, NDTMap< PointTarget > &target)
double lineSearchMT (Eigen::Matrix< double, 6, 1 > &score_gradient_init, Eigen::Matrix< double, 6, 1 > &increment, pcl::PointCloud< PointSource > &source, Eigen::Transform< double, 3, Eigen::Affine, Eigen::ColMajor > &globalT, NDTMap< PointTarget > &target)
double normalizeAngle (double a)
void precomputeAngleDerivatives (Eigen::Vector3d &eulerAngles)
pcl::PointCloud< PointSource > subsample (pcl::PointCloud< PointSource > &original)
void update_hessian (Eigen::Matrix< double, 6, 6 > &Hessian, Eigen::Vector3d &transformed, Eigen::Matrix3d &Cinv)
bool update_score_gradient (Eigen::Matrix< double, 6, 1 > &score_gradient, Eigen::Vector3d &transformed, Eigen::Matrix3d &Cinv)

Private Attributes

Eigen::Vector3d a2
Eigen::Vector3d a3
Eigen::Vector3d b2
Eigen::Vector3d b3
Eigen::Vector3d c2
Eigen::Vector3d c3
double current_resolution
Eigen::Vector3d d1
Eigen::Vector3d d2
Eigen::Vector3d d3
Eigen::Vector3d e1
Eigen::Vector3d e2
Eigen::Vector3d e3
Eigen::Vector3d f1
Eigen::Vector3d f2
Eigen::Vector3d f3
Eigen::Matrix< double, 18, 6 > Hest
bool isIrregularGrid
Eigen::Matrix< double, 3, 6 > Jest
Eigen::Vector3d jest04
Eigen::Vector3d jest05
Eigen::Vector3d jest13
Eigen::Vector3d jest14
Eigen::Vector3d jest15
Eigen::Vector3d jest23
Eigen::Vector3d jest24
Eigen::Vector3d jest25
double lfd1
double lfd2
int NUMBER_OF_ACTIVE_CELLS
int NUMBER_OF_POINTS
std::vector< double > resolutions
bool useSimpleDerivatives

Detailed Description

template<typename PointSource, typename PointTarget>
class lslgeneric::NDTMatcherP2D< PointSource, PointTarget >

This class implements NDT registration for 3D point cloud scans.

Definition at line 49 of file ndt_matcher_p2d.h.


Constructor & Destructor Documentation

template<typename PointSource, typename PointTarget>
lslgeneric::NDTMatcherP2D< PointSource, PointTarget >::NDTMatcherP2D ( std::vector< double >  _resolutions) [inline]

Definition at line 52 of file ndt_matcher_p2d.h.

template<typename PointSource, typename PointTarget>
lslgeneric::NDTMatcherP2D< PointSource, PointTarget >::NDTMatcherP2D ( ) [inline]

Definition at line 56 of file ndt_matcher_p2d.h.

template<typename PointSource, typename PointTarget>
lslgeneric::NDTMatcherP2D< PointSource, PointTarget >::NDTMatcherP2D ( const NDTMatcherP2D< PointSource, PointTarget > &  other) [inline]

Definition at line 60 of file ndt_matcher_p2d.h.


Member Function Documentation

template<typename PointSource , typename PointTarget >
void lslgeneric::NDTMatcherP2D< PointSource, PointTarget >::computeDerivatives ( PointSource &  pt) [private]

Definition at line 511 of file ndt_matcher_p2d.hpp.

template<typename PointSource , typename PointTarget >
bool lslgeneric::NDTMatcherP2D< PointSource, PointTarget >::covariance ( pcl::PointCloud< PointTarget > &  target,
pcl::PointCloud< PointSource > &  source,
Eigen::Transform< double, 3, Eigen::Affine, Eigen::ColMajor > &  T,
Eigen::Matrix< double, 6, 6 > &  cov 
)

computes the covariance of the match between moving and fixed, at T. note --- computes NDT distributions based on the resolution in res result is returned in cov

Definition at line 238 of file ndt_matcher_p2d.hpp.

template<typename PointSource , typename PointTarget >
void lslgeneric::NDTMatcherP2D< PointSource, PointTarget >::derivativesPointCloud ( pcl::PointCloud< PointSource > &  source,
NDTMap< PointTarget > &  target,
Eigen::Transform< double, 3, Eigen::Affine, Eigen::ColMajor > &  transform,
Eigen::Matrix< double, 6, 1 > &  score_gradient,
Eigen::Matrix< double, 6, 6 > &  Hessian,
bool  computeHessian 
)

Definition at line 624 of file ndt_matcher_p2d.hpp.

template<typename PointSource , typename PointTarget >
void lslgeneric::NDTMatcherP2D< PointSource, PointTarget >::generateScoreDebug ( const char *  out,
pcl::PointCloud< PointTarget > &  target,
pcl::PointCloud< PointSource > &  source 
)

Definition at line 53 of file ndt_matcher_p2d.hpp.

template<typename PointSource , typename PointTarget >
void lslgeneric::NDTMatcherP2D< PointSource, PointTarget >::init ( bool  useDefaultGridResolutions,
std::vector< double >  _resolutions 
) [private]

Definition at line 14 of file ndt_matcher_p2d.hpp.

template<typename PointSource, typename PointTarget>
double lslgeneric::NDTMatcherP2D< PointSource, PointTarget >::lineSearch ( double  score_here,
Eigen::Matrix< double, 6, 1 > &  score_gradient,
Eigen::Matrix< double, 6, 1 > &  increment,
pcl::PointCloud< PointSource > &  source,
NDTMap< PointTarget > &  target 
) [private]
template<typename PointSource , typename PointTarget >
double lslgeneric::NDTMatcherP2D< PointSource, PointTarget >::lineSearchMT ( Eigen::Matrix< double, 6, 1 > &  score_gradient_init,
Eigen::Matrix< double, 6, 1 > &  increment,
pcl::PointCloud< PointSource > &  source,
Eigen::Transform< double, 3, Eigen::Affine, Eigen::ColMajor > &  globalT,
NDTMap< PointTarget > &  target 
) [private]

Definition at line 709 of file ndt_matcher_p2d.hpp.

template<typename PointSource , typename PointTarget >
bool lslgeneric::NDTMatcherP2D< PointSource, PointTarget >::match ( pcl::PointCloud< PointTarget > &  target,
pcl::PointCloud< PointSource > &  source,
Eigen::Transform< double, 3, Eigen::Affine, Eigen::ColMajor > &  T 
)

Register two point clouds. This method builds an NDT representation of the "fixed" point cloud and uses that for registering the "moving" point cloud.

Parameters:
fixedReference data. NDT structure is built for this point cloud.
movingThe output transformation registers this point cloud to fixed.
TThis is an input/output parameter. The initial value of T gives the initial pose estimate of moving. When the algorithm terminates, T holds the registration result.

Definition at line 165 of file ndt_matcher_p2d.hpp.

template<typename PointSource , typename PointTarget >
bool lslgeneric::NDTMatcherP2D< PointSource, PointTarget >::match ( NDTMap< PointTarget > &  target,
pcl::PointCloud< PointSource > &  source,
Eigen::Transform< double, 3, Eigen::Affine, Eigen::ColMajor > &  T 
)

Registers a point cloud to an NDT structure.

Parameters:
fixedReference data.
movingThe output transformation registers this point cloud to fixed.
TThis is an input/output parameter. The initial value of T gives the initial pose estimate of moving. When the algorithm terminates, T holds the registration result.

Definition at line 265 of file ndt_matcher_p2d.hpp.

template<typename PointSource , typename PointTarget >
double lslgeneric::NDTMatcherP2D< PointSource, PointTarget >::normalizeAngle ( double  a) [private]

Definition at line 1346 of file ndt_matcher_p2d.hpp.

template<typename PointSource , typename PointTarget >
void lslgeneric::NDTMatcherP2D< PointSource, PointTarget >::precomputeAngleDerivatives ( Eigen::Vector3d &  eulerAngles) [private]

Definition at line 469 of file ndt_matcher_p2d.hpp.

template<typename PointSource , typename PointTarget >
double lslgeneric::NDTMatcherP2D< PointSource, PointTarget >::scorePointCloud ( pcl::PointCloud< PointSource > &  source,
NDTMap< PointTarget > &  target 
)

Definition at line 562 of file ndt_matcher_p2d.hpp.

template<typename PointSource , typename PointTarget >
pcl::PointCloud< PointSource > lslgeneric::NDTMatcherP2D< PointSource, PointTarget >::subsample ( pcl::PointCloud< PointSource > &  original) [private]

Definition at line 1251 of file ndt_matcher_p2d.hpp.

template<typename PointSource , typename PointTarget >
void lslgeneric::NDTMatcherP2D< PointSource, PointTarget >::update_hessian ( Eigen::Matrix< double, 6, 6 > &  Hessian,
Eigen::Vector3d &  transformed,
Eigen::Matrix3d &  Cinv 
) [private]

Definition at line 443 of file ndt_matcher_p2d.hpp.

template<typename PointSource , typename PointTarget >
bool lslgeneric::NDTMatcherP2D< PointSource, PointTarget >::update_score_gradient ( Eigen::Matrix< double, 6, 1 > &  score_gradient,
Eigen::Vector3d &  transformed,
Eigen::Matrix3d &  Cinv 
) [private]

Definition at line 413 of file ndt_matcher_p2d.hpp.


Member Data Documentation

template<typename PointSource, typename PointTarget>
Eigen::Vector3d lslgeneric::NDTMatcherP2D< PointSource, PointTarget >::a2 [private]

Definition at line 192 of file ndt_matcher_p2d.h.

template<typename PointSource, typename PointTarget>
Eigen::Vector3d lslgeneric::NDTMatcherP2D< PointSource, PointTarget >::a3 [private]

Definition at line 192 of file ndt_matcher_p2d.h.

template<typename PointSource, typename PointTarget>
Eigen::Vector3d lslgeneric::NDTMatcherP2D< PointSource, PointTarget >::b2 [private]

Definition at line 192 of file ndt_matcher_p2d.h.

template<typename PointSource, typename PointTarget>
Eigen::Vector3d lslgeneric::NDTMatcherP2D< PointSource, PointTarget >::b3 [private]

Definition at line 192 of file ndt_matcher_p2d.h.

template<typename PointSource, typename PointTarget>
Eigen::Vector3d lslgeneric::NDTMatcherP2D< PointSource, PointTarget >::c2 [private]

Definition at line 192 of file ndt_matcher_p2d.h.

template<typename PointSource, typename PointTarget>
Eigen::Vector3d lslgeneric::NDTMatcherP2D< PointSource, PointTarget >::c3 [private]

Definition at line 192 of file ndt_matcher_p2d.h.

template<typename PointSource, typename PointTarget>
double lslgeneric::NDTMatcherP2D< PointSource, PointTarget >::current_resolution [private]

Definition at line 132 of file ndt_matcher_p2d.h.

template<typename PointSource, typename PointTarget>
Eigen::Vector3d lslgeneric::NDTMatcherP2D< PointSource, PointTarget >::d1 [private]

Definition at line 192 of file ndt_matcher_p2d.h.

template<typename PointSource, typename PointTarget>
Eigen::Vector3d lslgeneric::NDTMatcherP2D< PointSource, PointTarget >::d2 [private]

Definition at line 192 of file ndt_matcher_p2d.h.

template<typename PointSource, typename PointTarget>
Eigen::Vector3d lslgeneric::NDTMatcherP2D< PointSource, PointTarget >::d3 [private]

Definition at line 192 of file ndt_matcher_p2d.h.

template<typename PointSource, typename PointTarget>
Eigen::Vector3d lslgeneric::NDTMatcherP2D< PointSource, PointTarget >::e1 [private]

Definition at line 192 of file ndt_matcher_p2d.h.

template<typename PointSource, typename PointTarget>
Eigen::Vector3d lslgeneric::NDTMatcherP2D< PointSource, PointTarget >::e2 [private]

Definition at line 192 of file ndt_matcher_p2d.h.

template<typename PointSource, typename PointTarget>
Eigen::Vector3d lslgeneric::NDTMatcherP2D< PointSource, PointTarget >::e3 [private]

Definition at line 192 of file ndt_matcher_p2d.h.

template<typename PointSource, typename PointTarget>
Eigen::Vector3d lslgeneric::NDTMatcherP2D< PointSource, PointTarget >::f1 [private]

Definition at line 192 of file ndt_matcher_p2d.h.

template<typename PointSource, typename PointTarget>
Eigen::Vector3d lslgeneric::NDTMatcherP2D< PointSource, PointTarget >::f2 [private]

Definition at line 192 of file ndt_matcher_p2d.h.

template<typename PointSource, typename PointTarget>
Eigen::Vector3d lslgeneric::NDTMatcherP2D< PointSource, PointTarget >::f3 [private]

Definition at line 192 of file ndt_matcher_p2d.h.

template<typename PointSource, typename PointTarget>
double lslgeneric::NDTMatcherP2D< PointSource, PointTarget >::finalscore

Definition at line 124 of file ndt_matcher_p2d.h.

template<typename PointSource, typename PointTarget>
Eigen::Matrix<double,18,6> lslgeneric::NDTMatcherP2D< PointSource, PointTarget >::Hest [private]

Definition at line 128 of file ndt_matcher_p2d.h.

template<typename PointSource, typename PointTarget>
bool lslgeneric::NDTMatcherP2D< PointSource, PointTarget >::isIrregularGrid [private]

Definition at line 133 of file ndt_matcher_p2d.h.

template<typename PointSource, typename PointTarget>
Eigen::Matrix<double,3,6> lslgeneric::NDTMatcherP2D< PointSource, PointTarget >::Jest [private]

Definition at line 127 of file ndt_matcher_p2d.h.

template<typename PointSource, typename PointTarget>
Eigen::Vector3d lslgeneric::NDTMatcherP2D< PointSource, PointTarget >::jest04 [private]

Definition at line 191 of file ndt_matcher_p2d.h.

template<typename PointSource, typename PointTarget>
Eigen::Vector3d lslgeneric::NDTMatcherP2D< PointSource, PointTarget >::jest05 [private]

Definition at line 191 of file ndt_matcher_p2d.h.

template<typename PointSource, typename PointTarget>
Eigen::Vector3d lslgeneric::NDTMatcherP2D< PointSource, PointTarget >::jest13 [private]

Definition at line 191 of file ndt_matcher_p2d.h.

template<typename PointSource, typename PointTarget>
Eigen::Vector3d lslgeneric::NDTMatcherP2D< PointSource, PointTarget >::jest14 [private]

Definition at line 191 of file ndt_matcher_p2d.h.

template<typename PointSource, typename PointTarget>
Eigen::Vector3d lslgeneric::NDTMatcherP2D< PointSource, PointTarget >::jest15 [private]

Definition at line 191 of file ndt_matcher_p2d.h.

template<typename PointSource, typename PointTarget>
Eigen::Vector3d lslgeneric::NDTMatcherP2D< PointSource, PointTarget >::jest23 [private]

Definition at line 191 of file ndt_matcher_p2d.h.

template<typename PointSource, typename PointTarget>
Eigen::Vector3d lslgeneric::NDTMatcherP2D< PointSource, PointTarget >::jest24 [private]

Definition at line 191 of file ndt_matcher_p2d.h.

template<typename PointSource, typename PointTarget>
Eigen::Vector3d lslgeneric::NDTMatcherP2D< PointSource, PointTarget >::jest25 [private]

Definition at line 191 of file ndt_matcher_p2d.h.

template<typename PointSource, typename PointTarget>
double lslgeneric::NDTMatcherP2D< PointSource, PointTarget >::lfd1 [private]

Definition at line 130 of file ndt_matcher_p2d.h.

template<typename PointSource, typename PointTarget>
double lslgeneric::NDTMatcherP2D< PointSource, PointTarget >::lfd2 [private]

Definition at line 130 of file ndt_matcher_p2d.h.

template<typename PointSource, typename PointTarget>
int lslgeneric::NDTMatcherP2D< PointSource, PointTarget >::NUMBER_OF_ACTIVE_CELLS [private]

Definition at line 187 of file ndt_matcher_p2d.h.

template<typename PointSource, typename PointTarget>
int lslgeneric::NDTMatcherP2D< PointSource, PointTarget >::NUMBER_OF_POINTS [private]

Definition at line 186 of file ndt_matcher_p2d.h.

template<typename PointSource, typename PointTarget>
std::vector<double> lslgeneric::NDTMatcherP2D< PointSource, PointTarget >::resolutions [private]

Definition at line 194 of file ndt_matcher_p2d.h.

template<typename PointSource, typename PointTarget>
bool lslgeneric::NDTMatcherP2D< PointSource, PointTarget >::useSimpleDerivatives [private]

Definition at line 131 of file ndt_matcher_p2d.h.


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


ndt_registration
Author(s): Todor Stoyanov, Jari Saarinen, Henrik Andreasson
autogenerated on Mon Oct 6 2014 03:19:30