ndt_matcher_d2d.h
Go to the documentation of this file.
00001 /*
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2010, AASS Research Center, Orebro University.
00005  *  All rights reserved.
00006  *
00007  *  Redistribution and use in source and binary forms, with or without
00008  *  modification, are permitted provided that the following conditions
00009  *  are met:
00010  *
00011  *   * Redistributions of source code must retain the above copyright
00012  *     notice, this list of conditions and the following disclaimer.
00013  *   * Redistributions in binary form must reproduce the above
00014  *     copyright notice, this list of conditions and the following
00015  *     disclaimer in the documentation and/or other materials provided
00016  *     with the distribution.
00017  *   * Neither the name of AASS Research Center nor the names of its
00018  *     contributors may be used to endorse or promote products derived
00019  *     from this software without specific prior written permission.
00020  *
00021  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032  *  POSSIBILITY OF SUCH DAMAGE.
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     //compute the score of a point cloud to an NDT //UNUSED
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     //compute the score gradient & hessian of a point cloud + transformation to an NDT
00140     // input: moving, fixed, tr, computeHessian
00141     //output: score_gradient, Hessian, returns: score!
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         void generateScoreDebug(const char* out, pcl::PointCloud<pcl::PointXYZ>& fixed,
00151                             pcl::PointCloud<pcl::PointXYZ>& moving);
00152     */
00153     double finalscore;
00154     double current_resolution;
00156     int ITR_MAX;
00158     bool step_control;
00160     double DELTA_SCORE;
00161 
00162     //should we try to regularize the hessian or just give up?
00163     bool regularize;
00164     //how many neighbours to use in the objective
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     //lf = likelihood function d1 and d2 from the paper
00176     double lfd1,lfd2;
00177     //bool useSimpleDerivatives;
00178     int iteration_counter_internal;
00179 
00180     bool isIrregularGrid;
00181     std::vector<double> resolutions;
00182 
00183     //initializes stuff;
00184     void init(bool _isIrregularGrid,
00185               bool useDefaultGridResolutions, std::vector<double> _resolutions);
00186 
00187     //iteratively update the score gradient and hessian
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     //pre-computes the derivative matrices Jest, Hest, Zest, ZHest
00197     void computeDerivatives(Eigen::Vector3d &m1, Eigen::Matrix3d C1, bool computeHessian=true);
00198 
00199     //iteratively update the score gradient and hessian
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     //pre-computes the derivative matrices Jest, Hest, Zest, ZHest
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     //perform line search to find the best descent rate (Mohre&Thuente)
00221     //adapted from NOX
00222     double lineSearchMT(
00223         Eigen::Matrix<double,6,1> &increment,
00224         std::vector<NDTCell*> &source,
00225         NDTMap &target) ;
00226 
00227     //auxiliary functions for MoreThuente line search
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     }; //end MoreThuente
00238 
00239     //perform a subsampling depending on user choice
00240     int NUMBER_OF_POINTS;
00241     /*
00242     void gradient_numeric(
00243         std::vector<NDTCell*> &moving,
00244         NDTMap &fixed,
00245         Eigen::Transform<double,3,Eigen::Affine,Eigen::ColMajor> &transform,
00246         //Eigen::Vector3d &eulerAngles,
00247         Eigen::Matrix<double,6,1> &score_gradient
00248         );
00249     */
00250 
00251 protected:
00252     //storage for pre-computed angular derivatives
00253     //Eigen::Vector3d jest13, jest23, jest04, jest14, jest24, jest05, jest15, jest25;
00254     //Eigen::Vector3d a2,a3, b2,b3, c2,c3, d1,d2,d3, e1,e2,e3, f1,f2,f3;
00255     int NUMBER_OF_ACTIVE_CELLS;
00256     double normalizeAngle(double a);
00257 
00258     //vars for gradient
00259     Eigen::Matrix<double,6,1> xtBJ, xtBZBx, Q;
00260     //vars for hessian
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 } // end namespace
00269 
00270 //#include <ndt_registration/impl/ndt_matcher_d2d.hpp>
00271 #endif


ndt_registration
Author(s): Todor Stoyanov, Jari Saarinen, Henrik Andreasson
autogenerated on Wed Aug 26 2015 15:24:52