ndt_fuser_hmt.h
Go to the documentation of this file.
00001 #ifndef NDT_FUSER_HMT_HH
00002 #define NDT_FUSER_HMT_HH
00003 
00004 #include <ndt_visualisation/ndt_viz.h>
00005 #include <ndt_map/ndt_map.h>
00006 #include <ndt_map/ndt_map_hmt.h>
00007 #include <ndt_registration/ndt_matcher_d2d_2d.h>
00008 #include <ndt_registration/ndt_matcher_d2d.h>
00009 #include <pointcloud_vrml/pointcloud_utils.h>
00010 
00011 #include <Eigen/Eigen>
00012 #include <pcl/point_cloud.h>
00013 
00014 //#define BASELINE
00015 
00016 namespace lslgeneric {
00022 template <typename PointT>
00023 class NDTFuserHMT{
00024     public:
00025         Eigen::Affine3d Tnow, Tlast_fuse, Todom; 
00026         //lslgeneric::NDTMapHMT<PointT> *map;  ///< da map
00027         lslgeneric::NDTMap<PointT> *map;  
00028         bool checkConsistency;            
00029         double max_translation_norm, max_rotation_norm;
00030         double sensor_range;
00031         bool be2D, doMultires, fuseIncomplete, beHMT;
00032         int ctr;
00033         std::string prefix;
00034         std::string hmt_map_dir;
00035         NDTViz<PointT> *viewer;
00036         FILE *fAddTimes, *fRegTimes;
00037 
00038         NDTFuserHMT(double map_resolution, double map_size_x_, double map_size_y_, double map_size_z_, double sensor_range_ = 3, 
00039                     bool visualize_=false, bool be2D_=false, bool doMultires_=false, bool fuseIncomplete_=false, int max_itr=30, 
00040                     std::string prefix_="", bool beHMT_=true, std::string hmt_map_dir_="map", bool _step_control=true){
00041             isInit = false;
00042             resolution = map_resolution;
00043             sensor_pose.setIdentity();
00044             checkConsistency = false;
00045             visualize = true;
00046             translation_fuse_delta = 0.05;
00047             rotation_fuse_delta = 0.01;
00048             max_translation_norm = 1.;
00049             max_rotation_norm = M_PI/4;
00050             map_size_x = map_size_x_;
00051             map_size_y = map_size_y_;
00052             map_size_z = map_size_z_;
00053             visualize = visualize_;
00054             be2D = be2D_;
00055             sensor_range = sensor_range_;
00056             prefix = prefix_;
00057             doMultires = doMultires_;
00058             ctr =0;
00059             viewer = new NDTViz<PointT>(visualize);
00060             localMapSize<<sensor_range_,sensor_range_,map_size_z_;
00061             fuseIncomplete = fuseIncomplete_;
00062             matcher.ITR_MAX = max_itr;
00063             matcher2D.ITR_MAX = max_itr;
00064             matcher.step_control=_step_control;
00065             matcher2D.step_control=_step_control;
00066             beHMT = beHMT_;
00067             hmt_map_dir=hmt_map_dir_;
00068 
00069             
00070             char fname[1000];
00071             snprintf(fname,999,"%s_addTime.txt",prefix.c_str());
00072             fAddTimes = fopen(fname,"w");
00073 
00074             std::cout<<"MAP: resolution: "<<resolution<<" size "<<map_size_x<<" "<<map_size_y<<" "<<map_size_z<<" sr "<<sensor_range<<std::endl;
00075         }
00076         ~NDTFuserHMT()
00077         {
00078             delete map;
00079             delete viewer;
00080             if(fAddTimes!=NULL) fclose(fAddTimes);
00081             if(fRegTimes!=NULL) fclose(fRegTimes);
00082         }
00083 
00084         double getDoubleTime()
00085         {
00086             struct timeval time;
00087             gettimeofday(&time,NULL);
00088             return time.tv_sec + time.tv_usec * 1e-6;
00089         }
00090         void setSensorPose(Eigen::Affine3d spose){
00091             sensor_pose = spose;
00092         }
00093         
00094         bool wasInit()
00095         {
00096             return isInit;
00097         }
00098 
00099         bool saveMap() {
00100             if(!isInit) return false;
00101             if(map == NULL) return false;
00102             if(beHMT) {
00103                 lslgeneric::NDTMapHMT<PointT> *map_hmt = dynamic_cast<lslgeneric::NDTMapHMT<PointT>*> (map);
00104                 if(map_hmt==NULL) return false;
00105                 return (map_hmt->writeTo()==0);
00106             } else {
00107                 char fname[1000];
00108                 snprintf(fname,999,"%s/%s_map.jff",hmt_map_dir.c_str(),prefix.c_str());
00109                 return (map->writeToJFF(fname) == 0);
00110             }
00111         }
00112 
00116         void initialize(Eigen::Affine3d initPos, pcl::PointCloud<PointT> &cloud, bool preLoad=false){
00118             lslgeneric::transformPointCloudInPlace(sensor_pose, cloud);
00119             lslgeneric::transformPointCloudInPlace(initPos, cloud);
00120             Tnow = initPos;
00121 //#ifdef BASELINE
00122 //#else
00123             if(beHMT) {
00124                 map = new lslgeneric::NDTMapHMT<PointT>(resolution,
00125                         Tnow.translation()(0),Tnow.translation()(1),Tnow.translation()(2),
00126                         map_size_x,map_size_y,map_size_z,sensor_range,hmt_map_dir,true);
00127                 if(preLoad) {
00128                     lslgeneric::NDTMapHMT<PointT> *map_hmt = dynamic_cast<lslgeneric::NDTMapHMT<PointT>*> (map);
00129                     std::cout<<"Trying to pre-load maps at "<<initPos.translation()<<std::endl;
00130                     map_hmt->tryLoadPosition(initPos.translation());
00131                 }
00132             } else {
00133                 map = new lslgeneric::NDTMap<PointT>(new lslgeneric::LazyGrid<PointT>(resolution));
00134                 map->initialize(Tnow.translation()(0),Tnow.translation()(1),Tnow.translation()(2),map_size_x,map_size_y,map_size_z);
00135             }
00136 //#endif
00137             map->addPointCloud(Tnow.translation(),cloud, 0.1, 100.0, 0.1);
00138             //map->addPointCloudMeanUpdate(Tnow.translation(),cloud,localMapSize, 1e5, 1250, map_size_z/2, 0.06);
00139             //map->addPointCloudMeanUpdate(Tnow.translation(),cloud,localMapSize, 0.1, 100.0, 0.1);
00140             map->computeNDTCells(CELL_UPDATE_MODE_SAMPLE_VARIANCE, 1e5, 255, Tnow.translation(), 0.1);
00141             isInit = true;
00142             Tlast_fuse = Tnow;
00143             Todom = Tnow;
00144             if(visualize) 
00145             {
00146                 viewer->plotNDTSAccordingToOccupancy(-1,map); 
00147                 viewer->plotLocalNDTMap(cloud,resolution);
00148                 viewer->addTrajectoryPoint(Tnow.translation()(0),Tnow.translation()(1),Tnow.translation()(2)+0.2,1,0,0);
00149                 viewer->addTrajectoryPoint(Todom.translation()(0),Todom.translation()(1),Todom.translation()(2)+0.2,0,1,0);
00150                 viewer->displayTrajectory();
00151                 viewer->setCameraPointing(Tnow.translation()(0),Tnow.translation()(1),Tnow.translation()(2)+3);
00152                 viewer->repaint();      
00153             }
00154         }
00155 
00160         Eigen::Affine3d update(Eigen::Affine3d Tmotion, pcl::PointCloud<PointT> &cloud){
00161             if(!isInit){
00162                 fprintf(stderr,"NDT-FuserHMT: Call Initialize first!!\n");
00163                 return Tnow;
00164             }
00165             Todom = Todom * Tmotion; //we track this only for display purposes!
00166             double t0=0,t1=0,t2=0,t3=0,t4=0,t5=0,t6=0;
00168             lslgeneric::transformPointCloudInPlace(sensor_pose, cloud);
00169             t0 = getDoubleTime();
00171             lslgeneric::NDTMap<PointT> ndlocal(new lslgeneric::LazyGrid<PointT>(resolution));
00172             ndlocal.guessSize(0,0,0,sensor_range,sensor_range,map_size_z);
00173             ndlocal.loadPointCloud(cloud,sensor_range);
00174             ndlocal.computeNDTCells(CELL_UPDATE_MODE_SAMPLE_VARIANCE);
00175             //pass through ndlocal and set all cells with vertically pointing normals to non-gaussian :-O
00176             /*SpatialIndex<PointT> *index = ndlocal.getMyIndex();
00177             typename SpatialIndex<PointT>::CellVectorItr it = index->begin();
00178             while (it != index->end())
00179             {
00180                 NDTCell<PointT> *cell = dynamic_cast<NDTCell<PointT>*> (*it);
00181                 if(cell!=NULL)
00182                 {
00183                     if(cell->hasGaussian_)
00184                     {
00185                         if(cell->getClass() == NDTCell<PointT>::HORIZONTAL) {
00186                             cell->hasGaussian_ = false;
00187                         }
00188                     }
00189                 }
00190                 it++;
00191             }*/
00192 
00193             t1 = getDoubleTime();
00194             Eigen::Affine3d Tinit = Tnow * Tmotion;
00195             if(doMultires) {
00196                 //create two ndt maps with resolution = 3*resolution (or 5?)
00197                 lslgeneric::NDTMap<PointT> ndlocalLow(new lslgeneric::LazyGrid<PointT>(3*resolution));
00198                 ndlocalLow.guessSize(0,0,0,sensor_range,sensor_range,map_size_z);
00199                 ndlocalLow.loadPointCloud(cloud,sensor_range);
00200                 ndlocalLow.computeNDTCells(CELL_UPDATE_MODE_SAMPLE_VARIANCE);
00201 
00202                 lslgeneric::NDTMap<PointT> mapLow(new lslgeneric::LazyGrid<PointT>(3*resolution));
00203                 //add distros
00204                 double cx,cy,cz;
00205                 if(!map->getCentroid(cx, cy, cz)){
00206                     fprintf(stderr,"Centroid NOT Given-abort!\n");
00207                 }
00208                 mapLow.initialize(cx,cy,cz,3*map_size_x,3*map_size_y,map_size_z);
00209 
00210                 std::vector<lslgeneric::NDTCell<PointT>*> ndts;
00211                 ndts = map->getAllCells(); //this copies cells?
00212         
00213                 for(int i=0; i<ndts.size(); i++)        
00214                 {
00215                     NDTCell<PointT> *cell = ndts[i];
00216                     if(cell!=NULL)
00217                     {
00218                         if(cell->hasGaussian_)
00219                         {
00220                             Eigen::Vector3d m = cell->getMean();        
00221                             Eigen::Matrix3d cov = cell->getCov();
00222                             unsigned int nump = cell->getN();
00223                             mapLow.addDistributionToCell(cov, m,nump);
00224                         }
00225                     }
00226                     delete cell;
00227                 }
00228                 //do match
00229                 if(matcher2D.match( mapLow, ndlocalLow,Tinit,true)){
00230                     //if success, set Tmotion to result
00231                     t2 = getDoubleTime();
00232                     //std::cout<<"success: new initial guess! t= "<<t2-t1<<std::endl;
00233                 } else {
00234                     Tinit = Tnow * Tmotion;
00235                 }           
00236             }
00237             
00238             if(be2D) {
00239                 t2 = getDoubleTime();
00240                 if(matcher2D.match( *map, ndlocal,Tinit,true) || fuseIncomplete){
00241                     t3 = getDoubleTime();
00242                     Eigen::Affine3d diff = (Tnow * Tmotion).inverse() * Tinit;
00243                     if((diff.translation().norm() > max_translation_norm || 
00244                                 diff.rotation().eulerAngles(0,1,2).norm() > max_rotation_norm) && checkConsistency){
00245                         fprintf(stderr,"****  NDTFuserHMT -- ALMOST DEFINATELY A REGISTRATION FAILURE *****\n");
00246                         Tnow = Tnow * Tmotion;
00247                     }else{
00248                         Tnow = Tinit;
00249                         lslgeneric::transformPointCloudInPlace(Tnow, cloud);
00250                         Eigen::Affine3d spose = Tnow*sensor_pose;
00251                         Eigen::Affine3d diff_fuse = Tlast_fuse.inverse()*Tnow;
00252                         if(diff_fuse.translation().norm() > translation_fuse_delta ||
00253                                 diff_fuse.rotation().eulerAngles(0,1,2).norm() > rotation_fuse_delta)
00254                         {
00255                             //std::cout<<"F: "<<spose.translation().transpose()<<" "<<spose.rotation().eulerAngles(0,1,2).transpose()<<std::endl;
00256                             t4 = getDoubleTime();
00257                             map->addPointCloudMeanUpdate(spose.translation(),cloud,localMapSize, 1e5, 1250, map_size_z/2, 0.06);
00258                             t5 = getDoubleTime();
00259                             //map->addPointCloudMeanUpdate(spose.translation(),cloud,localMapSize, 1e5, 25, 2*map_size_z, 0.06);
00260                             //map->addPointCloud(spose.translation(),cloud, 0.06, 25);
00261                             //map->computeNDTCells(CELL_UPDATE_MODE_SAMPLE_VARIANCE, 1e5, 255, spose.translation(), 0.1);
00262                             //t4 = getDoubleTime();
00263                             //std::cout<<"match: "<<t3-t2<<" addPointCloud: "<<t5-t4<<" ndlocal "<<t1-t0<<" total: "<<t5-t0<<std::endl;
00264                             Tlast_fuse = Tnow;
00265                             if(visualize) //&&ctr%20==0) 
00266                             {
00267                                 if(ctr%20==0) {
00268                                     viewer->plotNDTSAccordingToOccupancy(-1,map); 
00269                                     viewer->plotLocalNDTMap(cloud,resolution); 
00270                                 }
00271                                 viewer->addTrajectoryPoint(Tnow.translation()(0),Tnow.translation()(1),Tnow.translation()(2),1,0,0);
00272                                 viewer->addTrajectoryPoint(Todom.translation()(0),Todom.translation()(1),Todom.translation()(2),0,1,0);
00273                                 viewer->displayTrajectory();
00274                                 viewer->setCameraPointing(Tnow.translation()(0),Tnow.translation()(1),Tnow.translation()(2)+3);
00275                                 viewer->repaint();      
00276                             }
00277                             ctr++;
00278                         }
00279                     }
00280                 }else{
00281                     t3 = getDoubleTime();
00282                     Tnow = Tnow * Tmotion;
00283                 }
00284 
00285             }
00286             else
00287             {
00288                 
00289                 t2 = getDoubleTime();
00290                 if(matcher.match( *map, ndlocal,Tinit,true) || fuseIncomplete){
00291                     t3 = getDoubleTime();
00292                     Eigen::Affine3d diff = (Tnow * Tmotion).inverse() * Tinit;
00293                     
00294                     if((diff.translation().norm() > max_translation_norm || 
00295                                 diff.rotation().eulerAngles(0,1,2).norm() > max_rotation_norm) && checkConsistency){
00296                         fprintf(stderr,"****  NDTFuserHMT -- ALMOST DEFINATELY A REGISTRATION FAILURE *****\n");
00297                         Tnow = Tnow * Tmotion;
00298                         //save offending map:
00299                         //map->writeToJFF("map.jff");
00300                         //ndlocal.writeToJFF("local.jff");
00301                     }else{
00302                         Tnow = Tinit;
00303                         //Tnow = Tnow * Tmotion;
00304                         lslgeneric::transformPointCloudInPlace(Tnow, cloud);
00305                         Eigen::Affine3d spose = Tnow*sensor_pose;
00306                         Eigen::Affine3d diff_fuse = Tlast_fuse.inverse()*Tnow;
00307                         if(diff_fuse.translation().norm() > translation_fuse_delta ||
00308                                 diff_fuse.rotation().eulerAngles(0,1,2).norm() > rotation_fuse_delta)
00309                         {
00310                             //std::cout<<"F: "<<spose.translation().transpose()<<" "<<spose.rotation().eulerAngles(0,1,2).transpose()<<std::endl;
00311                             t4 = getDoubleTime();
00312                             map->addPointCloudMeanUpdate(spose.translation(),cloud,localMapSize, 1e5, 1250, map_size_z/2, 0.06);
00313                             t5 = getDoubleTime();
00314                             //map->addPointCloudMeanUpdate(spose.translation(),cloud,localMapSize, 1e5, 25, 2*map_size_z, 0.06);
00315                             //map->addPointCloud(spose.translation(),cloud, 0.06, 25);
00316                             //map->computeNDTCells(CELL_UPDATE_MODE_SAMPLE_VARIANCE, 1e5, 255, spose.translation(), 0.1);
00317                             //t4 = getDoubleTime();
00318                             //std::cout<<"match: "<<t3-t2<<" addPointCloud: "<<t5-t4<<" ndlocal "<<t1-t0<<" total: "<<t5-t0<<std::endl;
00319                             Tlast_fuse = Tnow;
00320                             if(visualize) //&&ctr%20==0) 
00321                             {
00322                                 viewer->plotNDTSAccordingToOccupancy(-1,map); 
00323                                 viewer->plotLocalNDTMap(cloud,resolution); 
00324                             }
00325                             ctr++;
00326                         }
00327                     }
00328                 }else{
00329                     t3 = getDoubleTime();
00330                     Tnow = Tnow * Tmotion;
00331                 }
00332             }
00333             
00334             t6 = getDoubleTime();
00335             if(fAddTimes!=NULL) {
00336                 fprintf(fAddTimes,"%lf %lf %lf\n",t3-t2,t5-t4,t6-t0);
00337                 fflush(fAddTimes);
00338             }
00339 
00340             return Tnow;
00341         }
00342 
00343     private:
00344         bool isInit;
00345 
00346         double resolution; 
00347         double map_size;
00348         
00349         double translation_fuse_delta, rotation_fuse_delta;
00350         double map_size_x;
00351         double map_size_y;
00352         double map_size_z;
00353         bool visualize;
00354 
00355         Eigen::Affine3d sensor_pose;
00356         lslgeneric::NDTMatcherD2D<PointT,PointT> matcher;
00357         lslgeneric::NDTMatcherD2D_2D<PointT,PointT> matcher2D;
00358         Eigen::Vector3d localMapSize;
00359 
00360     public:
00361         EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00362 
00363 };
00364 }
00365 #endif


ndt_fuser
Author(s): Todor Stoyanov, Jari Saarinen
autogenerated on Mon Oct 6 2014 03:20:34