ndt_matcher_d2d_2d.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_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 class NDTMatcherD2D_2D
00053 {
00054 public:
00061     NDTMatcherD2D_2D(bool _isIrregularGrid,
00062                   bool useDefaultGridResolutions, std::vector<double> _resolutions)
00063     {
00064         this->init(_isIrregularGrid,useDefaultGridResolutions,_resolutions);
00065     }
00066     NDTMatcherD2D_2D()
00067     {
00068         this->init(false,true,std::vector<double>());
00069     }
00070     NDTMatcherD2D_2D(const NDTMatcherD2D_2D& 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 
00109     //compute the score gradient & hessian of a point cloud + transformation to an NDT (assuming a 2D transformation)
00110     // input: moving, fixed, tr, computeHessian
00111     //output: score_gradient, Hessian, returns: score!
00112     virtual double derivativesNDT_2d(
00113         const std::vector<NDTCell*> &source,
00114         const NDTMap &target,
00115         Eigen::MatrixXd &score_gradient,
00116         Eigen::MatrixXd &Hessian,
00117         bool computeHessian
00118     );
00119     double finalscore;
00120     double current_resolution;
00121     
00123     int ITR_MAX;
00125     bool step_control;
00127     double DELTA_SCORE;
00128 protected:
00129 
00130     Eigen::Matrix<double,3,3> Jest;
00131     Eigen::Matrix<double,9,3> Hest;
00132     Eigen::Matrix<double,3,9> Zest;
00133     Eigen::Matrix<double,9,9> ZHest;
00134     //vars for gradient
00135     Eigen::Matrix<double,3,1> xtBJ, xtBZBx, Q;
00136     //vars for hessian
00137     Eigen::Matrix<double,3,3> JtBJ, xtBZBJ, xtBH, xtBZBZBx, xtBZhBx;
00138     Eigen::Matrix<double,1,3> TMP1, xtB;
00139 
00140     int NUMBER_OF_ACTIVE_CELLS;
00141     int NUMBER_OF_POINTS;
00142     double lfd1,lfd2;
00143     int iteration_counter_internal;
00144     bool isIrregularGrid;
00145     std::vector<double> resolutions;
00146 
00147     double normalizeAngle(double a);
00148     //initializes stuff;
00149     void init(bool _isIrregularGrid,
00150               bool useDefaultGridResolutions, std::vector<double> _resolutions);
00151 
00152     //iteratively update the score gradient and hessian
00153     virtual bool update_gradient_hessian_2d(
00154         Eigen::MatrixXd &score_gradient,
00155         Eigen::MatrixXd &Hessian,
00156         const Eigen::Vector3d &m1,
00157         const Eigen::Matrix3d &C1,
00158         const double &likelihood,
00159         bool computeHessian);
00160 
00161     //pre-computes the derivative matrices Jest, Hest, Zest, ZHest
00162     void computeDerivatives_2d(Eigen::Vector3d &m1, Eigen::Matrix3d C1, bool computeHessian=true);
00163 
00164     //iteratively update the score gradient and hessian (2d version)
00165     virtual bool update_gradient_hessian_local_2d(
00166         Eigen::MatrixXd &score_gradient,
00167         Eigen::MatrixXd &Hessian,
00168         const Eigen::Vector3d &m1,
00169         const Eigen::Matrix3d &C1,
00170         const double &likelihood,
00171         const Eigen::Matrix<double,3,3> &_Jest,
00172         const Eigen::Matrix<double,9,3> &_Hest,
00173         const Eigen::Matrix<double,3,9> &_Zest,
00174         const Eigen::Matrix<double,9,9> &_ZHest,
00175         bool computeHessian);
00176 
00177     //pre-computes the derivative matrices Jest, Hest, Zest, ZHest
00178     void computeDerivativesLocal_2d(Eigen::Vector3d &m1, Eigen::Matrix3d C1,
00179                                  Eigen::Matrix<double,3,3> &_Jest,
00180                                  Eigen::Matrix<double,9,3> &_Hest,
00181                                  Eigen::Matrix<double,3,9> &_Zest,
00182                                  Eigen::Matrix<double,9,9> &_ZHest,
00183                                  bool computeHessian);
00184 
00185     //perform line search to find the best descent rate (Mohre&Thuente)
00186     //adapted from NOX
00187     double lineSearch2D(
00188         Eigen::Matrix<double,3,1> &increment,
00189         std::vector<NDTCell*> &source,
00190         NDTMap &target) ;
00191 
00192     //auxiliary functions for MoreThuente line search
00193     struct MoreThuente
00194     {
00195         static double min(double a, double b);
00196         static double max(double a, double b);
00197         static double absmax(double a, double b, double c);
00198         static int cstep(double& stx, double& fx, double& dx,
00199                          double& sty, double& fy, double& dy,
00200                          double& stp, double& fp, double& dp,
00201                          bool& brackt, double stmin, double stmax);
00202     }; //end MoreThuente
00203     //perform a subsampling depending on user choice
00204 
00205 public:
00206     EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00207 };
00208 
00209 } // end namespace
00210 
00211 #endif


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