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

#include <ndt_matcher_d2d_2d.h>

List of all members.

Classes

struct  MoreThuente

Public Member Functions

virtual double derivativesNDT_2d (const std::vector< NDTCell< PointSource > * > &source, const NDTMap< PointTarget > &target, Eigen::MatrixXd &score_gradient, Eigen::MatrixXd &Hessian, bool computeHessian)
bool match (pcl::PointCloud< PointTarget > &target, pcl::PointCloud< PointSource > &source, Eigen::Transform< double, 3, Eigen::Affine, Eigen::ColMajor > &T, bool useInitialGuess=false)
bool match (NDTMap< PointTarget > &target, NDTMap< PointSource > &source, Eigen::Transform< double, 3, Eigen::Affine, Eigen::ColMajor > &T, bool useInitialGuess=false)
 NDTMatcherD2D_2D (bool _isIrregularGrid, bool useDefaultGridResolutions, std::vector< double > _resolutions)
 NDTMatcherD2D_2D ()
 NDTMatcherD2D_2D (const NDTMatcherD2D_2D &other)

Public Attributes

double current_resolution
double DELTA_SCORE
 the change in score after which we converge. Set to 1e-3 in constructor
double finalscore
int ITR_MAX
 max iterations, set in constructor
bool step_control
 sets step control on/off. set to true in constructor

Protected Member Functions

void computeDerivatives_2d (Eigen::Vector3d &m1, Eigen::Matrix3d C1, bool computeHessian=true)
void computeDerivativesLocal_2d (Eigen::Vector3d &m1, Eigen::Matrix3d C1, Eigen::Matrix< double, 3, 3 > &_Jest, Eigen::Matrix< double, 9, 3 > &_Hest, Eigen::Matrix< double, 3, 9 > &_Zest, Eigen::Matrix< double, 9, 9 > &_ZHest, bool computeHessian)
void init (bool _isIrregularGrid, bool useDefaultGridResolutions, std::vector< double > _resolutions)
double lineSearch2D (Eigen::Matrix< double, 3, 1 > &increment, std::vector< NDTCell< PointSource > * > &source, NDTMap< PointTarget > &target)
double normalizeAngle (double a)
virtual bool update_gradient_hessian_2d (Eigen::MatrixXd &score_gradient, Eigen::MatrixXd &Hessian, const Eigen::Vector3d &m1, const Eigen::Matrix3d &C1, const double &likelihood, bool computeHessian)
virtual bool update_gradient_hessian_local_2d (Eigen::MatrixXd &score_gradient, Eigen::MatrixXd &Hessian, const Eigen::Vector3d &m1, const Eigen::Matrix3d &C1, const double &likelihood, const Eigen::Matrix< double, 3, 3 > &_Jest, const Eigen::Matrix< double, 9, 3 > &_Hest, const Eigen::Matrix< double, 3, 9 > &_Zest, const Eigen::Matrix< double, 9, 9 > &_ZHest, bool computeHessian)

Protected Attributes

Eigen::Matrix< double, 9, 3 > Hest
bool isIrregularGrid
int iteration_counter_internal
Eigen::Matrix< double, 3, 3 > Jest
Eigen::Matrix< double, 3, 3 > JtBJ
double lfd1
double lfd2
int NUMBER_OF_ACTIVE_CELLS
int NUMBER_OF_POINTS
Eigen::Matrix< double, 3, 1 > Q
std::vector< double > resolutions
Eigen::Matrix< double, 1, 3 > TMP1
Eigen::Matrix< double, 1, 3 > xtB
Eigen::Matrix< double, 3, 3 > xtBH
Eigen::Matrix< double, 3, 1 > xtBJ
Eigen::Matrix< double, 3, 3 > xtBZBJ
Eigen::Matrix< double, 3, 1 > xtBZBx
Eigen::Matrix< double, 3, 3 > xtBZBZBx
Eigen::Matrix< double, 3, 3 > xtBZhBx
Eigen::Matrix< double, 3, 9 > Zest
Eigen::Matrix< double, 9, 9 > ZHest

Detailed Description

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

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

Definition at line 53 of file ndt_matcher_d2d_2d.h.


Constructor & Destructor Documentation

template<typename PointSource, typename PointTarget>
lslgeneric::NDTMatcherD2D_2D< PointSource, PointTarget >::NDTMatcherD2D_2D ( bool  _isIrregularGrid,
bool  useDefaultGridResolutions,
std::vector< double >  _resolutions 
) [inline]

parametrized constructor. A default set is (false,false,true,empty_vector). parameters are:

Parameters:
_isIrregularGrid--- experimental single pass through an irregular grid. also unstable
useDefaultGridResolutions--- if set, the following parameter is set to a preset value
_resolutions--- if previous bool is not set, these are the resolutions (in reverse order) that we will go through

Definition at line 62 of file ndt_matcher_d2d_2d.h.

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

Definition at line 67 of file ndt_matcher_d2d_2d.h.

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

Definition at line 71 of file ndt_matcher_d2d_2d.h.


Member Function Documentation

template<typename PointSource , typename PointTarget >
void lslgeneric::NDTMatcherD2D_2D< PointSource, PointTarget >::computeDerivatives_2d ( Eigen::Vector3d &  m1,
Eigen::Matrix3d  C1,
bool  computeHessian = true 
) [protected]

Definition at line 483 of file ndt_matcher_d2d_2d.hpp.

template<typename PointSource , typename PointTarget >
void lslgeneric::NDTMatcherD2D_2D< PointSource, PointTarget >::computeDerivativesLocal_2d ( Eigen::Vector3d &  m1,
Eigen::Matrix3d  C1,
Eigen::Matrix< double, 3, 3 > &  _Jest,
Eigen::Matrix< double, 9, 3 > &  _Hest,
Eigen::Matrix< double, 3, 9 > &  _Zest,
Eigen::Matrix< double, 9, 9 > &  _ZHest,
bool  computeHessian 
) [protected]

Definition at line 455 of file ndt_matcher_d2d_2d.hpp.

template<typename PointSource , typename PointTarget >
double lslgeneric::NDTMatcherD2D_2D< PointSource, PointTarget >::derivativesNDT_2d ( const std::vector< NDTCell< PointSource > * > &  source,
const NDTMap< PointTarget > &  target,
Eigen::MatrixXd &  score_gradient,
Eigen::MatrixXd &  Hessian,
bool  computeHessian 
) [virtual]

Definition at line 513 of file ndt_matcher_d2d_2d.hpp.

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

Definition at line 15 of file ndt_matcher_d2d_2d.hpp.

template<typename PointSource , typename PointTarget >
double lslgeneric::NDTMatcherD2D_2D< PointSource, PointTarget >::lineSearch2D ( Eigen::Matrix< double, 3, 1 > &  increment,
std::vector< NDTCell< PointSource > * > &  source,
NDTMap< PointTarget > &  target 
) [protected]

Definition at line 710 of file ndt_matcher_d2d_2d.hpp.

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

Register two point clouds. Use only 2D rotations 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 47 of file ndt_matcher_d2d_2d.hpp.

template<typename PointSource , typename PointTarget >
bool lslgeneric::NDTMatcherD2D_2D< PointSource, PointTarget >::match ( NDTMap< PointTarget > &  target,
NDTMap< PointSource > &  source,
Eigen::Transform< double, 3, Eigen::Affine, Eigen::ColMajor > &  T,
bool  useInitialGuess = false 
)

Registers a two ndt maps using only 2D rotation/translation.

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 183 of file ndt_matcher_d2d_2d.hpp.

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

Definition at line 1284 of file ndt_matcher_d2d_2d.hpp.

template<typename PointSource , typename PointTarget >
bool lslgeneric::NDTMatcherD2D_2D< PointSource, PointTarget >::update_gradient_hessian_2d ( Eigen::MatrixXd &  score_gradient,
Eigen::MatrixXd &  Hessian,
const Eigen::Vector3d &  m1,
const Eigen::Matrix3d &  C1,
const double &  likelihood,
bool  computeHessian 
) [protected, virtual]

Definition at line 405 of file ndt_matcher_d2d_2d.hpp.

template<typename PointSource , typename PointTarget >
bool lslgeneric::NDTMatcherD2D_2D< PointSource, PointTarget >::update_gradient_hessian_local_2d ( Eigen::MatrixXd &  score_gradient,
Eigen::MatrixXd &  Hessian,
const Eigen::Vector3d &  m1,
const Eigen::Matrix3d &  C1,
const double &  likelihood,
const Eigen::Matrix< double, 3, 3 > &  _Jest,
const Eigen::Matrix< double, 9, 3 > &  _Hest,
const Eigen::Matrix< double, 3, 9 > &  _Zest,
const Eigen::Matrix< double, 9, 9 > &  _ZHest,
bool  computeHessian 
) [protected, virtual]

Definition at line 343 of file ndt_matcher_d2d_2d.hpp.


Member Data Documentation

template<typename PointSource, typename PointTarget>
double lslgeneric::NDTMatcherD2D_2D< PointSource, PointTarget >::current_resolution

Definition at line 121 of file ndt_matcher_d2d_2d.h.

template<typename PointSource, typename PointTarget>
double lslgeneric::NDTMatcherD2D_2D< PointSource, PointTarget >::DELTA_SCORE

the change in score after which we converge. Set to 1e-3 in constructor

Definition at line 128 of file ndt_matcher_d2d_2d.h.

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

Definition at line 120 of file ndt_matcher_d2d_2d.h.

template<typename PointSource, typename PointTarget>
Eigen::Matrix<double,9,3> lslgeneric::NDTMatcherD2D_2D< PointSource, PointTarget >::Hest [protected]

Definition at line 132 of file ndt_matcher_d2d_2d.h.

template<typename PointSource, typename PointTarget>
bool lslgeneric::NDTMatcherD2D_2D< PointSource, PointTarget >::isIrregularGrid [protected]

Definition at line 145 of file ndt_matcher_d2d_2d.h.

template<typename PointSource, typename PointTarget>
int lslgeneric::NDTMatcherD2D_2D< PointSource, PointTarget >::iteration_counter_internal [protected]

Definition at line 144 of file ndt_matcher_d2d_2d.h.

template<typename PointSource, typename PointTarget>
int lslgeneric::NDTMatcherD2D_2D< PointSource, PointTarget >::ITR_MAX

max iterations, set in constructor

Definition at line 124 of file ndt_matcher_d2d_2d.h.

template<typename PointSource, typename PointTarget>
Eigen::Matrix<double,3,3> lslgeneric::NDTMatcherD2D_2D< PointSource, PointTarget >::Jest [protected]

Definition at line 131 of file ndt_matcher_d2d_2d.h.

template<typename PointSource, typename PointTarget>
Eigen::Matrix<double,3,3> lslgeneric::NDTMatcherD2D_2D< PointSource, PointTarget >::JtBJ [protected]

Definition at line 138 of file ndt_matcher_d2d_2d.h.

template<typename PointSource, typename PointTarget>
double lslgeneric::NDTMatcherD2D_2D< PointSource, PointTarget >::lfd1 [protected]

Definition at line 143 of file ndt_matcher_d2d_2d.h.

template<typename PointSource, typename PointTarget>
double lslgeneric::NDTMatcherD2D_2D< PointSource, PointTarget >::lfd2 [protected]

Definition at line 143 of file ndt_matcher_d2d_2d.h.

template<typename PointSource, typename PointTarget>
int lslgeneric::NDTMatcherD2D_2D< PointSource, PointTarget >::NUMBER_OF_ACTIVE_CELLS [protected]

Definition at line 141 of file ndt_matcher_d2d_2d.h.

template<typename PointSource, typename PointTarget>
int lslgeneric::NDTMatcherD2D_2D< PointSource, PointTarget >::NUMBER_OF_POINTS [protected]

Definition at line 142 of file ndt_matcher_d2d_2d.h.

template<typename PointSource, typename PointTarget>
Eigen::Matrix<double,3,1> lslgeneric::NDTMatcherD2D_2D< PointSource, PointTarget >::Q [protected]

Definition at line 136 of file ndt_matcher_d2d_2d.h.

template<typename PointSource, typename PointTarget>
std::vector<double> lslgeneric::NDTMatcherD2D_2D< PointSource, PointTarget >::resolutions [protected]

Definition at line 146 of file ndt_matcher_d2d_2d.h.

template<typename PointSource, typename PointTarget>
bool lslgeneric::NDTMatcherD2D_2D< PointSource, PointTarget >::step_control

sets step control on/off. set to true in constructor

Definition at line 126 of file ndt_matcher_d2d_2d.h.

template<typename PointSource, typename PointTarget>
Eigen::Matrix<double,1,3> lslgeneric::NDTMatcherD2D_2D< PointSource, PointTarget >::TMP1 [protected]

Definition at line 139 of file ndt_matcher_d2d_2d.h.

template<typename PointSource, typename PointTarget>
Eigen::Matrix<double,1,3> lslgeneric::NDTMatcherD2D_2D< PointSource, PointTarget >::xtB [protected]

Definition at line 139 of file ndt_matcher_d2d_2d.h.

template<typename PointSource, typename PointTarget>
Eigen::Matrix<double,3,3> lslgeneric::NDTMatcherD2D_2D< PointSource, PointTarget >::xtBH [protected]

Definition at line 138 of file ndt_matcher_d2d_2d.h.

template<typename PointSource, typename PointTarget>
Eigen::Matrix<double,3,1> lslgeneric::NDTMatcherD2D_2D< PointSource, PointTarget >::xtBJ [protected]

Definition at line 136 of file ndt_matcher_d2d_2d.h.

template<typename PointSource, typename PointTarget>
Eigen::Matrix<double,3,3> lslgeneric::NDTMatcherD2D_2D< PointSource, PointTarget >::xtBZBJ [protected]

Definition at line 138 of file ndt_matcher_d2d_2d.h.

template<typename PointSource, typename PointTarget>
Eigen::Matrix<double,3,1> lslgeneric::NDTMatcherD2D_2D< PointSource, PointTarget >::xtBZBx [protected]

Definition at line 136 of file ndt_matcher_d2d_2d.h.

template<typename PointSource, typename PointTarget>
Eigen::Matrix<double,3,3> lslgeneric::NDTMatcherD2D_2D< PointSource, PointTarget >::xtBZBZBx [protected]

Definition at line 138 of file ndt_matcher_d2d_2d.h.

template<typename PointSource, typename PointTarget>
Eigen::Matrix<double,3,3> lslgeneric::NDTMatcherD2D_2D< PointSource, PointTarget >::xtBZhBx [protected]

Definition at line 138 of file ndt_matcher_d2d_2d.h.

template<typename PointSource, typename PointTarget>
Eigen::Matrix<double,3,9> lslgeneric::NDTMatcherD2D_2D< PointSource, PointTarget >::Zest [protected]

Definition at line 133 of file ndt_matcher_d2d_2d.h.

template<typename PointSource, typename PointTarget>
Eigen::Matrix<double,9,9> lslgeneric::NDTMatcherD2D_2D< PointSource, PointTarget >::ZHest [protected]

Definition at line 134 of file ndt_matcher_d2d_2d.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