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_HH
00036 #define NDT_MATCHER_D2D_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 class NDTMatcherD2D
00053 {
00054 public:
00061 NDTMatcherD2D(bool _isIrregularGrid,
00062 bool useDefaultGridResolutions, std::vector<double> _resolutions)
00063 {
00064 this->init(_isIrregularGrid,useDefaultGridResolutions,_resolutions);
00065 }
00066 NDTMatcherD2D()
00067 {
00068 this->init(false,true,std::vector<double>());
00069 }
00070 NDTMatcherD2D(const NDTMatcherD2D& other)
00071 {
00072 this->init(other.isIrregularGrid,false,other.resolutions);
00073 }
00074
00088 bool match( pcl::PointCloud<pcl::PointXYZ>& target,
00089 pcl::PointCloud<pcl::PointXYZ>& source,
00090 Eigen::Transform<double,3,Eigen::Affine,Eigen::ColMajor>& T,
00091 bool useInitialGuess = false);
00092
00104 bool match( NDTMap& target,
00105 NDTMap& source,
00106 Eigen::Transform<double,3,Eigen::Affine,Eigen::ColMajor>& T,
00107 bool useInitialGuess = false);
00108
00114 bool covariance( pcl::PointCloud<pcl::PointXYZ>& target,
00115 pcl::PointCloud<pcl::PointXYZ>& source,
00116 Eigen::Transform<double,3,Eigen::Affine,Eigen::ColMajor>& T,
00117 Eigen::MatrixXd &cov
00118 );
00119
00124 bool covariance( NDTMap& target,
00125 NDTMap& source,
00126 Eigen::Transform<double,3,Eigen::Affine,Eigen::ColMajor>& T,
00127 Eigen::MatrixXd &cov
00128 );
00129
00130
00131 virtual double scoreNDT(std::vector<NDTCell*> &source, NDTMap &target);
00132
00133 virtual double scoreNDT_OM(NDTMap &source, NDTMap &target);
00134
00135
00136 virtual double scoreNDTPositive(std::vector<NDTCell*> &sourceNDT, NDTMap &targetNDT,
00137 Eigen::Transform<double,3,Eigen::Affine,Eigen::ColMajor>& T);
00138
00139
00140
00141
00142 virtual double derivativesNDT(
00143 const std::vector<NDTCell*> &source,
00144 const NDTMap &target,
00145 Eigen::MatrixXd &score_gradient,
00146 Eigen::MatrixXd &Hessian,
00147 bool computeHessian
00148 );
00149
00150
00151
00152
00153 double finalscore;
00154 double current_resolution;
00156 int ITR_MAX;
00158 bool step_control;
00160 double DELTA_SCORE;
00161
00162
00163 bool regularize;
00164
00165 int n_neighbours;
00166 protected:
00167
00168 Eigen::Matrix<double,3,6> Jest;
00169 Eigen::Matrix<double,18,6> Hest;
00170 Eigen::Matrix<double,3,18> Zest;
00171 Eigen::Matrix<double,18,18> ZHest;
00172
00173 Eigen::Matrix<double,3,3> dRdx, dRdy, dRdz;
00174 Eigen::Matrix<double,3,3> dRdxdx, dRdxdy, dRdxdz, dRdydy, dRdydz, dRdzdz;
00175
00176 double lfd1,lfd2;
00177
00178 int iteration_counter_internal;
00179
00180 bool isIrregularGrid;
00181 std::vector<double> resolutions;
00182
00183
00184 void init(bool _isIrregularGrid,
00185 bool useDefaultGridResolutions, std::vector<double> _resolutions);
00186
00187
00188 virtual bool update_gradient_hessian(
00189 Eigen::MatrixXd &score_gradient,
00190 Eigen::MatrixXd &Hessian,
00191 const Eigen::Vector3d &m1,
00192 const Eigen::Matrix3d &C1,
00193 const double &likelihood,
00194 bool computeHessian);
00195
00196
00197 void computeDerivatives(Eigen::Vector3d &m1, Eigen::Matrix3d C1, bool computeHessian=true);
00198
00199
00200 virtual bool update_gradient_hessian_local(
00201 Eigen::MatrixXd &score_gradient,
00202 Eigen::MatrixXd &Hessian,
00203 const Eigen::Vector3d &m1,
00204 const Eigen::Matrix3d &C1,
00205 const double &likelihood,
00206 const Eigen::Matrix<double,3,6> &_Jest,
00207 const Eigen::Matrix<double,18,6> &_Hest,
00208 const Eigen::Matrix<double,3,18> &_Zest,
00209 const Eigen::Matrix<double,18,18> &_ZHest,
00210 bool computeHessian);
00211
00212
00213 void computeDerivativesLocal(Eigen::Vector3d &m1, Eigen::Matrix3d C1,
00214 Eigen::Matrix<double,3,6> &_Jest,
00215 Eigen::Matrix<double,18,6> &_Hest,
00216 Eigen::Matrix<double,3,18> &_Zest,
00217 Eigen::Matrix<double,18,18> &_ZHest,
00218 bool computeHessian);
00219
00220
00221
00222 double lineSearchMT(
00223 Eigen::Matrix<double,6,1> &increment,
00224 std::vector<NDTCell*> &source,
00225 NDTMap &target) ;
00226
00227
00228 struct MoreThuente
00229 {
00230 static double min(double a, double b);
00231 static double max(double a, double b);
00232 static double absmax(double a, double b, double c);
00233 static int cstep(double& stx, double& fx, double& dx,
00234 double& sty, double& fy, double& dy,
00235 double& stp, double& fp, double& dp,
00236 bool& brackt, double stmin, double stmax);
00237 };
00238
00239
00240 int NUMBER_OF_POINTS;
00241
00242
00243
00244
00245
00246
00247
00248
00249
00250
00251 protected:
00252
00253
00254
00255 int NUMBER_OF_ACTIVE_CELLS;
00256 double normalizeAngle(double a);
00257
00258
00259 Eigen::Matrix<double,6,1> xtBJ, xtBZBx, Q;
00260
00261 Eigen::Matrix<double,6,6> JtBJ, xtBZBJ, xtBH, xtBZBZBx, xtBZhBx;
00262 Eigen::Matrix<double,1,3> TMP1, xtB;
00263
00264 public:
00265 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00266 };
00267
00268 }
00269
00270
00271 #endif