ndt_matcher_p2d.hpp
Go to the documentation of this file.
00001 #include "Eigen/Eigen"
00002 #include "ndt_map/ndt_cell.h"
00003 #include <fstream>
00004 #include <vector>
00005 #include <ndt_map/lazy_grid.h>
00006 #include <ndt_map/oc_tree.h>
00007 
00008 namespace lslgeneric
00009 {
00010 
00011 //#define DO_DEBUG_PROC
00012 
00013 template <typename PointSource, typename PointTarget>
00014 void NDTMatcherP2D<PointSource,PointTarget>::init(bool useDefaultGridResolutions, std::vector<double> _resolutions)
00015 {
00016 
00018     double lfc1,lfc2,lfd3;
00019     double integral, outlier_ratio, support_size;
00020     integral = 0.1;
00021     outlier_ratio = 0.01;
00022     //outlier_ratio = 0.5;
00023     support_size = 4; //???
00024     lfc1 = (1-outlier_ratio)/integral;
00025     lfc2 = outlier_ratio/pow(support_size,3);
00026     lfd3 = -log(lfc2);
00027     lfd1 = -log( lfc1 + lfc2 ) - lfd3;
00028     lfd2 = -log((-log( lfc1 * exp( -0.5 ) + lfc2 ) - lfd3 ) / lfd1);
00029     //d1 = 0.1;
00030     //d2 = 0.001;
00031     //cout<<lfd1<<" "<<lfd2<<endl;
00033     useSimpleDerivatives = false;
00034     Jest.setZero();
00035     Jest.block<3,3>(0,0).setIdentity();
00036     Hest.setZero();
00037     NUMBER_OF_ACTIVE_CELLS = 0;
00038 
00039     if(useDefaultGridResolutions)
00040     {
00041         resolutions.push_back(0.2);
00042         resolutions.push_back(0.5);
00043         resolutions.push_back(1);
00044         resolutions.push_back(2);
00045     }
00046     else
00047     {
00048         resolutions = _resolutions;
00049     }
00050 }
00051 
00052 template <typename PointSource, typename PointTarget>
00053 void NDTMatcherP2D<PointSource,PointTarget>::generateScoreDebug(const char* out, pcl::PointCloud<PointTarget>& fixed,
00054         pcl::PointCloud<PointSource>& moving)
00055 {
00056 
00057     std::ofstream lg(out,std::ios_base::out);
00058     int N_LINEAR = 100;
00059     int N_ROT    = 100;
00060 
00061     std::cout<<"generating scores...\n";
00062     for(int q = resolutions.size()-1; q>=0; q--)
00063     {
00064         current_resolution = resolutions[q];
00065         std::cout<<"res "<<current_resolution<<std::endl;
00066         double lfc1,lfc2,lfd3;
00067         double integral, outlier_ratio, support_size;
00068         integral = 0.1;
00069         outlier_ratio = 0.35;
00070         support_size = current_resolution;
00071         lfc1 = (1-outlier_ratio)/integral;
00072         lfc2 = outlier_ratio/pow(support_size,3);
00073         lfd3 = -log(lfc2);
00074         lfd1 = -(-log( lfc1 + lfc2 ) - lfd3);
00075         lfd2 = -log((-log( lfc1 * exp( -0.5 ) + lfc2 ) - lfd3 ) / -lfd1);
00076 
00077         double lmin=-2, lmax=2, rmin=-M_PI/2, rmax=M_PI/2;
00078         double lstep = (lmax-lmin)/(N_LINEAR-1);
00079         double rstep = (rmax-rmin)/(N_ROT-1);
00080         Eigen::MatrixXd S(6,N_LINEAR);
00081         Eigen::Transform<double,3,Eigen::Affine,Eigen::ColMajor> T;
00082 
00083         LazyGrid<PointTarget> prototype(current_resolution);
00084         NDTMap<PointTarget> ndt( &prototype );
00085         ndt.loadPointCloud( fixed );
00086         ndt.computeNDTCells();
00087 
00088         int k=0;
00089         for(double x=lmin; x<lmax; x+=lstep)
00090         {
00091             T = Eigen::Translation<double,3>(x,0,0);
00092             //T = Eigen::Transform<double,3>(x,0,0);
00093             pcl::PointCloud<PointSource> cloud = moving;
00094             lslgeneric::transformPointCloudInPlace(T,cloud);
00095 
00096             S(0,k) = scorePointCloud(cloud,ndt);
00097             k++;
00098         }
00099         k=0;
00100         for(double x=lmin; x<lmax; x+=lstep)
00101         {
00102             T = Eigen::Translation<double,3>(0,x,0);
00103             //T = Eigen::Transform<double,3>(0,x,0);
00104             pcl::PointCloud<PointSource> cloud = moving;
00105             lslgeneric::transformPointCloudInPlace(T,cloud);
00106 
00107             S(1,k) = scorePointCloud(cloud,ndt);
00108             k++;
00109         }
00110         k=0;
00111         for(double x=lmin; x<lmax; x+=lstep)
00112         {
00113             T = Eigen::Translation<double,3>(0.,0.,x);
00114             //T = Eigen::Transform<double,3>(0.,0.,x);
00115             pcl::PointCloud<PointSource> cloud = moving;
00116             lslgeneric::transformPointCloudInPlace(T,cloud);
00117 
00118             S(2,k) = scorePointCloud(cloud,ndt);
00119             k++;
00120         }
00121 
00122         k=0;
00123         for(double r=rmin; r<rmax; r+=rstep)
00124         {
00125             T = Eigen::AngleAxis<double>(r,Eigen::Vector3d::UnitX()) *
00126                 Eigen::AngleAxis<double>(0,Eigen::Vector3d::UnitY()) *
00127                 Eigen::AngleAxis<double>(0,Eigen::Vector3d::UnitZ()) ;
00128             pcl::PointCloud<PointSource> cloud = moving;
00129             lslgeneric::transformPointCloudInPlace(T,cloud);
00130             S(3,k) = scorePointCloud(cloud,ndt);
00131             k++;
00132         }
00133         k=0;
00134         for(double r=rmin; r<rmax; r+=rstep)
00135         {
00136             T = Eigen::AngleAxis<double>(0,Eigen::Vector3d::UnitX()) *
00137                 Eigen::AngleAxis<double>(r,Eigen::Vector3d::UnitY()) *
00138                 Eigen::AngleAxis<double>(0,Eigen::Vector3d::UnitZ()) ;
00139             pcl::PointCloud<PointSource> cloud = moving;
00140             lslgeneric::transformPointCloudInPlace(T,cloud);
00141 
00142             S(4,k) = scorePointCloud(cloud,ndt);
00143             k++;
00144         }
00145         k=0;
00146         for(double r=rmin; r<rmax; r+=rstep)
00147         {
00148             T = Eigen::AngleAxis<double>(0,Eigen::Vector3d::UnitX()) *
00149                 Eigen::AngleAxis<double>(0,Eigen::Vector3d::UnitY()) *
00150                 Eigen::AngleAxis<double>(r,Eigen::Vector3d::UnitZ()) ;
00151             pcl::PointCloud<PointSource> cloud = moving;
00152             lslgeneric::transformPointCloudInPlace(T,cloud);
00153 
00154             S(5,k) = scorePointCloud(cloud,ndt);
00155             k++;
00156         }
00157 
00158         lg<<"Sp2f"<<(int)current_resolution<<" = ["<<S<<"];\n";
00159     }
00160     lg.close();
00161 
00162 }
00163 
00164 template <typename PointSource, typename PointTarget>
00165 bool NDTMatcherP2D<PointSource,PointTarget>::match( pcl::PointCloud<PointTarget>& target,
00166         pcl::PointCloud<PointSource>& source,
00167         Eigen::Transform<double,3,Eigen::Affine,Eigen::ColMajor>& T )
00168 {
00169 
00170     Eigen::Transform<double,3,Eigen::Affine,Eigen::ColMajor> Temp;
00171     T.setIdentity();
00172 #ifdef DO_DEBUG_PROC
00173     char fname[50];
00174     snprintf(fname,49,"/home/tsv/ndt_tmp/initial_clouds.wrl");
00175     FILE *fout = fopen(fname,"w");
00176     fprintf(fout,"#VRML V2.0 utf8\n");
00177 
00178     lslgeneric::writeToVRML<PointTarget>(fout,target,Eigen::Vector3d(0,1,0));
00179     lslgeneric::writeToVRML<PointSource>(fout,source,Eigen::Vector3d(1,0,0));
00180     fclose(fout);
00181 #endif
00182 
00183     isIrregularGrid = false;
00184     bool ret;
00185 
00186     if(isIrregularGrid)
00187     {
00188         current_resolution=0.5;
00189         pcl::PointCloud<PointSource> cloud = subsample(source);
00190         OctTree<PointTarget> prototype;
00191         prototype.BIG_CELL_SIZE = 4;
00192         prototype.SMALL_CELL_SIZE = 0.5;
00193         NDTMap<PointTarget> ndt( &prototype );
00194         ndt.loadPointCloud( target );
00195         ndt.computeNDTCells();
00196         ret = this->match( ndt, cloud, T );
00197 
00198     }
00199     else
00200     {
00201         pcl::PointCloud<PointSource> moving = subsample(source);
00202         //cout<<"subsampled points size is "<<moving.points.size()<<endl;
00203         //iterative regular grid
00204         for(current_resolution = 2; current_resolution >= 0.5; current_resolution = current_resolution/2)
00205         {
00206 
00207             LazyGrid<PointTarget> prototype(current_resolution);
00208             NDTMap<PointTarget> ndt( &prototype );
00209             ndt.loadPointCloud( target );
00210             ndt.computeNDTCells();
00211 
00212             ret = this->match( ndt, moving, Temp );
00213             T = Temp*T;
00214             //transform moving
00215             lslgeneric::transformPointCloudInPlace(Temp,moving);
00216 #ifdef DO_DEBUG_PROC
00217 //        cout<<"RESOLUTION: "<<current_resolution<<endl;
00218             Eigen::Vector3d out = Temp.rotation().eulerAngles(0,1,2);
00219             std::cout<<"OUT: "<<out.transpose()<<std::endl;
00220             std::cout<<"translation "<<Temp.translation().transpose()<<std::endl;
00221             //cout<<"--------------------------------------------------------\n";
00222             char fname[50];
00223             snprintf(fname,49,"/home/tsv/ndt_tmp/inner_cloud%lf.wrl",current_resolution);
00224             FILE *fout = fopen(fname,"w");
00225             fprintf(fout,"#VRML V2.0 utf8\n");
00226             lslgeneric::writeToVRML<PointTarget>(fout,target,Eigen::Vector3d(0,1,0));
00227             lslgeneric::writeToVRML<PointSource>(fout,moving,Eigen::Vector3d(1,0,0));
00228             //ndt.writeToVRML(fout);
00229             fclose(fout);
00230 #endif
00231         }
00232     }
00233 
00234     return ret;
00235 }
00236 
00237 template <typename PointSource, typename PointTarget>
00238 bool NDTMatcherP2D<PointSource,PointTarget>::covariance( pcl::PointCloud<PointTarget>& target,
00239         pcl::PointCloud<PointSource>& source,
00240         Eigen::Transform<double,3,Eigen::Affine,Eigen::ColMajor>& T,
00241         Eigen::Matrix<double,6,6> &cov
00242                                                        )
00243 {
00244 
00245     Eigen::Transform<double,3,Eigen::Affine,Eigen::ColMajor> TR;
00246     pcl::PointCloud<PointSource> cloud = source;
00247     lslgeneric::transformPointCloudInPlace(T,cloud);
00248 
00249     LazyGrid<PointTarget> prototype(current_resolution);
00250     NDTMap<PointTarget> ndt( &prototype );
00251     ndt.loadPointCloud( target );
00252     ndt.computeNDTCells();
00253 
00254     TR.setIdentity();
00255     Eigen::Matrix<double,6,1> sc;
00256     derivativesPointCloud(cloud,ndt,TR,sc,cov,true);
00257     //cout<<"cov:"<<cov<<endl;
00258     cov = 0.5*cov.inverse();
00259     //cout<<"cov2:"<<cov<<endl;
00260 
00261     return true;
00262 }
00263 
00264 template <typename PointSource, typename PointTarget>
00265 bool NDTMatcherP2D<PointSource,PointTarget>::match( NDTMap<PointTarget>& targetNDT,
00266         pcl::PointCloud<PointSource>& source,
00267         Eigen::Transform<double,3,Eigen::Affine,Eigen::ColMajor>& T )
00268 {
00270     double lfc1,lfc2,lfd3;
00271     double integral, outlier_ratio, support_size;
00272     integral = 0.1;
00273     outlier_ratio = 0.35;
00274     //outlier_ratio = 0.35;
00275     support_size = current_resolution; //???
00276     lfc1 = (1-outlier_ratio)/integral;
00277     lfc2 = outlier_ratio/pow(support_size,3);
00278     lfd3 = -log(lfc2);
00279     lfd1 = -log( lfc1 + lfc2 ) - lfd3;
00280     lfd2 = -log((-log( lfc1 * exp( -0.5 ) + lfc2 ) - lfd3 ) / lfd1);
00281     //d1 = 0.1;
00282     //d2 = 0.001;
00283     //cout<<lfd1<<" "<<lfd2<<endl;
00285     useSimpleDerivatives = false;
00286     Jest.setZero();
00287     Jest.block<3,3>(0,0).setIdentity();
00288     Hest.setZero();
00289 
00290     //locals
00291     int ITR_MAX = 100;
00292     bool convergence = false;
00293     double score=0;
00294     double DELTA_SCORE = 0.0001;
00295 //    double NORM_MAX = support_size/8, ROT_MAX = M_PI/18; //
00296     double NORM_MAX = 4*support_size, ROT_MAX = M_PI/4; //
00297     int itr_ctr = 0;
00298     double step_size = 1;
00299     Eigen::Matrix<double,6,1> pose_increment_v, pose_increment_reg_v, score_gradient; //column vectors
00300     Eigen::Matrix<double,6,6> Hessian;
00301     Eigen::Matrix3d cov;
00302     Eigen::Transform<double,3,Eigen::Affine,Eigen::ColMajor> TR;
00303     Eigen::Vector3d transformed_vec, mean;
00304     bool ret = true;
00305 
00306     pcl::PointCloud<PointSource> prevCloud, nextCloud;
00307     prevCloud = source;
00308     nextCloud = source;
00309     T.setIdentity();
00310     TR.setIdentity();
00311     Eigen::Vector3d eulerAngles = T.rotation().eulerAngles(0,1,2);
00312 
00313     double scoreP = 0;
00314     while(!convergence)
00315     {
00316 #ifdef DO_DEBUG_PROC
00317         if(itr_ctr == 0)
00318         {
00319             char fname[100];
00320             snprintf(fname,99,"/home/tsv/ndt_tmp/inner_cloud%lf_itr1_dbg.wrl",current_resolution);
00321             targetNDT.debugToVRML(fname, nextCloud);
00322         }
00323 #endif
00324 
00325         score_gradient.setZero();
00326         Hessian.setZero();
00327         //derivativesPointCloud(source,targetNDT,T,score_gradient,Hessian,true);
00328 
00329         TR.setIdentity();
00330         derivativesPointCloud(prevCloud,targetNDT,TR,score_gradient,Hessian,true);
00331 
00332         pose_increment_v = Hessian.ldlt().solve(-score_gradient);
00333 
00334         score = scorePointCloud(prevCloud,targetNDT);
00335         //cout<<"iteration "<<itr_ctr<<" pose norm "<<(pose_increment_v.norm())<<" score "<<score<<endl;
00336 
00337 //step control...
00338         double pnorm = sqrt(pose_increment_v(0)*pose_increment_v(0) + pose_increment_v(1)*pose_increment_v(1)
00339                             +pose_increment_v(2)*pose_increment_v(2));
00340         if(pnorm > NORM_MAX)
00341         {
00342             pose_increment_v(0) = NORM_MAX*pose_increment_v(0)/pnorm;
00343             pose_increment_v(1) = NORM_MAX*pose_increment_v(1)/pnorm;
00344             pose_increment_v(2) = NORM_MAX*pose_increment_v(2)/pnorm;
00345         }
00346         pose_increment_v(3) = normalizeAngle(pose_increment_v(3));
00347         pose_increment_v(3) = (pose_increment_v(3) > ROT_MAX) ? ROT_MAX : pose_increment_v(3);
00348         pose_increment_v(3) = (pose_increment_v(3) < -ROT_MAX) ? -ROT_MAX : pose_increment_v(3);
00349         pose_increment_v(4) = normalizeAngle(pose_increment_v(4));
00350         pose_increment_v(4) = (pose_increment_v(4) > ROT_MAX) ? ROT_MAX : pose_increment_v(4);
00351         pose_increment_v(4) = (pose_increment_v(4) < -ROT_MAX) ? -ROT_MAX : pose_increment_v(4);
00352         pose_increment_v(5) = normalizeAngle(pose_increment_v(5));
00353         pose_increment_v(5) = (pose_increment_v(5) > ROT_MAX) ? ROT_MAX : pose_increment_v(5);
00354         pose_increment_v(5) = (pose_increment_v(5) < -ROT_MAX) ? -ROT_MAX : pose_increment_v(5);
00355 //      cout<<"H  =  ["<<Hessian<<"]"<<endl;
00356 //      cout<<"grad= ["<<score_gradient.transpose()<<"]"<<endl;
00357 //      cout<<"dg    "<<pose_increment_v.dot(score_gradient)<<endl;
00358 
00359         TR.setIdentity();
00360         TR =  Eigen::Translation<double,3>(pose_increment_v(0),pose_increment_v(1),pose_increment_v(2))*
00361               Eigen::AngleAxis<double>(pose_increment_v(3),Eigen::Vector3d::UnitX()) *
00362               Eigen::AngleAxis<double>(pose_increment_v(4),Eigen::Vector3d::UnitY()) *
00363               Eigen::AngleAxis<double>(pose_increment_v(5),Eigen::Vector3d::UnitZ()) ;
00364 
00365         step_size = lineSearchMT(score_gradient,pose_increment_v,prevCloud,TR,targetNDT);
00366         if(step_size < 0)
00367         {
00368             //    cout<<"can't decrease in this direction any more, done \n";
00369             return true;
00370         }
00371         pose_increment_v = step_size*pose_increment_v;
00372 
00373 
00374 //      cout<<"incr= ["<<pose_increment_v.transpose()<<"]"<<endl;
00375         TR.setIdentity();
00376         TR =  Eigen::Translation<double,3>(pose_increment_v(0),pose_increment_v(1),pose_increment_v(2))*
00377               Eigen::AngleAxis<double>(pose_increment_v(3),Eigen::Vector3d::UnitX()) *
00378               Eigen::AngleAxis<double>(pose_increment_v(4),Eigen::Vector3d::UnitY()) *
00379               Eigen::AngleAxis<double>(pose_increment_v(5),Eigen::Vector3d::UnitZ()) ;
00380         T = TR*T;
00381 
00382         //eulerAngles<<pose_increment_v(3),pose_increment_v(4),pose_increment_v(5);
00383         //eulerAngles = T.rotation().eulerAngles(0,1,2);
00384 
00385         prevCloud = lslgeneric::transformPointCloud<PointSource>(T,source);
00386         scoreP = score;
00387         score = scorePointCloud(prevCloud,targetNDT);
00388 
00389         //cout<<"iteration "<<itr_ctr<<" pose norm "<<(pose_increment_v.norm())<<" score_prev "<<scoreP<<" scoreN "<<score<<endl;
00390         //cout<<"step size "<<step_size<<endl;
00391 
00392         if(itr_ctr>0)
00393         {
00394             convergence = ((pose_increment_v.norm()) < DELTA_SCORE);
00395         }
00396         if(itr_ctr>ITR_MAX)
00397         {
00398             convergence = true;
00399             ret = false;
00400         }
00401         itr_ctr++;
00402     }
00403 //    cout<<"res: "<<current_resolution<<" itr "<<itr_ctr<<endl;
00404 //    cout<<"T: \n t = "<<T.translation().transpose()<<endl;
00405 //    cout<<"r= \n"<<T.rotation()<<endl;
00406 
00407     this->finalscore = score/NUMBER_OF_ACTIVE_CELLS;
00408     return ret;
00409 }
00410 
00411 
00412 template <typename PointSource, typename PointTarget>
00413 bool NDTMatcherP2D<PointSource,PointTarget>::update_score_gradient(Eigen::Matrix<double,6,1> &score_gradient,
00414         Eigen::Vector3d &transformed,
00415         Eigen::Matrix3d & Cinv)
00416 {
00417 
00418     Eigen::Vector3d CxX, CxdX;
00419     double factor = (-lfd2*transformed.dot(Cinv*transformed)/2);
00420 
00421     //these conditions were copied from martin's code
00422     if(factor < -120)
00423     {
00424         return false;
00425     }
00426     factor = lfd2*exp(factor);
00427     if(factor > 1 || factor < 0 || factor*0 !=0)
00428     {
00429         return false;
00430     }
00431     factor *=lfd1;
00432 
00433     for(int i=0; i<6; i++)
00434     {
00435         CxdX = Cinv*Jest.col(i);
00436         score_gradient(i) += transformed.dot(CxdX)*factor;
00437     }
00438     return true;
00439 
00440 }
00441 
00442 template <typename PointSource, typename PointTarget>
00443 void NDTMatcherP2D<PointSource,PointTarget>::update_hessian(Eigen::Matrix<double,6,6> &Hessian,
00444         Eigen::Vector3d &transformed,
00445         Eigen::Matrix3d & Cinv)
00446 {
00447 
00448     Eigen::Vector3d CxX, CxdXdI, CxdXdJ, CxSecondOrder;
00449     CxX = Cinv*transformed;
00450     double factor = lfd1*lfd2*exp(-lfd2*transformed.dot(CxX)/2);
00451     for(int i=0; i<Hessian.rows(); i++)
00452     {
00453         for(int j=0; j<Hessian.cols(); j++)
00454         {
00455 
00456             CxdXdI = Cinv*Jest.col(i);
00457             CxdXdJ = Cinv*Jest.col(j);
00458             CxSecondOrder = Cinv*Hest.block<3,1>(3*i,j);
00459 
00460             Hessian(i,j) += factor*(-lfd2*transformed.dot(CxdXdI)*transformed.dot(CxdXdJ) +
00461                                     transformed.dot(CxSecondOrder) +
00462                                     Jest.col(j).dot(CxdXdI) );
00463         }
00464     }
00465 
00466 }
00467 
00468 template <typename PointSource, typename PointTarget>
00469 void NDTMatcherP2D<PointSource,PointTarget>::precomputeAngleDerivatives(Eigen::Vector3d &eulerAngles)
00470 {
00471     if(fabsf(eulerAngles(0)) < 10e-5) eulerAngles(0) = 0;
00472     if(fabsf(eulerAngles(1)) < 10e-5) eulerAngles(1) = 0;
00473     if(fabsf(eulerAngles(2)) < 10e-5) eulerAngles(2) = 0;
00474     double cx,cy,cz, sx,sy,sz;
00475     cx = cos(eulerAngles(0));
00476     cy = cos(eulerAngles(1));
00477     cz = cos(eulerAngles(2));
00478     sx = sin(eulerAngles(0));
00479     sy = sin(eulerAngles(1));
00480     sz = sin(eulerAngles(2));
00481 
00482     jest13 << (-sx*sz+cx*sy*cz) , (-sx*cz - cx*sy*sz) , (-cx*cy) ;
00483     jest23 << (cx*sz+sx*sy*cz) , (cx*cz-sx*sy*sz) , (-sx*cy);
00484     jest04 << (-sy*cz) , sy*sz , cy;
00485     jest14 << sx*cy*cz , (-sx*cy*sz) , sx*sy;
00486     jest24 << (-cx*cy*cz) , cx*cy*sz , (-cx*sy);
00487     jest05 << (-cy*sz) , (-cy*cz), 0;
00488     jest15 << (cx*cz-sx*sy*sz) , (-cx*sz - sx*sy*cz), 0;
00489     jest25 << (sx*cz + cx*sy*sz) ,(cx*sy*cz - sx*sz), 0;
00490 
00491 
00492     a2 << (-cx*sz-sx*sy*cz),(-cx*cz+sx*sy*sz),sx*cy;
00493     a3 << (-sx*sz+cx*sy*cz),(-cx*sy*sz-sx*cz),(-cx*cy);
00494     b2 << (cx*cy*cz),(-cx*cy*sz),(cx*sy);
00495     b3 << (sx*cy*cz),(-sx*cy*sz),(sx*sy);
00496     c2 << (-sx*cz-cx*sy*sz),(sx*sz-cx*sy*cz),0;
00497     c3 << (cx*cz-sx*sy*sz),(-sx*sy*cz-cx*sz),0;
00498     d1 << (-cy*cz),(cy*sz),(sy);
00499     d2 << (-sx*sy*cz),(sx*sy*sz),(sx*cy);
00500     d3 << (cx*sy*cz),(-cx*sy*sz),(-cx*cy);
00501     e1 << (sy*sz),(sy*cz),0;
00502     e2 << (-sx*cy*sz),(-sx*cy*cz),0;
00503     e3 << (cx*cy*sz),(cx*cy*cz),0;
00504     f1 << (-cy*cz),(cy*sz),0;
00505     f2 << (-cx*sz -sx*sy*cz),(-cx*cz+sx*sy*sz),0;
00506     f3 << (-sx*sz+cx*sy*cz),(-cx*sy*sz-sx*cz),0;
00507 
00508 }
00509 
00510 template <typename PointSource, typename PointTarget>
00511 void NDTMatcherP2D<PointSource,PointTarget>::computeDerivatives(PointSource &pt)
00512 {
00513 
00514     if(useSimpleDerivatives)
00515     {
00516         Jest(1,3) = -pt.z;
00517         Jest(2,3) = pt.y;
00518         Jest(0,4) = pt.z;
00519         Jest(2,4) = -pt.x;
00520         Jest(0,5) = -pt.y;
00521         Jest(1,5) = pt.x;
00522 
00523         return;
00524     }
00525 
00526     Eigen::Vector3d x;
00527     x<<pt.x,pt.y,pt.z;
00528 
00529     //full derivatives
00530     Jest(1,3) = x.dot(jest13);
00531     Jest(2,3) = x.dot(jest23);
00532     Jest(0,4) = x.dot(jest04);
00533     Jest(1,4) = x.dot(jest14);
00534     Jest(2,4) = x.dot(jest24);
00535     Jest(0,5) = x.dot(jest05);
00536     Jest(1,5) = x.dot(jest15);
00537     Jest(2,5) = x.dot(jest25);
00538 
00539     Eigen::Vector3d a,b,c,d,e,f;
00540 
00541     a<<0,x.dot(a2),x.dot(a3);
00542     b<<0,x.dot(b2),x.dot(b3);
00543     c<<0,x.dot(c2),x.dot(c3);
00544     d<<x.dot(d1),x.dot(d2),x.dot(d3);
00545     e<<x.dot(e1),x.dot(e2),x.dot(e3);
00546     f<<x.dot(f1),x.dot(f2),x.dot(f3);
00547 
00548     //Hest
00549     Hest.block<3,1>(9,3) = a;
00550     Hest.block<3,1>(12,3) = b;
00551     Hest.block<3,1>(15,3) = c;
00552     Hest.block<3,1>(9,4) = b;
00553     Hest.block<3,1>(12,4) = d;
00554     Hest.block<3,1>(15,4) = e;
00555     Hest.block<3,1>(9,5) = c;
00556     Hest.block<3,1>(12,5) = e;
00557     Hest.block<3,1>(15,5) = f;
00558 
00559 }
00560 
00561 template <typename PointSource, typename PointTarget>
00562 double NDTMatcherP2D<PointSource,PointTarget>::scorePointCloud(pcl::PointCloud<PointSource> &source,
00563         NDTMap<PointTarget> &targetNDT)
00564 {
00565     double score_here = 0;
00566     double score_native = 0;
00567     NDTCell<PointTarget> *cell;
00568     Eigen::Matrix3d icov;
00569     Eigen::Vector3d mean;
00570     Eigen::Vector3d point;
00571     NUMBER_OF_ACTIVE_CELLS = 0;
00572     for(unsigned int i=0; i<source.points.size(); i++)
00573     {
00574         point<<source.points[i].x,source.points[i].y,source.points[i].z;
00575 
00576         std::vector<NDTCell<PointTarget>*> cells = targetNDT.getCellsForPoint(source.points[i],current_resolution);
00577         for(unsigned int j=0; j<cells.size(); j++)
00578         {
00579             cell = cells[j];
00580 
00581             //{
00582             //    if(!targetNDT.getCellForPoint(source.points[i],cell)) {
00583             //        continue;
00584             //  }
00585             if(cell == NULL)
00586             {
00587                 continue;
00588             }
00589             icov = cell->getInverseCov();
00590             mean = cell->getMean();
00591             double l = (point-mean).dot(icov*(point-mean));
00592             if(l*0 != 0) continue;
00593 
00594             if(isIrregularGrid)
00595             {
00596                 //these lines should be done only for irregular grids!!
00597                 double lfc1,lfc2,lfd3;
00598                 double xs,ys,zs;
00599                 double integral, outlier_ratio, support_size;
00600                 integral = 0.1;
00601                 outlier_ratio = 0.35;
00602                 cell->getDimensions(xs,ys,zs);
00603                 support_size = xs;
00604                 lfc1 = (1-outlier_ratio)/integral;
00605                 lfc2 = outlier_ratio/pow(support_size,3);
00606                 lfd3 = -log(lfc2);
00607                 lfd1 = -log( lfc1 + lfc2 ) - lfd3;
00608                 lfd2 = -2*log((-log( lfc1 * exp( -0.5 ) + lfc2 ) - lfd3 ) / lfd1);
00609             }
00610             if(l > 120) continue;
00611 
00612             score_here += (lfd1*exp(-lfd2*l/2));
00613             score_native += (targetNDT.getLikelihoodForPoint(source.points[i]));
00614             NUMBER_OF_ACTIVE_CELLS += 1;
00615         }
00616     }
00617 //    cout<<"here: "<<score_here<<" native: "<<score_native<<endl;
00618 //    score_here /= NUMBER_OF_POINTS;
00619     return score_here;
00620 }
00621 
00622 //compute the score gradient of a point cloud + transformation to an NDT
00623 template <typename PointSource, typename PointTarget>
00624 void NDTMatcherP2D<PointSource,PointTarget>::derivativesPointCloud(pcl::PointCloud<PointSource> &source,
00625         NDTMap<PointTarget> &targetNDT,
00626         Eigen::Transform<double,3,Eigen::Affine,Eigen::ColMajor> &transform,
00627 //      Eigen::Vector3d &eulerAngles,
00628         Eigen::Matrix<double,6,1> &score_gradient,
00629         Eigen::Matrix<double,6,6> &Hessian,
00630         bool computeHessian)
00631 {
00632 
00633     NDTCell<PointTarget> *cell;
00634     Eigen::Vector3d transformed;
00635     Eigen::Matrix3d Cinv;
00636     Eigen::Vector3d eulerAngles = transform.rotation().eulerAngles(0,1,2);
00637 
00638     Jest.setZero();
00639     Jest.block<3,3>(0,0).setIdentity();
00640     Hest.setZero();
00641 
00642     score_gradient.setZero();
00643     Hessian.setZero();
00644     //precompute angles for the derivative matrices
00645     precomputeAngleDerivatives(eulerAngles);
00646 
00647     for(unsigned int i=0; i<source.points.size(); i++)
00648     {
00649         transformed<<source.points[i].x,source.points[i].y,source.points[i].z;
00650         transformed = transform*transformed;
00651 
00652         // vector<NDTCell*> cells = targetNDT.getCellsForPoint(source.points[i],current_resolution);
00653         // for( int j=0; j<cells.size(); j++) {
00654         //      cell = cells[j];
00655         //
00656         {
00657             if(!targetNDT.getCellForPoint(source.points[i],cell))   //
00658             {
00659                 continue;
00660             }
00661 
00662             if(cell == NULL)
00663             {
00664                 continue;
00665             }
00666             transformed -=cell->getMean();
00667             Cinv = cell->getInverseCov();
00668 
00669             if(isIrregularGrid)
00670             {
00671                 //these lines set the rescaling parameters for irregular cell grids
00672                 double lfc1,lfc2,lfd3;
00673                 double xs,ys,zs;
00674                 double integral, outlier_ratio, support_size;
00675                 integral = 0.1;
00676                 outlier_ratio = 0.35;
00677                 cell->getDimensions(xs,ys,zs);
00678                 support_size = xs;
00679                 lfc1 = (1-outlier_ratio)/integral;
00680                 lfc2 = outlier_ratio/pow(support_size,3);
00681                 lfd3 = -log(lfc2);
00682                 lfd1 = -log( lfc1 + lfc2 ) - lfd3;
00683                 lfd2 = -2*log((-log( lfc1 * exp( -0.5 ) + lfc2 ) - lfd3 ) / lfd1);
00684             }
00685 
00686             //compute Jest and Hest
00687             computeDerivatives(source.points[i]);
00688 
00689             //update score gradient
00690             if(!update_score_gradient(score_gradient, transformed, Cinv))
00691             {
00692                 continue;
00693             }
00694 
00695             //update hessian matrix
00696             if(computeHessian)
00697             {
00698                 update_hessian(Hessian, transformed, Cinv);
00699             }
00700             cell = NULL;
00701         }
00702     }
00703     score_gradient = -score_gradient;
00704     Hessian = -Hessian;
00705 }
00706 
00707 //perform line search to find the best descent rate (More&Thuente)
00708 template <typename PointSource, typename PointTarget>
00709 double NDTMatcherP2D<PointSource,PointTarget>::lineSearchMT(  Eigen::Matrix<double,6,1> &score_gradient_init,
00710         Eigen::Matrix<double,6,1> &increment,
00711         pcl::PointCloud<PointSource> &sourceCloud,
00712         Eigen::Transform<double,3,Eigen::Affine,Eigen::ColMajor> &globalT,
00713         NDTMap<PointTarget> &targetNDT)
00714 {
00715 
00716     // default params
00717     double stp = 4.0; //default step
00718     double recoverystep = 0.05;
00719     double dginit = 0.0;
00720     double ftol = 0.0001; //epsilon 1
00721     double gtol = 0.9999; //epsilon 2
00722     double stpmax = 10.0;
00723     double stpmin = 0.0001;
00724     int maxfev = 10; //max function evaluations
00725     double xtol = 0.01; //window of uncertainty around the optimal step
00726 
00727     double direction = 1.0;
00728     //my temporary variables
00729     pcl::PointCloud<PointSource> cloudHere = sourceCloud;
00730     //cloudHere = lslgeneric::transformPointCloud(globalT,cloud);
00731     double score_init = 0.0;
00732 
00733     Eigen::Transform<double,3,Eigen::Affine,Eigen::ColMajor> ps,ps2;
00734     Eigen::Matrix<double,6,1> pincr, score_gradient_here;
00735     Eigen::Matrix<double,6,6> pseudoH;
00736     Eigen::Vector3d eulerAngles;
00738 
00739     int info = 0;                       // return code
00740     int infoc = 1;              // return code for subroutine cstep
00741 
00742     // Compute the initial gradient in the search direction and check
00743     // that s is a descent direction.
00744 
00745     //we want to maximize s, so we should minimize -s
00746     score_init = scorePointCloud(cloudHere,targetNDT);
00747 
00748     //gradient directions are opposite for the negated function
00749     //score_gradient_init = -score_gradient_init;
00750 
00751 //  cout<<"score_init "<<score_init<<endl;
00752 //  cout<<"score_gradient_init "<<score_gradient_init.transpose()<<endl;
00753 //  cout<<"increment "<<increment.transpose()<<endl;
00754 
00755     dginit = increment.dot(score_gradient_init);
00756 //  cout<<"dginit "<<dginit<<endl;
00757 
00758     if (dginit >= 0.0)
00759     {
00760 //    cout << "MoreThuente::cvsrch - wrong direction (dginit = " << dginit << ")" << endl;
00761         //return recoverystep; //TODO TSV -1; //
00762 
00763         increment = -increment;
00764         dginit = -dginit;
00765         direction = -1;
00766 
00767         if (dginit >= 0.0)
00768         {
00769 //    cout << "MoreThuente::cvsrch - Non-descent direction (dginit = " << dginit << ")" << endl;
00770             //stp = recoverystep;
00771             //newgrp.computeX(oldgrp, dir, stp);
00772             return recoverystep;
00773         }
00774     }
00775     else
00776     {
00777 //     cout<<"correct direction (dginit = " << dginit << ")" << endl;
00778     }
00779 
00780     // Initialize local variables.
00781 
00782     bool brackt = false;                // has the soln been bracketed?
00783     bool stage1 = true;         // are we in stage 1?
00784     int nfev = 0;                       // number of function evaluations
00785     double dgtest = ftol * dginit; // f for curvature condition
00786     double width = stpmax - stpmin; // interval width
00787     double width1 = 2 * width;  // ???
00788 
00789     //cout<<"dgtest "<<dgtest<<endl;
00790     // initial function value
00791     double finit = 0.0;
00792     finit = score_init;
00793 
00794     // The variables stx, fx, dgx contain the values of the step,
00795     // function, and directional derivative at the best step.  The
00796     // variables sty, fy, dgy contain the value of the step, function,
00797     // and derivative at the other endpoint of the interval of
00798     // uncertainty.  The variables stp, f, dg contain the values of the
00799     // step, function, and derivative at the current step.
00800 
00801     double stx = 0.0;
00802     double fx = finit;
00803     double dgx = dginit;
00804     double sty = 0.0;
00805     double fy = finit;
00806     double dgy = dginit;
00807 
00808     // Get the linear solve tolerance for adjustable forcing term
00809     double eta_original = -1.0;
00810     double eta = 0.0;
00811     eta = eta_original;
00812 
00813     // Start of iteration.
00814 
00815     double stmin, stmax;
00816     double fm, fxm, fym, dgm, dgxm, dgym;
00817 
00818     while (1)
00819     {
00820         // Set the minimum and maximum steps to correspond to the present
00821         // interval of uncertainty.
00822         if (brackt)
00823         {
00824             stmin = MoreThuente::min(stx, sty);
00825             stmax = MoreThuente::max(stx, sty);
00826         }
00827         else
00828         {
00829             stmin = stx;
00830             stmax = stp + 4 * (stp - stx);
00831         }
00832 
00833         // Force the step to be within the bounds stpmax and stpmin.
00834         stp = MoreThuente::max(stp, stpmin);
00835         stp = MoreThuente::min(stp, stpmax);
00836 
00837         // If an unusual termination is to occur then let stp be the
00838         // lowest point obtained so far.
00839 
00840         if ((brackt && ((stp <= stmin) || (stp >= stmax))) ||
00841                 (nfev >= maxfev - 1) || (infoc == 0) ||
00842                 (brackt && (stmax - stmin <= xtol * stmax)))
00843         {
00844             stp = stx;
00845         }
00846 
00847         // Evaluate the function and gradient at stp
00848         // and compute the directional derivative.
00850 
00851         pincr = stp*increment;
00852 
00853         ps = Eigen::Translation<double,3>(pincr(0),pincr(1),pincr(2))*
00854              Eigen::AngleAxisd(pincr(3),Eigen::Vector3d::UnitX())*
00855              Eigen::AngleAxisd(pincr(4),Eigen::Vector3d::UnitY())*
00856              Eigen::AngleAxisd(pincr(5),Eigen::Vector3d::UnitZ());
00857 
00858         //ps2 = ps*globalT;
00859         //eulerAngles = ps2.rotation().eulerAngles(0,1,2);
00860 
00861         //eulerAngles<<pincr(3),pincr(4),pincr(5);
00862         cloudHere = lslgeneric::transformPointCloud(ps,sourceCloud);
00863 
00864         double f = 0.0;
00865         f = scorePointCloud(cloudHere,targetNDT);
00866         score_gradient_here.setZero();
00867 
00868         ps2.setIdentity();
00869         derivativesPointCloud(cloudHere,targetNDT,ps2,score_gradient_here,pseudoH,false);
00870 
00871         //derivativesPointCloud(cloud,ndt,ps,score_gradient_here,pseudoH,false);
00872 
00873         //derivativesPointCloud(cloudHere,ndt,ps2,score_gradient_here,pseudoH,false);
00874         //negate score gradient
00875         //score_gradient_here = -score_gradient_here;
00876 
00877         //cout<<"incr " <<pincr.transpose()<<endl;
00878         //cout<<"scg  " <<score_gradient_here.transpose()<<endl;
00879         //cout<<"score (f) "<<f<<endl;
00880 
00881         //VALGRIND_CHECK_VALUE_IS_DEFINED(score_gradient_here);
00882         //VALGRIND_CHECK_VALUE_IS_DEFINED(increment);
00883         double dg = 0.0;
00884         dg = increment.dot(score_gradient_here);
00885 
00886 
00887         //VALGRIND_CHECK_VALUE_IS_DEFINED(dg);
00888         //cout<<"dg = "<<dg<<endl;
00889         nfev ++;
00890 
00892 
00893         //cout<<"consider step "<<stp<<endl;
00894         // Armijo-Goldstein sufficient decrease
00895         double ftest1 = finit + stp * dgtest;
00896         //cout<<"ftest1 is "<<ftest1<<endl;
00897 
00898         // Test for convergence.
00899 
00900         if ((brackt && ((stp <= stmin) || (stp >= stmax))) || (infoc == 0))
00901             info = 6;                   // Rounding errors
00902 
00903         if ((stp == stpmax) && (f <= ftest1) && (dg <= dgtest))
00904             info = 5;                   // stp=stpmax
00905 
00906         if ((stp == stpmin) && ((f > ftest1) || (dg >= dgtest)))
00907             info = 4;                   // stp=stpmin
00908 
00909         if (nfev >= maxfev)
00910             info = 3;                   // max'd out on fevals
00911 
00912         if (brackt && (stmax-stmin <= xtol*stmax))
00913             info = 2;                   // bracketed soln
00914 
00915         // RPP sufficient decrease test can be different
00916         bool sufficientDecreaseTest = false;
00917         sufficientDecreaseTest = (f <= ftest1);  // Armijo-Golstein
00918 
00919         //cout<<"ftest2 "<<gtol*(-dginit)<<endl;
00920         //cout<<"sufficientDecrease? "<<sufficientDecreaseTest<<endl;
00921         //cout<<"curvature ok? "<<(fabs(dg) <= gtol*(-dginit))<<endl;
00922         if ((sufficientDecreaseTest) && (fabs(dg) <= gtol*(-dginit)))
00923             info = 1;                   // Success!!!!
00924 
00925         if (info != 0)          // Line search is done
00926         {
00927             if (info != 1)              // Line search failed
00928             {
00929                 // RPP add
00930                 // counter.incrementNumFailedLineSearches();
00931 
00932                 //if (recoveryStepType == Constant)
00933                 stp = recoverystep;
00934 
00935                 //newgrp.computeX(oldgrp, dir, stp);
00936 
00937                 //message = "(USING RECOVERY STEP!)";
00938 
00939             }
00940             else                        // Line search succeeded
00941             {
00942                 //message = "(STEP ACCEPTED!)";
00943             }
00944 
00945             //print.printStep(nfev, stp, finit, f, message);
00946 
00947             // Returning the line search flag
00948             //cout<<"LineSearch::"<<message<<" info "<<info<<endl;
00949             return stp;
00950 
00951         } // info != 0
00952 
00953         // RPP add
00954         //counter.incrementNumIterations();
00955 
00956         // In the first stage we seek a step for which the modified
00957         // function has a nonpositive value and nonnegative derivative.
00958 
00959         if (stage1 && (f <= ftest1) && (dg >= MoreThuente::min(ftol, gtol) * dginit))
00960         {
00961             stage1 = false;
00962         }
00963 
00964         // A modified function is used to predict the step only if we have
00965         // not obtained a step for which the modified function has a
00966         // nonpositive function value and nonnegative derivative, and if a
00967         // lower function value has been obtained but the decrease is not
00968         // sufficient.
00969 
00970         if (stage1 && (f <= fx) && (f > ftest1))
00971         {
00972 
00973             // Define the modified function and derivative values.
00974 
00975             fm = f - stp * dgtest;
00976             fxm = fx - stx * dgtest;
00977             fym = fy - sty * dgtest;
00978             dgm = dg - dgtest;
00979             dgxm = dgx - dgtest;
00980             dgym = dgy - dgtest;
00981 
00982             // Call cstep to update the interval of uncertainty
00983             // and to compute the new step.
00984 
00985             //VALGRIND_CHECK_VALUE_IS_DEFINED(dgm);
00986             infoc = MoreThuente::cstep(stx,fxm,dgxm,sty,fym,dgym,stp,fm,dgm,
00987                                        brackt,stmin,stmax);
00988 
00989             // Reset the function and gradient values for f.
00990 
00991             fx = fxm + stx*dgtest;
00992             fy = fym + sty*dgtest;
00993             dgx = dgxm + dgtest;
00994             dgy = dgym + dgtest;
00995 
00996         }
00997 
00998         else
00999         {
01000 
01001             // Call cstep to update the interval of uncertainty
01002             // and to compute the new step.
01003 
01004             //VALGRIND_CHECK_VALUE_IS_DEFINED(dg);
01005             infoc = MoreThuente::cstep(stx,fx,dgx,sty,fy,dgy,stp,f,dg,
01006                                        brackt,stmin,stmax);
01007 
01008         }
01009 
01010         // Force a sufficient decrease in the size of the
01011         // interval of uncertainty.
01012 
01013         if (brackt)
01014         {
01015             if (fabs(sty - stx) >= 0.66 * width1)
01016                 stp = stx + 0.5 * (sty - stx);
01017             width1 = width;
01018             width = fabs(sty-stx);
01019         }
01020 
01021     } // while-loop
01022 
01023 }
01024 
01025 
01026 template <typename PointSource, typename PointTarget>
01027 int NDTMatcherP2D<PointSource,PointTarget>::MoreThuente::cstep(double& stx, double& fx, double& dx,
01028         double& sty, double& fy, double& dy,
01029         double& stp, double& fp, double& dp,
01030         bool& brackt, double stmin, double stmax)
01031 {
01032     int info = 0;
01033 
01034     // Check the input parameters for errors.
01035 
01036     if ((brackt && ((stp <= MoreThuente::min(stx, sty)) || (stp >= MoreThuente::max(stx, sty)))) ||
01037             (dx * (stp - stx) >= 0.0) || (stmax < stmin))
01038         return info;
01039 
01040     // Determine if the derivatives have opposite sign.
01041 
01042     double sgnd = dp * (dx / fabs(dx));
01043 
01044     // First case. A higher function value.  The minimum is
01045     // bracketed. If the cubic step is closer to stx than the quadratic
01046     // step, the cubic step is taken, else the average of the cubic and
01047     // quadratic steps is taken.
01048 
01049     bool bound;
01050     double theta;
01051     double s;
01052     double gamma;
01053     double p,q,r;
01054     double stpc, stpq, stpf;
01055 
01056     if (fp > fx)
01057     {
01058         info = 1;
01059         bound = 1;
01060         theta = 3 * (fx - fp) / (stp - stx) + dx + dp;
01061         //VALGRIND_CHECK_VALUE_IS_DEFINED(theta);
01062         //VALGRIND_CHECK_VALUE_IS_DEFINED(dx);
01063         //VALGRIND_CHECK_VALUE_IS_DEFINED(dp);
01064         s = MoreThuente::absmax(theta, dx, dp);
01065         gamma = s * sqrt(((theta / s) * (theta / s)) - (dx / s) * (dp / s));
01066         if (stp < stx)
01067             gamma = -gamma;
01068 
01069         p = (gamma - dx) + theta;
01070         q = ((gamma - dx) + gamma) + dp;
01071         r = p / q;
01072         stpc = stx + r * (stp - stx);
01073         stpq = stx + ((dx / ((fx - fp) / (stp - stx) + dx)) / 2) * (stp - stx);
01074         if (fabs(stpc - stx) < fabs(stpq - stx))
01075             stpf = stpc;
01076         else
01077             stpf = stpc + (stpq - stpc) / 2;
01078 
01079         brackt = true;
01080     }
01081 
01082     // Second case. A lower function value and derivatives of opposite
01083     // sign. The minimum is bracketed. If the cubic step is closer to
01084     // stx than the quadratic (secant) step, the cubic step is taken,
01085     // else the quadratic step is taken.
01086 
01087     else if (sgnd < 0.0)
01088     {
01089         info = 2;
01090         bound = false;
01091         theta = 3 * (fx - fp) / (stp - stx) + dx + dp;
01092         s = MoreThuente::absmax(theta,dx,dp);
01093         gamma = s * sqrt(((theta/s) * (theta/s)) - (dx / s) * (dp / s));
01094         if (stp > stx)
01095             gamma = -gamma;
01096         p = (gamma - dp) + theta;
01097         q = ((gamma - dp) + gamma) + dx;
01098         r = p / q;
01099         stpc = stp + r * (stx - stp);
01100         stpq = stp + (dp / (dp - dx)) * (stx - stp);
01101         if (fabs(stpc - stp) > fabs(stpq - stp))
01102             stpf = stpc;
01103         else
01104             stpf = stpq;
01105         brackt = true;
01106     }
01107 
01108     // Third case. A lower function value, derivatives of the same sign,
01109     // and the magnitude of the derivative decreases.  The cubic step is
01110     // only used if the cubic tends to infinity in the direction of the
01111     // step or if the minimum of the cubic is beyond stp. Otherwise the
01112     // cubic step is defined to be either stmin or stmax. The
01113     // quadratic (secant) step is also computed and if the minimum is
01114     // bracketed then the the step closest to stx is taken, else the
01115     // step farthest away is taken.
01116 
01117     else if (fabs(dp) < fabs(dx))
01118     {
01119         info = 3;
01120         bound = true;
01121         theta = 3 * (fx - fp) / (stp - stx) + dx + dp;
01122         s = MoreThuente::absmax(theta, dx, dp);
01123 
01124         // The case gamma = 0 only arises if the cubic does not tend
01125         // to infinity in the direction of the step.
01126 
01127         gamma = s * sqrt(max(0,(theta / s) * (theta / s) - (dx / s) * (dp / s)));
01128         if (stp > stx)
01129             gamma = -gamma;
01130 
01131         p = (gamma - dp) + theta;
01132         q = (gamma + (dx - dp)) + gamma;
01133         r = p / q;
01134         if ((r < 0.0) && (gamma != 0.0))
01135             stpc = stp + r * (stx - stp);
01136         else if (stp > stx)
01137             stpc = stmax;
01138         else
01139             stpc = stmin;
01140 
01141         stpq = stp + (dp/ (dp - dx)) * (stx - stp);
01142         if (brackt)
01143         {
01144             if (fabs(stp - stpc) < fabs(stp - stpq))
01145                 stpf = stpc;
01146             else
01147                 stpf = stpq;
01148         }
01149         else
01150         {
01151             if (fabs(stp - stpc) > fabs(stp - stpq))
01152                 stpf = stpc;
01153             else
01154                 stpf = stpq;
01155         }
01156     }
01157 
01158     // Fourth case. A lower function value, derivatives of the same
01159     // sign, and the magnitude of the derivative does not decrease. If
01160     // the minimum is not bracketed, the step is either stmin or
01161     // stmax, else the cubic step is taken.
01162 
01163     else
01164     {
01165         info = 4;
01166         bound = false;
01167         if (brackt)
01168         {
01169             theta = 3 * (fp - fy) / (sty - stp) + dy + dp;
01170             s = MoreThuente::absmax(theta, dy, dp);
01171             gamma = s * sqrt(((theta/s)*(theta/s)) - (dy / s) * (dp / s));
01172             if (stp > sty)
01173                 gamma = -gamma;
01174             p = (gamma - dp) + theta;
01175             q = ((gamma - dp) + gamma) + dy;
01176             r = p / q;
01177             stpc = stp + r * (sty - stp);
01178             stpf = stpc;
01179         }
01180         else if (stp > stx)
01181             stpf = stmax;
01182         else
01183             stpf = stmin;
01184     }
01185 
01186     // Update the interval of uncertainty. This update does not depend
01187     // on the new step or the case analysis above.
01188 
01189     if (fp > fx)
01190     {
01191         sty = stp;
01192         fy = fp;
01193         dy = dp;
01194     }
01195     else
01196     {
01197         if (sgnd < 0.0)
01198         {
01199             sty = stx;
01200             fy = fx;
01201             dy = dx;
01202         }
01203         stx = stp;
01204         fx = fp;
01205         dx = dp;
01206     }
01207 
01208     // Compute the new step and safeguard it.
01209 
01210     stpf = MoreThuente::min(stmax, stpf);
01211     stpf = MoreThuente::max(stmin, stpf);
01212     stp = stpf;
01213     if (brackt && bound)
01214     {
01215         if (sty > stx)
01216             stp = min(stx + 0.66 * (sty - stx), stp);
01217         else
01218             stp = max(stx + 0.66 * (sty - stx), stp);
01219     }
01220 
01221     return info;
01222 
01223 }
01224 
01225 template <typename PointSource, typename PointTarget>
01226 double NDTMatcherP2D<PointSource,PointTarget>::MoreThuente::min(double a, double b)
01227 {
01228     return (a < b ? a : b);
01229 }
01230 
01231 template <typename PointSource, typename PointTarget>
01232 double NDTMatcherP2D<PointSource,PointTarget>::MoreThuente::max(double a, double b)
01233 {
01234     return (a > b ? a : b);
01235 }
01236 
01237 template <typename PointSource, typename PointTarget>
01238 double NDTMatcherP2D<PointSource,PointTarget>::MoreThuente::absmax(double a, double b, double c)
01239 {
01240     a = fabs(a);
01241     b = fabs(b);
01242     c = fabs(c);
01243 
01244     if (a > b)
01245         return (a > c) ? a : c;
01246     else
01247         return (b > c) ? b : c;
01248 }
01249 
01250 template <typename PointSource, typename PointTarget>
01251 pcl::PointCloud<PointSource> NDTMatcherP2D<PointSource,PointTarget>::subsample(pcl::PointCloud<PointSource>& original)
01252 {
01253 
01254     std::string subsampleType = "TREE";
01255     if(subsampleType == "NONE")
01256     {
01257         return original;
01258     }
01259     if(subsampleType == "GRID")
01260     {
01261         double subsampleRes = 0.4;//current_resolution/2;
01262         pcl::PointCloud<PointSource> res;
01263         LazyGrid<PointSource> prototype(subsampleRes);
01264         NDTMap<PointSource> ndt( &prototype );
01265         ndt.loadPointCloud( original );
01266         typename std::vector<Cell<PointSource>*>::iterator it = ndt.getMyIndex()->begin();
01267 
01268         while(it!=ndt.getMyIndex()->end())
01269         {
01270             NDTCell<PointSource>* ndcell = dynamic_cast<NDTCell<PointSource>*>(*it);
01271             if(ndcell!=NULL)
01272             {
01273                 if(ndcell->points_.size() > 0)
01274                 {
01275                     res.points.push_back(ndcell->points_.front());
01276                 }
01277             }
01278             it++;
01279         }
01280         return res;
01281 
01282     }
01283 
01284     if(subsampleType == "MEAN")
01285     {
01286         pcl::PointCloud<PointSource> res;
01287 
01288         NDTMap<PointSource> ndt( new OctTree<PointSource>() );
01289         ndt.loadPointCloud( original );
01290         ndt.computeNDTCells();
01291         typename std::vector<Cell<PointSource>*>::iterator it = ndt.getMyIndex()->begin();
01292 
01293         while(it!=ndt.getMyIndex()->end())
01294         {
01295             NDTCell<PointSource>* ndcell = dynamic_cast<NDTCell<PointSource>*>(*it);
01296             if(ndcell!=NULL)
01297             {
01298                 if(ndcell->points_.size() > 0)
01299                 {
01300                     PointSource pt;
01301                     Eigen::Vector3d m = ndcell->getMean();
01302                     pt.x = m(0);
01303                     pt.y = m(1);
01304                     pt.z = m(2);
01305                     res.points.push_back(pt);
01306                 }
01307             }
01308             it++;
01309         }
01310         return res;
01311 
01312     }
01313 
01314     if(subsampleType == "TREE")
01315     {
01316         //   double subsampleRes = 0.2;
01317         pcl::PointCloud<PointSource> res;
01318         //LazyGrid prototype(subsampleRes);
01319         //NDTMap ndt( &prototype );
01320 
01321         NDTMap<PointSource> ndt( new OctTree<PointSource>() );
01322         ndt.loadPointCloud( original );
01323         ndt.computeNDTCells();
01324         typename std::vector<Cell<PointSource>*>::iterator it = ndt.getMyIndex()->begin();
01325 
01326         while(it!=ndt.getMyIndex()->end())
01327         {
01328             NDTCell<PointSource>* ndcell = dynamic_cast<NDTCell<PointSource>*>(*it);
01329             if(ndcell!=NULL)
01330             {
01331                 if(ndcell->points_.size() > 0)
01332                 {
01333                     res.points.push_back(ndcell->points_.front());
01334                 }
01335             }
01336             it++;
01337         }
01338         return res;
01339     }
01340 
01341 
01342     return original;
01343 }
01344 
01345 template <typename PointSource, typename PointTarget>
01346 double NDTMatcherP2D<PointSource,PointTarget>::normalizeAngle(double a)
01347 {
01348     //set the angle between -M_PI and M_PI
01349     return atan2(sin(a), cos(a));
01350 
01351 }
01352 
01353 }


ndt_registration
Author(s): Todor Stoyanov, Jari Saarinen, Henrik Andreasson
autogenerated on Mon Oct 6 2014 03:19:30