00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035 #ifndef NDT_MATCHER_D2D_2D_HH
00036 #define NDT_MATCHER_D2D_2D_HH
00037
00038 #include <ndt_map/ndt_map.h>
00039 #include "pcl/point_cloud.h"
00040 #include "Eigen/Core"
00041
00042 #include <stdlib.h>
00043 #include <stdio.h>
00044 #include <math.h>
00045
00046 namespace lslgeneric
00047 {
00048
00052 template <typename PointSource, typename PointTarget>
00053 class NDTMatcherD2D_2D
00054 {
00055 public:
00062 NDTMatcherD2D_2D(bool _isIrregularGrid,
00063 bool useDefaultGridResolutions, std::vector<double> _resolutions)
00064 {
00065 this->init(_isIrregularGrid,useDefaultGridResolutions,_resolutions);
00066 }
00067 NDTMatcherD2D_2D()
00068 {
00069 this->init(false,true,std::vector<double>());
00070 }
00071 NDTMatcherD2D_2D(const NDTMatcherD2D_2D& other)
00072 {
00073 this->init(other.isIrregularGrid,false,other.resolutions);
00074 }
00075
00089 bool match( pcl::PointCloud<PointTarget>& target,
00090 pcl::PointCloud<PointSource>& source,
00091 Eigen::Transform<double,3,Eigen::Affine,Eigen::ColMajor>& T,
00092 bool useInitialGuess = false);
00093
00105 bool match( NDTMap<PointTarget>& target,
00106 NDTMap<PointSource>& source,
00107 Eigen::Transform<double,3,Eigen::Affine,Eigen::ColMajor>& T,
00108 bool useInitialGuess = false);
00109
00110
00111
00112
00113 virtual double derivativesNDT_2d(
00114 const std::vector<NDTCell<PointSource>*> &source,
00115 const NDTMap<PointTarget> &target,
00116 Eigen::MatrixXd &score_gradient,
00117 Eigen::MatrixXd &Hessian,
00118 bool computeHessian
00119 );
00120 double finalscore;
00121 double current_resolution;
00122
00124 int ITR_MAX;
00126 bool step_control;
00128 double DELTA_SCORE;
00129 protected:
00130
00131 Eigen::Matrix<double,3,3> Jest;
00132 Eigen::Matrix<double,9,3> Hest;
00133 Eigen::Matrix<double,3,9> Zest;
00134 Eigen::Matrix<double,9,9> ZHest;
00135
00136 Eigen::Matrix<double,3,1> xtBJ, xtBZBx, Q;
00137
00138 Eigen::Matrix<double,3,3> JtBJ, xtBZBJ, xtBH, xtBZBZBx, xtBZhBx;
00139 Eigen::Matrix<double,1,3> TMP1, xtB;
00140
00141 int NUMBER_OF_ACTIVE_CELLS;
00142 int NUMBER_OF_POINTS;
00143 double lfd1,lfd2;
00144 int iteration_counter_internal;
00145 bool isIrregularGrid;
00146 std::vector<double> resolutions;
00147
00148 double normalizeAngle(double a);
00149
00150 void init(bool _isIrregularGrid,
00151 bool useDefaultGridResolutions, std::vector<double> _resolutions);
00152
00153
00154 virtual bool update_gradient_hessian_2d(
00155 Eigen::MatrixXd &score_gradient,
00156 Eigen::MatrixXd &Hessian,
00157 const Eigen::Vector3d &m1,
00158 const Eigen::Matrix3d &C1,
00159 const double &likelihood,
00160 bool computeHessian);
00161
00162
00163 void computeDerivatives_2d(Eigen::Vector3d &m1, Eigen::Matrix3d C1, bool computeHessian=true);
00164
00165
00166 virtual bool update_gradient_hessian_local_2d(
00167 Eigen::MatrixXd &score_gradient,
00168 Eigen::MatrixXd &Hessian,
00169 const Eigen::Vector3d &m1,
00170 const Eigen::Matrix3d &C1,
00171 const double &likelihood,
00172 const Eigen::Matrix<double,3,3> &_Jest,
00173 const Eigen::Matrix<double,9,3> &_Hest,
00174 const Eigen::Matrix<double,3,9> &_Zest,
00175 const Eigen::Matrix<double,9,9> &_ZHest,
00176 bool computeHessian);
00177
00178
00179 void computeDerivativesLocal_2d(Eigen::Vector3d &m1, Eigen::Matrix3d C1,
00180 Eigen::Matrix<double,3,3> &_Jest,
00181 Eigen::Matrix<double,9,3> &_Hest,
00182 Eigen::Matrix<double,3,9> &_Zest,
00183 Eigen::Matrix<double,9,9> &_ZHest,
00184 bool computeHessian);
00185
00186
00187
00188 double lineSearch2D(
00189 Eigen::Matrix<double,3,1> &increment,
00190 std::vector<NDTCell<PointSource>*> &source,
00191 NDTMap<PointTarget> &target) ;
00192
00193
00194 struct MoreThuente
00195 {
00196 static double min(double a, double b);
00197 static double max(double a, double b);
00198 static double absmax(double a, double b, double c);
00199 static int cstep(double& stx, double& fx, double& dx,
00200 double& sty, double& fy, double& dy,
00201 double& stp, double& fp, double& dp,
00202 bool& brackt, double stmin, double stmax);
00203 };
00204
00205
00206 public:
00207 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00208 };
00209
00210 }
00211
00212 #include <ndt_registration/impl/ndt_matcher_d2d_2d.hpp>
00213 #endif