ndt_matcher_p2d.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_HH
00036 #define NDT_MATCHER_HH
00037 
00038 #include "ndt_map/ndt_map.h"
00039 #include "ndt_map/pointcloud_utils.h"
00040 #include "pcl/point_cloud.h"
00041 #include "Eigen/Core"
00042 
00043 namespace lslgeneric
00044 {
00045 
00049 class NDTMatcherP2D
00050 {
00051 public:
00052     NDTMatcherP2D(std::vector<double> _resolutions)
00053     {
00054         this->init(false,_resolutions);
00055     }
00056     NDTMatcherP2D()
00057     {
00058         this->init(true,std::vector<double>());
00059     }
00060     NDTMatcherP2D(const NDTMatcherP2D& other)
00061     {
00062         this->init(false,other.resolutions);
00063     }
00064 
00082     bool match( pcl::PointCloud<pcl::PointXYZ>& target,
00083                 pcl::PointCloud<pcl::PointXYZ>& source,
00084                 Eigen::Transform<double,3,Eigen::Affine,Eigen::ColMajor>& T );
00085 
00086 
00098   void check( pcl::PointCloud<pcl::PointXYZ>& fixed,
00099               pcl::PointCloud<pcl::PointXYZ>& moving,
00100               Eigen::Transform<double,3,Eigen::Affine,Eigen::ColMajor>& T
00101               //= Eigen::Translation3f( 0.0, 0.0, 0.0 ) * Eigen::AngleAxisf( 0.0, Eigen::Vector3d( 1.0, 0.0, 0.0 ) )
00102               );
00103   
00104   
00120     bool match( NDTMap& target,
00121                 pcl::PointCloud<pcl::PointXYZ>& source,
00122                 Eigen::Transform<double,3,Eigen::Affine,Eigen::ColMajor>& T );
00123 
00124 
00125 
00126   
00132     bool covariance( pcl::PointCloud<pcl::PointXYZ>& target,
00133                      pcl::PointCloud<pcl::PointXYZ>& source,
00134                      Eigen::Transform<double,3,Eigen::Affine,Eigen::ColMajor>& T,
00135                      Eigen::Matrix<double,6,6> &cov
00136                    );
00137 
00138     //compute the score of a point cloud to an NDT
00139     double scorePointCloud(pcl::PointCloud<pcl::PointXYZ> &source,
00140                            NDTMap &target);
00141 
00142     //compute the score gradient & hessian of a point cloud + transformation to an NDT
00143     // input: moving, fixed, tr, computeHessian
00144     //output: score_gradient, Hessian
00145     void derivativesPointCloud(pcl::PointCloud<pcl::PointXYZ> &source,
00146                                NDTMap &target,
00147                                Eigen::Transform<double,3,Eigen::Affine,Eigen::ColMajor> &transform,
00148                                Eigen::Matrix<double,6,1> &score_gradient,
00149                                Eigen::Matrix<double,6,6> &Hessian,
00150                                bool computeHessian);
00151 
00152     void generateScoreDebug(const char* out, pcl::PointCloud<pcl::PointXYZ>& target,
00153                             pcl::PointCloud<pcl::PointXYZ>& source);
00154 
00155     double finalscore;
00156 private:
00157 
00158     Eigen::Matrix<double,3,6> Jest;
00159     Eigen::Matrix<double,18,6> Hest;
00160     //lf = likelihood function d1 and d2 from the paper
00161     double lfd1,lfd2;
00162     bool useSimpleDerivatives;
00163     double current_resolution;
00164     bool isIrregularGrid;
00165 
00166     //pre-computes the multipliers of the derivatives for all points
00167     void precomputeAngleDerivatives(Eigen::Vector3d &eulerAngles);
00168 
00169     //iteratively update the score gradient
00170     bool update_score_gradient(Eigen::Matrix<double,6,1> &score_gradient,
00171                                Eigen::Vector3d &transformed,
00172                                Eigen::Matrix3d &Cinv);
00173     //iteratively update the hessian matrix
00174     void update_hessian(Eigen::Matrix<double,6,6> &Hessian,
00175                         Eigen::Vector3d &transformed,
00176                         Eigen::Matrix3d &Cinv);
00177 
00178     //pre-computes the derivative matrices Jest and Hest
00179     void computeDerivatives(pcl::PointXYZ &pt);
00180 
00181     //perform line search to find the best descent rate (naive case)
00182     double lineSearch(double score_here,
00183                       Eigen::Matrix<double,6,1> &score_gradient,
00184                       Eigen::Matrix<double,6,1> &increment,
00185                       pcl::PointCloud<pcl::PointXYZ> &source,
00186                       NDTMap &target) ;
00187 
00188     //perform line search to find the best descent rate (Mohre&Thuente)
00189     //adapted from NOX
00190     double lineSearchMT( Eigen::Matrix<double,6,1> &score_gradient_init,
00191                          Eigen::Matrix<double,6,1> &increment,
00192                          pcl::PointCloud<pcl::PointXYZ> &source,
00193                          Eigen::Transform<double,3,Eigen::Affine,Eigen::ColMajor> &globalT,
00194                          NDTMap &target) ;
00195 
00196     //compute finited difference derivative, for debug
00197     /*
00198         void fdd(pcl::PointCloud<PointSource> &source,
00199              NDTMap<PointTarget> &target,
00200              Eigen::Matrix<double,6,1> &score_gradient);
00201     */
00202 
00203     //auxiliary functions for MoreThuente line search
00204     struct MoreThuente
00205     {
00206         static double min(double a, double b);
00207         static double max(double a, double b);
00208         static double absmax(double a, double b, double c);
00209         static int cstep(double& stx, double& fx, double& dx,
00210                          double& sty, double& fy, double& dy,
00211                          double& stp, double& fp, double& dp,
00212                          bool& brackt, double stmin, double stmax);
00213     }; //end MoreThuente
00214 
00215     //perform a subsampling depending on user choice
00216     pcl::PointCloud<pcl::PointXYZ> subsample(pcl::PointCloud<pcl::PointXYZ>& original);
00217     int NUMBER_OF_POINTS;
00218     int NUMBER_OF_ACTIVE_CELLS;
00219 
00220 private:
00221     //storage for pre-computed angular derivatives
00222     Eigen::Vector3d jest13, jest23, jest04, jest14, jest24, jest05, jest15, jest25;
00223     Eigen::Vector3d a2,a3, b2,b3, c2,c3, d1,d2,d3, e1,e2,e3, f1,f2,f3;
00224 
00225     std::vector<double> resolutions;
00226     //initializes stuff;
00227     void init(bool useDefaultGridResolutions, std::vector<double> _resolutions);
00228     double normalizeAngle(double a);
00229 public:
00230     int ITR_MAX;
00231     double subsample_size;
00232     EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00233 };
00234 
00235 } // end namespace
00236 
00237 #endif


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