#include <ndt_matcher_d2d_2d.h>
Classes | |
struct | MoreThuente |
Public Member Functions | |
virtual double | derivativesNDT_2d (const std::vector< NDTCell * > &source, const NDTMap &target, Eigen::MatrixXd &score_gradient, Eigen::MatrixXd &Hessian, bool computeHessian) |
bool | match (pcl::PointCloud< pcl::PointXYZ > &target, pcl::PointCloud< pcl::PointXYZ > &source, Eigen::Transform< double, 3, Eigen::Affine, Eigen::ColMajor > &T, bool useInitialGuess=false) |
bool | match (NDTMap &target, NDTMap &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 * > &source, NDTMap &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 |
This class implements NDT registration for 3D point cloud scans.
Definition at line 52 of file ndt_matcher_d2d_2d.h.
lslgeneric::NDTMatcherD2D_2D::NDTMatcherD2D_2D | ( | bool | _isIrregularGrid, |
bool | useDefaultGridResolutions, | ||
std::vector< double > | _resolutions | ||
) | [inline] |
parametrized constructor. A default set is (false,false,true,empty_vector). parameters are:
_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 61 of file ndt_matcher_d2d_2d.h.
lslgeneric::NDTMatcherD2D_2D::NDTMatcherD2D_2D | ( | ) | [inline] |
Definition at line 66 of file ndt_matcher_d2d_2d.h.
lslgeneric::NDTMatcherD2D_2D::NDTMatcherD2D_2D | ( | const NDTMatcherD2D_2D & | other | ) | [inline] |
Definition at line 70 of file ndt_matcher_d2d_2d.h.
void lslgeneric::NDTMatcherD2D_2D::computeDerivatives_2d | ( | Eigen::Vector3d & | m1, |
Eigen::Matrix3d | C1, | ||
bool | computeHessian = true |
||
) | [protected] |
Definition at line 441 of file ndt_matcher_d2d_2d.cpp.
void lslgeneric::NDTMatcherD2D_2D::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 414 of file ndt_matcher_d2d_2d.cpp.
double lslgeneric::NDTMatcherD2D_2D::derivativesNDT_2d | ( | const std::vector< NDTCell * > & | source, |
const NDTMap & | target, | ||
Eigen::MatrixXd & | score_gradient, | ||
Eigen::MatrixXd & | Hessian, | ||
bool | computeHessian | ||
) | [virtual] |
Definition at line 470 of file ndt_matcher_d2d_2d.cpp.
void lslgeneric::NDTMatcherD2D_2D::init | ( | bool | _isIrregularGrid, |
bool | useDefaultGridResolutions, | ||
std::vector< double > | _resolutions | ||
) | [protected] |
Definition at line 14 of file ndt_matcher_d2d_2d.cpp.
double lslgeneric::NDTMatcherD2D_2D::lineSearch2D | ( | Eigen::Matrix< double, 3, 1 > & | increment, |
std::vector< NDTCell * > & | source, | ||
NDTMap & | target | ||
) | [protected] |
Definition at line 666 of file ndt_matcher_d2d_2d.cpp.
bool lslgeneric::NDTMatcherD2D_2D::match | ( | pcl::PointCloud< pcl::PointXYZ > & | target, |
pcl::PointCloud< pcl::PointXYZ > & | 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.
fixed | Reference data. NDT structure is built for this point cloud. |
moving | The output transformation registers this point cloud to fixed . |
T | This 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 45 of file ndt_matcher_d2d_2d.cpp.
bool lslgeneric::NDTMatcherD2D_2D::match | ( | NDTMap & | target, |
NDTMap & | source, | ||
Eigen::Transform< double, 3, Eigen::Affine, Eigen::ColMajor > & | T, | ||
bool | useInitialGuess = false |
||
) |
Registers a two ndt maps using only 2D rotation/translation.
fixed | Reference data. |
moving | The output transformation registers this point cloud to fixed . |
T | This 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 145 of file ndt_matcher_d2d_2d.cpp.
double lslgeneric::NDTMatcherD2D_2D::normalizeAngle | ( | double | a | ) | [protected] |
Definition at line 1235 of file ndt_matcher_d2d_2d.cpp.
bool lslgeneric::NDTMatcherD2D_2D::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 365 of file ndt_matcher_d2d_2d.cpp.
bool lslgeneric::NDTMatcherD2D_2D::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 304 of file ndt_matcher_d2d_2d.cpp.
Definition at line 120 of file ndt_matcher_d2d_2d.h.
the change in score after which we converge. Set to 1e-3 in constructor
Definition at line 127 of file ndt_matcher_d2d_2d.h.
Definition at line 119 of file ndt_matcher_d2d_2d.h.
Eigen::Matrix<double,9,3> lslgeneric::NDTMatcherD2D_2D::Hest [protected] |
Definition at line 131 of file ndt_matcher_d2d_2d.h.
bool lslgeneric::NDTMatcherD2D_2D::isIrregularGrid [protected] |
Definition at line 144 of file ndt_matcher_d2d_2d.h.
int lslgeneric::NDTMatcherD2D_2D::iteration_counter_internal [protected] |
Definition at line 143 of file ndt_matcher_d2d_2d.h.
max iterations, set in constructor
Definition at line 123 of file ndt_matcher_d2d_2d.h.
Eigen::Matrix<double,3,3> lslgeneric::NDTMatcherD2D_2D::Jest [protected] |
Definition at line 130 of file ndt_matcher_d2d_2d.h.
Eigen::Matrix<double,3,3> lslgeneric::NDTMatcherD2D_2D::JtBJ [protected] |
Definition at line 137 of file ndt_matcher_d2d_2d.h.
double lslgeneric::NDTMatcherD2D_2D::lfd1 [protected] |
Definition at line 142 of file ndt_matcher_d2d_2d.h.
double lslgeneric::NDTMatcherD2D_2D::lfd2 [protected] |
Definition at line 142 of file ndt_matcher_d2d_2d.h.
int lslgeneric::NDTMatcherD2D_2D::NUMBER_OF_ACTIVE_CELLS [protected] |
Definition at line 140 of file ndt_matcher_d2d_2d.h.
int lslgeneric::NDTMatcherD2D_2D::NUMBER_OF_POINTS [protected] |
Definition at line 141 of file ndt_matcher_d2d_2d.h.
Eigen::Matrix<double,3,1> lslgeneric::NDTMatcherD2D_2D::Q [protected] |
Definition at line 135 of file ndt_matcher_d2d_2d.h.
std::vector<double> lslgeneric::NDTMatcherD2D_2D::resolutions [protected] |
Definition at line 145 of file ndt_matcher_d2d_2d.h.
sets step control on/off. set to true in constructor
Definition at line 125 of file ndt_matcher_d2d_2d.h.
Eigen::Matrix<double,1,3> lslgeneric::NDTMatcherD2D_2D::TMP1 [protected] |
Definition at line 138 of file ndt_matcher_d2d_2d.h.
Eigen::Matrix<double,1,3> lslgeneric::NDTMatcherD2D_2D::xtB [protected] |
Definition at line 138 of file ndt_matcher_d2d_2d.h.
Eigen::Matrix<double,3,3> lslgeneric::NDTMatcherD2D_2D::xtBH [protected] |
Definition at line 137 of file ndt_matcher_d2d_2d.h.
Eigen::Matrix<double,3,1> lslgeneric::NDTMatcherD2D_2D::xtBJ [protected] |
Definition at line 135 of file ndt_matcher_d2d_2d.h.
Eigen::Matrix<double,3,3> lslgeneric::NDTMatcherD2D_2D::xtBZBJ [protected] |
Definition at line 137 of file ndt_matcher_d2d_2d.h.
Eigen::Matrix<double,3,1> lslgeneric::NDTMatcherD2D_2D::xtBZBx [protected] |
Definition at line 135 of file ndt_matcher_d2d_2d.h.
Eigen::Matrix<double,3,3> lslgeneric::NDTMatcherD2D_2D::xtBZBZBx [protected] |
Definition at line 137 of file ndt_matcher_d2d_2d.h.
Eigen::Matrix<double,3,3> lslgeneric::NDTMatcherD2D_2D::xtBZhBx [protected] |
Definition at line 137 of file ndt_matcher_d2d_2d.h.
Eigen::Matrix<double,3,9> lslgeneric::NDTMatcherD2D_2D::Zest [protected] |
Definition at line 132 of file ndt_matcher_d2d_2d.h.
Eigen::Matrix<double,9,9> lslgeneric::NDTMatcherD2D_2D::ZHest [protected] |
Definition at line 133 of file ndt_matcher_d2d_2d.h.