00001 #include <Eigen/Eigen>
00002 #include <pcl/point_cloud.h>
00003 #include <pcl/features/feature.h>
00004
00005 #include <string>
00006 #include <climits>
00007
00008 #include <ndt_map/oc_tree.h>
00009 #include <ndt_map/lazy_grid.h>
00010 #include <ndt_map/cell_vector.h>
00011
00012 #include <cstring>
00013 #include <cstdio>
00014
00015 #ifndef _JFFVERSION_
00016 #define _JFFVERSION_ "#JFF V0.50"
00017 #endif
00018 #define JFFERR(x) std::cerr << x << std::endl; return -1;
00019
00020 namespace lslgeneric
00021 {
00022
00023 template<typename PointT>
00024 void NDTMapHMT<PointT>::initializeGrids() {
00025
00026 if(grids_init) return;
00027
00028 LazyGrid<PointT> *proto = dynamic_cast<LazyGrid<PointT>*>(index_);
00029 if(proto == NULL) return;
00030
00031 double centerX,centerY,centerZ;
00032 proto->getCenter(centerX, centerY, centerZ);
00033 double sizeX,sizeY,sizeZ;
00034 proto->getGridSizeInMeters(sizeX, sizeY, sizeZ);
00035 std::cout<<"inti grids: res="<<resolution<<" cen "<<centerX<<" "<<centerY<<" "<<centerZ<<" size "<<sizeX<<" "<<sizeY<<" "<<sizeZ<<std::endl;
00036
00037 for(int i=-1; i<2; i++) {
00038 for(int j=-1; j<2; j++) {
00039 if(i==0 && j==0) {
00040
00041 LazyGrid<PointT> *lz = dynamic_cast<LazyGrid<PointT>*>(index_);
00042 grid_[i+1][j+1] = lz;
00043 } else {
00044 double cenX,cenY;
00045 cenX = centerX+(double)i*sizeX;
00046 cenY = centerY+(double)j*sizeY;
00047 std::cout<<i<<":"<<j<<" center "<<cenX<<" "<<cenY<<std::endl;
00048 NDTCell<PointT> *ptCell = new NDTCell<PointT>();
00049 LazyGrid<PointT> *lz = new LazyGrid<PointT>(resolution);
00050 lz->setCellType(ptCell);
00051 lz->setCenter(cenX,cenY,centerZ);
00052 lz->setSize(sizeX,sizeY,sizeZ);
00053 lz->initializeAll();
00054 grid_[i+1][j+1] = lz;
00055 delete ptCell;
00056 }
00057 }
00058 }
00059 grids_init = true;
00060
00061 }
00062
00063 template<typename PointT>
00064 bool NDTMapHMT<PointT>::tryLoadPosition(const Eigen::Vector3d &newPos) {
00065
00066 if(my_directory == "" || !grids_init)
00067 {
00068 std::cout<<"cannot load from directory!\n";
00069 return false;
00070 }
00071
00072 LazyGrid<PointT> *proto = dynamic_cast<LazyGrid<PointT>*>(index_);
00073 if(proto == NULL) return false;
00074 double sizeX,sizeY,sizeZ;
00075 double centerX,centerY,centerZ;
00076 proto->getGridSizeInMeters(sizeX, sizeY, sizeZ);
00077
00078 std::string meta = my_directory;
00079 meta += "/metadata.txt";
00080
00081 FILE* meta_f = fopen(meta.c_str(),"a+");
00082 if(meta_f==0) return false;
00083 char *line = NULL;
00084 size_t len;
00085 bool found=false;
00086
00087
00088
00089
00090
00091
00092 if(getline(&line,&len,meta_f) >0 ) {
00093 char *tk = strtok(line," ");
00094 if(tk==NULL) return false;
00095 if (strncmp(tk,"VERSION",7) == 0) {
00096 tk = strtok(NULL," ");
00097 if(tk==NULL) return false;
00098 if(strncmp(tk,"2.0",3) == 0) {
00099 if(!getline(&line,&len,meta_f) >0 ) {
00100 return false;
00101 }
00102 tk = strtok(line," ");
00103 if(tk==NULL) return false;
00104 if(strncmp(tk,"SIZE",4) != 0) return false;
00105 tk = strtok(NULL," ");
00106 double sizeMeta = atof(tk);
00107 if(fabsf(sizeMeta - sizeX) > 0.01) {
00108 std::cerr<<"cannot load map, different grid size used... reverting to empty map\n";
00109 return false;
00110 }
00111 }
00112
00113
00114 } else {
00115
00116 std::cerr<<"metafile version 1.0, no protection against different grid size\n";
00117 fclose(meta_f);
00118 meta_f = fopen(meta.c_str(),"a+");
00119 }
00120 }
00121
00122 while(getline(&line,&len,meta_f) >0 )
00123 {
00124 pcl::PointXYZ cen;
00125 char *token = strtok(line," ");
00126 if(token==NULL) return -1;
00127 cen.x = atof(token);
00128 token = strtok(NULL," ");
00129 if(token==NULL) return -1;
00130 cen.y = atof(token);
00131 token = strtok(NULL," ");
00132 if(token==NULL) return -1;
00133 cen.z = atof(token);
00134
00135 token = strtok(NULL," ");
00136 if(token==NULL) return -1;
00137
00138 if(fabsf(newPos(0)-cen.x) < sizeX/2 &&
00139 fabsf(newPos(1)-cen.y) < sizeY/2 && fabsf(newPos(2)-cen.z) < sizeZ/2) {
00140 found = true;
00141 centerX = cen.x; centerY = cen.y; centerZ = cen.z;
00142
00143 break;
00144 }
00145
00146 }
00147 fclose(meta_f);
00148 if(!found) {
00149 std::cerr<<"Map file not found!\n";
00150 return false;
00151 }
00152
00153
00154 LazyGrid<PointT> *tmp_grid[3][3];
00155 for(int i=-1; i<2; i++) {
00156 for(int j=-1; j<2; j++) {
00157 double cenX,cenY;
00158 cenX = centerX+(double)i*sizeX;
00159 cenY = centerY+(double)j*sizeY;
00160 std::cout<<i<<":"<<j<<" NEW center "<<cenX<<" "<<cenY<<std::endl;
00161 if(this->tryLoad(cenX,cenY,centerZ,tmp_grid[i+1][j+1])) {
00162 delete grid_[i+1][j+1];
00163 grid_[i+1][j+1] = tmp_grid[i+1][j+1];
00164 } else {
00165 grid_[i+1][j+1]->setCenter(cenX,cenY,centerZ);
00166 }
00167 }
00168 }
00169 return true;
00170 }
00171
00172 template<typename PointT>
00173 void NDTMapHMT<PointT>::setInsertPosition(const Eigen::Vector3d &newPos) {
00174
00175 last_insert = newPos;
00176 PointT newPosP;
00177 newPosP.x = newPos(0);
00178 newPosP.y = newPos(1);
00179 newPosP.z = newPos(2);
00180
00181 if(grid_[1][1]->isInside(newPosP)) return;
00182
00183 std::cout<<"We are outside the central grid, time to switch pointers\n";
00184
00185 this->writeTo();
00186
00187
00188 int qi=0,qj=0;
00189 for(int i=-1; i<2; i++) {
00190 for(int j=-1; j<2; j++) {
00191 if(grid_[i+1][j+1]->isInside(newPosP)) {
00192
00193 qi=i; qj=j;
00194 }
00195 }
00196 }
00197 LazyGrid<PointT> *tmp_grid[3][3];
00198 bool copy[3][3];
00199
00200 double centerX,centerY,centerZ;
00201 grid_[qi+1][qj+1]->getCenter(centerX, centerY, centerZ);
00202 double sizeX,sizeY,sizeZ;
00203 grid_[qi+1][qj+1]->getGridSizeInMeters(sizeX, sizeY, sizeZ);
00204 for(int i=0; i<3; i++) {
00205 for(int j=0; j<3; j++) {
00206 copy[i][j]=false;
00207 }
00208 }
00209 int oi,oj;
00210 for(int i=0; i<3; i++) {
00211 for(int j=0; j<3; j++) {
00212 oi = i+qi;
00213 oj = j+qj;
00214 if(oi>=0 && oi<3 && oj>=0 &&oj<3) {
00215
00216
00217 copy[oi][oj] = true;
00218 tmp_grid[i][j] = grid_[oi][oj];
00219 } else {
00220
00221 double cenX,cenY;
00222 cenX = centerX+(double)(i-1)*sizeX;
00223 cenY = centerY+(double)(j-1)*sizeY;
00224 if(!this->tryLoad(cenX,cenY,centerZ,tmp_grid[i][j])) {
00225
00226
00227
00228
00229 NDTCell<PointT> *ptCell = new NDTCell<PointT>();
00230 LazyGrid<PointT> *lz = new LazyGrid<PointT>(resolution);
00231 lz->setCellType(ptCell);
00232 lz->setCenter(cenX,cenY,centerZ);
00233 lz->setSize(sizeX,sizeY,sizeZ);
00234 lz->initializeAll();
00235 tmp_grid[i][j] = lz;
00236 delete ptCell;
00237 } else {
00238
00239 }
00240 }
00241 }
00242 }
00243
00244
00245 for(int i=0; i<3; i++) {
00246 for(int j=0; j<3; j++) {
00247 if(!copy[i][j]) {
00248
00249 delete grid_[i][j];
00250 }
00251 grid_[i][j] = tmp_grid[i][j];
00252 }
00253 }
00254
00255 }
00265 template<typename PointT>
00266 void NDTMapHMT<PointT>::loadPointCloud(const pcl::PointCloud<PointT> &pc, double range_limit)
00267 {
00268
00269
00270 typename pcl::PointCloud<PointT>::const_iterator it = pc.points.begin();
00271 NDTCell<PointT> *ptCell;
00272
00273 while(it!=pc.points.end())
00274 {
00275 Eigen::Vector3d d;
00276 if(std::isnan(it->x) ||std::isnan(it->y) ||std::isnan(it->z))
00277 {
00278 it++;
00279 continue;
00280 }
00281
00282
00283
00284
00285
00286
00287
00288
00289
00290
00291 for(int i=0; i<3; ++i) {
00292 for(int j=0; j<3; ++j) {
00293 if(grid_[i][j]->isInside(*it)) {
00294 ptCell = dynamic_cast<NDTCell<PointT>*>(grid_[i][j]->addPoint(*it));
00295 if(ptCell!=NULL) {
00296 update_set.insert(ptCell);
00297 }
00298 break;
00299 }
00300 }
00301 }
00302 it++;
00303 }
00304 isFirstLoad_ = false;
00305 }
00306
00310 template<typename PointT>
00311 void NDTMapHMT<PointT>::addPointCloud(const Eigen::Vector3d &origin, const pcl::PointCloud<PointT> &pc, double classifierTh, double maxz, double sensor_noise, double occupancy_limit)
00312 {
00313
00314 if(isFirstLoad_)
00315 {
00316
00317 this->loadPointCloud(pc);
00318 return;
00319 }
00320
00321 this->setInsertPosition(origin);
00322 typename pcl::PointCloud<PointT>::const_iterator it = pc.points.begin();
00323
00324 LazyGrid<PointT> *lz = grid_[1][1];
00325
00326 double centerX, centerY, centerZ;
00327 double sizeXmeters, sizeYmeters, sizeZmeters;
00328 double eps = 0.001;
00329 Eigen::Vector3d diff2;
00330 lz->getGridSizeInMeters(sizeXmeters, sizeYmeters, sizeZmeters);
00331 lz->getCenter(centerX, centerY, centerZ);
00332 PointT po, pt;
00333 Eigen::Vector3d pf;
00334 po.x = origin(0); po.y = origin(1); po.z = origin(2);
00335 NDTCell<PointT>* ptCell = NULL;
00336
00337 std::vector< NDTCell<PointT>*> cells;
00338 bool updatePositive = true;
00339
00340
00341 while(it!=pc.points.end())
00342 {
00343 if(std::isnan(it->x) ||std::isnan(it->y) ||std::isnan(it->z))
00344 {
00345 it++;
00346 continue;
00347 }
00348
00349 Eigen::Vector3d diff;
00350 diff << it->x-origin(0), it->y-origin(1), it->z-origin(2);
00351 double l = diff.norm();
00352
00353 if(l>max_range_)
00354 {
00355
00356 it++;
00357 continue;
00358 }
00359
00360 cells.clear();
00361 if(!lz->traceLineWithEndpoint(origin,*it,diff,maxz,cells,pf)) {
00362 it++;
00363 continue;
00364 }
00365
00366 diff2 << it->x-pf(0), it->y-pf(1), it->z-pf(2);
00367 if((diff2).norm() > eps) {
00368
00369 int i=0,j=0;
00370 if(it->x > centerX+sizeXmeters/2-resolution/2) {
00371 i = 1;
00372 }
00373 if(it->x < centerX-sizeXmeters/2-resolution/2) {
00374 i = -1;
00375 }
00376 if(it->y > centerY+sizeYmeters/2-resolution/2) {
00377 j = 1;
00378 }
00379 if(it->y < centerY-sizeYmeters/2-resolution/2) {
00380 j = -1;
00381 }
00382 std::vector< NDTCell<PointT>*> cells2;
00383 if(!grid_[i+1][j+1]->traceLineWithEndpoint(pf,*it,diff2,maxz,cells,pf)) {
00384 std::cerr<<"ray outside central map: at "<<it->x<<" "<<it->y<<" "<<it->z<<" with diff "<<diff.transpose()<<" starts at " <<origin.transpose()
00385 <<" stops at "<<pf.transpose()<<" diff2 is "<<diff2.transpose()<<" check grid "<<i<<" "<<j<<std::endl;
00386 it++;
00387 continue;
00388 }
00389 cells.insert(cells.begin(),cells2.begin(),cells2.end());
00390
00391 }
00392
00393 for(unsigned int i=0; i<cells.size(); i++)
00394 {
00395 ptCell = cells[i];
00396 if(ptCell != NULL)
00397 {
00398 double l2target = 0;
00399 if(ptCell->hasGaussian_)
00400 {
00401 Eigen::Vector3d out, pend,vpt;
00402 pend << it->x,it->y,it->z;
00403 double lik = ptCell->computeMaximumLikelihoodAlongLine(po, *it, out);
00404 l2target = (out-pend).norm();
00405
00406 double dist = (origin-out).norm();
00407 if(dist > l) continue;
00408
00409 l2target = (out-pend).norm();
00410
00411 double sigma_dist = 0.5 * (dist/30.0);
00412 double snoise = sigma_dist + sensor_noise;
00413 double thr =exp(-0.5*(l2target*l2target)/(snoise*snoise));
00414 lik *= (1.0-thr);
00415 if(lik<0.3) continue;
00416 lik = 0.1*lik+0.5;
00417 double logoddlik = log( (1.0-lik)/(lik) );
00418 ptCell->updateOccupancy(logoddlik, occupancy_limit);
00419 if(ptCell->getOccupancy()<=0) ptCell->hasGaussian_ = false;
00420 }
00421 else
00422 {
00423 ptCell->updateOccupancy(-0.2, occupancy_limit);
00424 if(ptCell->getOccupancy()<=0) ptCell->hasGaussian_ = false;
00425 }
00426 }
00427 }
00428 if(updatePositive) {
00429 int i=0,j=0;
00430 if(it->x > centerX+sizeXmeters/2-resolution/2) {
00431 i = 1;
00432 }
00433 if(it->x < centerX-sizeXmeters/2-resolution/2) {
00434 i = -1;
00435 }
00436 if(it->y > centerY+sizeYmeters/2-resolution/2) {
00437 j = 1;
00438 }
00439 if(it->y < centerY-sizeYmeters/2-resolution/2) {
00440 j = -1;
00441 }
00442 if(grid_[i+1][j+1]->isInside(*it)) {
00443 ptCell = dynamic_cast<NDTCell<PointT>*>(grid_[i+1][j+1]->addPoint(*it));
00444 if(ptCell!=NULL) {
00445 update_set.insert(ptCell);
00446 }
00447 }
00448 }
00449 it++;
00450 }
00451 isFirstLoad_ = false;
00452 }
00453
00457
00472 template<typename PointT>
00473 void NDTMapHMT<PointT>::addPointCloudMeanUpdate(const Eigen::Vector3d &origin,
00474 const pcl::PointCloud<PointT> &pc,
00475 const Eigen::Vector3d &localmapsize,
00476 unsigned int maxnumpoints, float occupancy_limit,double maxz, double sensor_noise){
00477
00478
00479
00480 if(isFirstLoad_){
00481
00482 loadPointCloud(pc);
00483 return;
00484 }
00485 this->setInsertPosition(origin);
00486
00487 LazyGrid<PointT> *lz = grid_[1][1];
00489 double sizeXmeters, sizeYmeters, sizeZmeters;
00490 double eps = 0.001;
00491 lz->getGridSizeInMeters(sizeXmeters, sizeYmeters, sizeZmeters);
00492 double centerX,centerY,centerZ;
00493 lz->getCenter(centerX, centerY, centerZ);
00494 int sizeX,sizeY,sizeZ;
00495 lz->getGridSize(sizeX, sizeY, sizeZ);
00496
00497 Eigen::Vector3d old_centroid;
00498 old_centroid(0) = centerX;
00499 old_centroid(1) = centerY;
00500 old_centroid(2) = centerZ;
00501
00503 lslgeneric::NDTMap<PointT> ndlocal(new lslgeneric::LazyGrid<PointT>(resolution));
00504 ndlocal.loadPointCloudCentroid(pc,origin, old_centroid, localmapsize, max_range_);
00505 ndlocal.computeNDTCells();
00506
00508 std::vector<lslgeneric::NDTCell<PointT>*> ndts;
00509 ndts = ndlocal.getAllCells();
00510
00511 NDTCell<PointT>* ptCell = NULL;
00512 std::vector< NDTCell<PointT>*> cells;
00513
00514 PointT pt;
00515 PointT po,mpoint;
00516 po.x = origin(0); po.y = origin(1); po.z = origin(2);
00517
00518 bool updatePositive = true;
00519 int num_high = 0;
00520 for(unsigned int it=0;it<ndts.size();it++)
00521 {
00522 if(ndts[it] == NULL){
00523 fprintf(stderr,"NDTMap<PointT>::addPointCloudMeanUpdate::GOT NULL FROM MAP -- SHOULD NEVER HAPPEN!!!\n");
00524 continue;
00525 }
00526
00527 if(!ndts[it]->hasGaussian_){
00528 fprintf(stderr,"NDTMap<PointT>::addPointCloudMeanUpdate::NO GAUSSIAN!!!! -- SHOULD NEVER HAPPEN!!!\n");
00529 continue;
00530 }
00531
00532 int numpoints = ndts[it]->getN();
00533
00534 if(numpoints<=0){
00535 fprintf(stderr,"addPointCloudMeanUpdate::Number of points in distribution<=0!!");
00536 continue;
00537 }
00538 Eigen::Vector3d diff,diff2,pf;
00539 Eigen::Vector3d m = ndts[it]->getMean();
00540 mpoint.x = m(0);
00541 mpoint.y = m(1);
00542 mpoint.z = m(2);
00543 diff = m-origin;
00544 double l = diff.norm();
00545
00546 if(l>max_range_)
00547 {
00548
00549 it++;
00550 continue;
00551 }
00552 cells.clear();
00553 if(!lz->traceLineWithEndpoint(origin,mpoint,diff,maxz,cells,pf)) {
00554 it++;
00555 continue;
00556 }
00557
00558 diff2 = m-pf;
00559 if((diff2).norm() > eps) {
00560
00561 int i=0,j=0;
00562 if(mpoint.x > centerX+sizeXmeters/2-resolution/2) {
00563 i = 1;
00564 }
00565 if(mpoint.x < centerX-sizeXmeters/2-resolution/2) {
00566 i = -1;
00567 }
00568 if(mpoint.y > centerY+sizeYmeters/2-resolution/2) {
00569 j = 1;
00570 }
00571 if(mpoint.y < centerY-sizeYmeters/2-resolution/2) {
00572 j = -1;
00573 }
00574 std::vector< NDTCell<PointT>*> cells2;
00575 if(!grid_[i+1][j+1]->traceLineWithEndpoint(pf,mpoint,diff2,maxz,cells,pf)) {
00576 std::cerr<<"ray outside central map: at "<<mpoint.x<<" "<<mpoint.y<<" "<<mpoint.z<<" with diff "<<diff.transpose()<<" starts at " <<origin.transpose()
00577 <<" stops at "<<pf.transpose()<<" diff2 is "<<diff2.transpose()<<" check grid "<<i<<" "<<j<<std::endl;
00578 it++;
00579 continue;
00580 }
00581 cells.insert(cells.begin(),cells2.begin(),cells2.end());
00582
00583 }
00584
00585 for(unsigned int i=0; i<cells.size(); i++)
00586 {
00587 ptCell = cells[i];
00588
00589 if(ptCell != NULL){
00590 double l2target = 0;
00591 if(ptCell->hasGaussian_)
00592 {
00593 Eigen::Vector3d out, pend,vpt;
00594 pend = m;
00595 double lik = ptCell->computeMaximumLikelihoodAlongLine(po, mpoint, out);
00596 l2target = (out-pend).norm();
00597
00598 double dist = (origin-out).norm();
00599 if(dist > l) continue;
00600
00601 l2target = (out-pend).norm();
00602
00603 double sigma_dist = 0.5 * (dist/30.0);
00604 double snoise = sigma_dist + sensor_noise;
00605 double thr =exp(-0.5*(l2target*l2target)/(snoise*snoise));
00606 lik *= (1.0-thr);
00607 if(lik<0.3) continue;
00608 lik = 0.1*lik+0.5;
00609 double logoddlik = log( (1.0-lik)/(lik) );
00610 ptCell->updateOccupancy(numpoints*logoddlik, occupancy_limit);
00611 if(ptCell->getOccupancy()<=0) ptCell->hasGaussian_ = false;
00612 }
00613 else
00614 {
00615 ptCell->updateOccupancy(-0.2*numpoints, occupancy_limit);
00616 if(ptCell->getOccupancy()<=0) ptCell->hasGaussian_ = false;
00617 }
00618 }
00619 else{
00620 std::cerr<<"PANIC!!\n";
00621 index_->addPoint(pt);
00622 }
00623 }
00624 if(updatePositive){
00625 Eigen::Matrix3d ucov = ndts[it]->getCov();
00626 float r,g,b;
00627 ndts[it]->getRGB(r,g,b);
00628 addDistributionToCell(ucov, m, numpoints, r, g,b,maxnumpoints,occupancy_limit);
00629 }
00630 }
00631
00632 for(unsigned int i=0;i<ndts.size();i++) delete ndts[i];
00633 isFirstLoad_ = false;
00634
00635
00636
00637 }
00638
00642 template<typename PointT>
00643 void NDTMapHMT<PointT>::addDistributionToCell(const Eigen::Matrix3d &ucov, const Eigen::Vector3d &umean, unsigned int numpointsindistribution,
00644 float r, float g,float b, unsigned int maxnumpoints, float max_occupancy)
00645 {
00646 PointT pt;
00647 pt.x = umean[0];
00648 pt.y = umean[1];
00649 pt.z = umean[2];
00650
00651 double centerX,centerY,centerZ;
00652 grid_[1][1]->getCenter(centerX, centerY, centerZ);
00653 double sizeXmeters, sizeYmeters, sizeZmeters;
00654 grid_[1][1]->getGridSizeInMeters(sizeXmeters, sizeYmeters, sizeZmeters);
00655
00656 int i=0, j=0;
00657 if(pt.x > centerX+sizeXmeters/2-resolution/2) {
00658 i = 1;
00659 }
00660 if(pt.x < centerX-sizeXmeters/2-resolution/2) {
00661 i = -1;
00662 }
00663 if(pt.y > centerY+sizeYmeters/2-resolution/2) {
00664 j = 1;
00665 }
00666 if(pt.y < centerY-sizeYmeters/2-resolution/2) {
00667 j = -1;
00668 }
00669
00670 if(grid_[i+1][j+1]->isInside(pt)) {
00671 NDTCell<PointT> *ptCell = NULL;
00672 grid_[i+1][j+1]->getNDTCellAt(pt,ptCell);
00673 if(ptCell != NULL)
00674 {
00675 ptCell->updateSampleVariance(ucov, umean, numpointsindistribution, true, max_occupancy,maxnumpoints);
00676 ptCell->setRGB(r,g,b);
00677 }
00678 }
00679
00680 }
00681
00684 template<typename PointT>
00685 void NDTMapHMT<PointT>::computeNDTCells(int cellupdatemode, unsigned int maxnumpoints, float occupancy_limit, Eigen::Vector3d origin, double sensor_noise)
00686 {
00687 conflictPoints.clear();
00688 typename std::set<NDTCell<PointT>*>::iterator it = update_set.begin();
00689 while (it != update_set.end())
00690 {
00691 NDTCell<PointT> *cell = *it;
00692 if(cell!=NULL)
00693 {
00694 cell->computeGaussian(cellupdatemode,maxnumpoints, occupancy_limit, origin,sensor_noise);
00696 if(cell->points_.size()>0)
00697 {
00698 for(unsigned int i=0; i<cell->points_.size(); i++) conflictPoints.push_back(cell->points_[i]);
00699 cell->points_.clear();
00700 }
00701 }
00702 it++;
00703 }
00704 update_set.clear();
00705 }
00706
00707
00708
00711 template<typename PointT>
00712 int NDTMapHMT<PointT>::writeTo()
00713 {
00714
00715 if(my_directory == "" || !grids_init)
00716 {
00717 std::cout<<"provide directory name\n";
00718 return -1;
00719 }
00720
00721
00722 char fname[500];
00723 std::string jffnames[3][3];
00724 bool already[3][3];
00725 double centx, centy, centz, sizeX, sizeY, sizeZ;
00726
00727 for(int i=0; i<3; i++) {
00728 for(int j=0; j<3; j++) {
00729 if(grid_[i][j]==NULL) return -1;
00730 grid_[i][j]->getCenter(centx,centy,centz);
00731 snprintf(fname,499,"lz_%05lf_%05lf_%05lf.jff",centx,centy,centz);
00732 jffnames[i][j] = fname;
00733 already[i][j] = false;
00734
00735 }
00736 }
00737 grid_[1][1]->getGridSizeInMeters(sizeX, sizeY, sizeZ);
00738
00739 std::string meta = my_directory;
00740 meta += "/metadata.txt";
00741
00742
00743 FILE* meta_f = fopen(meta.c_str(),"a+");
00744 if(meta_f==0) return -1;
00745
00746
00747 char *line = NULL;
00748 size_t len;
00749 bool first=true;
00750 size_t length = 0;
00751 double epsilon = 1e-5;
00752
00753
00754
00755
00756
00757
00758
00759 if(getline(&line,&len,meta_f) >0 ) {
00760 char *tk = strtok(line," ");
00761 if(tk==NULL) return false;
00762 if (strncmp(tk,"VERSION",7) == 0) {
00763 tk = strtok(NULL," ");
00764 if(tk==NULL) return false;
00765 if(strncmp(tk,"2.0",3) == 0) {
00766 if(!getline(&line,&len,meta_f) >0 ) {
00767 return false;
00768 }
00769 tk = strtok(line," ");
00770 if(tk==NULL) return false;
00771 if(strncmp(tk,"SIZE",4) != 0) return false;
00772 tk = strtok(NULL," ");
00773 double sizeMeta = atof(tk);
00774 if(fabsf(sizeMeta - sizeX) > 0.01) {
00775 std::cerr<<"cannot write map, different grid size used...\n";
00776 char ndir[500];
00777 snprintf(ndir,499,"%s_%5d",my_directory.c_str(),rand());
00778 my_directory = ndir;
00779 std::cerr<<"SWITCHING DIRECTORY! "<<my_directory<<std::endl;
00780 int res = mkdir(my_directory.c_str(),S_IRWXU);
00781 if(res <0 ) return false;
00782 fclose(meta_f);
00783 meta = my_directory+"/metadata.txt";
00784 meta_f = fopen(meta.c_str(),"a+");
00785 fprintf(meta_f,"VERSION 2.0\nSIZE %lf\n",sizeX);
00786 }
00787 }
00788
00789
00790 } else {
00791
00792 std::cerr<<"metafile version 1.0, no protection against different grid size\n";
00793 fclose(meta_f);
00794 meta_f = fopen(meta.c_str(),"a+");
00795 }
00796 } else {
00797
00798 fprintf(meta_f,"VERSION 2.0\nSIZE %lf\n",sizeX);
00799 }
00800
00801 while(getline(&line,&len,meta_f) >0 )
00802 {
00803 pcl::PointXYZ cen;
00804 char *token = strtok(line," ");
00805 if(token==NULL) return -1;
00806 cen.x = atof(token);
00807 token = strtok(NULL," ");
00808 if(token==NULL) return -1;
00809 cen.y = atof(token);
00810 token = strtok(NULL," ");
00811 if(token==NULL) return -1;
00812 cen.z = atof(token);
00813
00814 token = strtok(NULL," ");
00815 if(token==NULL) return -1;
00816
00817 for(int i=0; i<3; i++) {
00818 for(int j=0; j<3; j++) {
00819 if(grid_[i][j]==NULL) return -1;
00820 grid_[i][j]->getCenter(centx,centy,centz);
00821 if(fabsf(cen.x-centx) < epsilon &&
00822 fabsf(cen.y-centy) < epsilon && fabsf(cen.z-centz) < epsilon) {
00823 already[i][j] = true;
00824 token[strlen(token)-1]='\0';
00825 jffnames[i][j] = token;
00826
00827 }
00828 }
00829 }
00830
00831 }
00832
00833
00834
00835
00836
00837 for(int i=0; i<3; i++) {
00838 for(int j=0; j<3; j++) {
00839 if(grid_[i][j]==NULL) return -1;
00840 grid_[i][j]->getCenter(centx,centy,centz);
00841 if(!already[i][j]) {
00842 fprintf(meta_f,"%05lf %05lf %05lf %s\n",centx,centy,centz,jffnames[i][j].c_str());
00843
00844 }
00845 }
00846 }
00847 fclose(meta_f);
00848
00849
00850 std::string sep = "/";
00851 for(int i=0; i<3; i++) {
00852 for(int j=0; j<3; j++) {
00853 std::string path = my_directory+sep+jffnames[i][j];
00854
00855 FILE * jffout = fopen(path.c_str(), "w+b");
00856 fwrite(_JFFVERSION_, sizeof(char), strlen(_JFFVERSION_), jffout);
00857 int indexType[1] = {3};
00858 fwrite(indexType, sizeof(int), 1, jffout);
00859 double sizeXmeters, sizeYmeters, sizeZmeters;
00860 double cellSizeX, cellSizeY, cellSizeZ;
00861 double centerX, centerY, centerZ;
00862 LazyGrid<PointT> *ind = grid_[i][j];
00863 ind->getGridSizeInMeters(sizeXmeters, sizeYmeters, sizeZmeters);
00864 ind->getCellSize(cellSizeX, cellSizeY, cellSizeZ);
00865 ind->getCenter(centerX, centerY, centerZ);
00866 double lazyGridData[9] = { sizeXmeters, sizeYmeters, sizeZmeters,
00867 cellSizeX, cellSizeY, cellSizeZ,
00868 centerX, centerY, centerZ
00869 };
00870 fwrite(lazyGridData, sizeof(double), 9, jffout);
00871 fwrite(ind->getProtoType(), sizeof(Cell<PointT>), 1, jffout);
00872
00873 typename SpatialIndex<PointT>::CellVectorItr it = ind->begin();
00874 while (it != ind->end())
00875 {
00876 NDTCell<PointT> *cell = dynamic_cast<NDTCell<PointT>*> (*it);
00877 if(cell!=NULL)
00878 {
00879 if(cell->writeToJFF(jffout) < 0) return -1;
00880 }
00881 else
00882 {
00883
00884 }
00885 it++;
00886 }
00887 fclose(jffout);
00888 }
00889 }
00890
00891 return 0;
00892 }
00893
00894 template<typename PointT>
00895 bool NDTMapHMT<PointT>::tryLoad(const double &cx, const double &cy, const double &cz, LazyGrid<PointT> *&grid) {
00896 std::cout<<"trying to load at "<<cx<<" "<<cy<<" "<<cz<<std::endl;
00897 if(my_directory == "" || !grids_init)
00898 {
00899 std::cout<<"provide directory name\n";
00900 return false;
00901 }
00902
00903 std::string jffname;
00904 std::string meta = my_directory;
00905 meta += "/metadata.txt";
00906
00907 FILE* meta_f = fopen(meta.c_str(),"a+");
00908 if(meta_f==0) return -1;
00909
00910
00911 char *line = NULL;
00912 size_t len;
00913 bool found=false;
00914 size_t length = 0;
00915 double epsilon = 1e-2;
00916
00917
00918 double sizeX,sizeY,sizeZ;
00919 grid_[1][1]->getGridSizeInMeters(sizeX, sizeY, sizeZ);
00920
00921
00922
00923
00924
00925 if(getline(&line,&len,meta_f) >0 ) {
00926 char *tk = strtok(line," ");
00927 if(tk==NULL) return false;
00928 if (strncmp(tk,"VERSION",7) == 0) {
00929 tk = strtok(NULL," ");
00930 if(tk==NULL) return false;
00931 if(strncmp(tk,"2.0",3) == 0) {
00932 if(!getline(&line,&len,meta_f) >0 ) {
00933 return false;
00934 }
00935 tk = strtok(line," ");
00936 if(tk==NULL) return false;
00937 if(strncmp(tk,"SIZE",4) != 0) return false;
00938 tk = strtok(NULL," ");
00939 double sizeMeta = atof(tk);
00940 if(fabsf(sizeMeta - sizeX) > 0.01) {
00941 std::cerr<<"cannot load map, different grid size used... reverting to empty map\n";
00942 return false;
00943 }
00944 }
00945
00946
00947 } else {
00948
00949 std::cerr<<"metafile version 1.0, no protection against different grid size\n";
00950 fclose(meta_f);
00951 meta_f = fopen(meta.c_str(),"a+");
00952 }
00953 }
00954
00955
00956 while(getline(&line,&len,meta_f) >0 )
00957 {
00958 pcl::PointXYZ cen;
00959 char *token = strtok(line," ");
00960 if(token==NULL) return -1;
00961 cen.x = atof(token);
00962 token = strtok(NULL," ");
00963 if(token==NULL) return -1;
00964 cen.y = atof(token);
00965 token = strtok(NULL," ");
00966 if(token==NULL) return -1;
00967 cen.z = atof(token);
00968
00969 token = strtok(NULL," ");
00970 if(token==NULL) return -1;
00971
00972 if(fabsf(cen.x-cx) < epsilon &&
00973 fabsf(cen.y-cy) < epsilon && fabsf(cen.z-cz) < epsilon) {
00974 token[strlen(token)-1]='\0';
00975 jffname = token;
00976 found = true;
00977
00978 break;
00979 }
00980
00981 }
00982 fclose(meta_f);
00983 if(!found) return false;
00984
00985 FILE * jffin;
00986 std::string sep = "/";
00987 std::string path = my_directory+sep+jffname;
00988 std::cout<<"reading file "<<path<<std::endl;
00989 jffin = fopen(path.c_str(),"r+b");
00990 if(jffin==NULL) return false;
00991
00992 char versionBuf[16];
00993 if(fread(&versionBuf, sizeof(char), strlen(_JFFVERSION_), jffin) <= 0)
00994 {
00995 std::cerr<<"reading version failed";
00996 return false;
00997 }
00998 versionBuf[strlen(_JFFVERSION_)] = '\0';
00999 int indexType;
01000 if(fread(&indexType, sizeof(int), 1, jffin) <= 0)
01001 {
01002 std::cerr<<"reading index type failed";
01003 return false;
01004 }
01005
01006 NDTCell<PointT> *ptCell = new NDTCell<PointT>();
01007 grid = new LazyGrid<PointT>(resolution);
01008 grid->setCellType(ptCell);
01009 delete ptCell;
01010 if(grid->loadFromJFF(jffin) < 0)
01011 {
01012 std::cerr<<"loading grid failed";
01013 return false;
01014 }
01015 fclose(jffin);
01016
01017 return true;
01018 }
01019
01034 template<typename PointT>
01035 int NDTMapHMT<PointT>::loadFrom()
01036 {
01037
01038 if(my_directory == "" || !grids_init)
01039 {
01040 std::cout<<"provide directory name\n";
01041 return -1;
01042 }
01043
01044
01045
01046
01047
01048
01049
01050
01051
01052
01053
01054
01055
01056
01057
01058
01059
01060
01061
01062
01063
01064
01065
01066
01067
01068
01069
01070
01071
01072
01073
01074
01075
01076
01077
01078
01079
01080
01081
01082 }
01083
01085 template<typename PointT>
01086 bool NDTMapHMT<PointT>::getCellAtPoint(const PointT &refPoint, NDTCell<PointT> *&cell)
01087 {
01088 if(grid_[1][1]->isInside(refPoint)) {
01089 grid_[1][1]->getNDTCellAt(refPoint,cell);
01090 } else {
01091 for(int i=0; i<3; ++i) {
01092 for(int j=0; j<3; ++j) {
01093 if(grid_[i][j]->isInside(refPoint)) {
01094 grid_[i][j]->getNDTCellAt(refPoint,cell);
01095 break;
01096 }
01097 }
01098 }
01099 }
01100 return (cell != NULL);
01101 }
01102
01103
01104 template<typename PointT>
01105 double NDTMapHMT<PointT>::getLikelihoodForPoint(PointT pt)
01106 {
01107 double uniform=0.00100;
01108 NDTCell<PointT>* ndCell = NULL;
01109 this->getCellAtPoint(pt,ndCell);
01110 if(ndCell == NULL) return uniform;
01111 double prob = ndCell->getLikelihood(pt);
01112 prob = (prob<0) ? 0 : prob;
01113 return prob;
01114 }
01115
01116 template<typename PointT>
01117 std::vector<NDTCell<PointT>*> NDTMapHMT<PointT>::getInitializedCellsForPoint(const PointT pt) const
01118 {
01119 std::vector<NDTCell<PointT>*> cells, tmpcells;
01120 for(int i=0; i<3; ++i) {
01121 for(int j=0; j<3; ++j) {
01122 if(grid_[i][j]->isInside(pt)) {
01123 tmpcells = grid_[i][j]->getClosestCells(pt);
01124 cells.insert(cells.begin(),tmpcells.begin(),tmpcells.end());
01125 }
01126 }
01127 }
01128 return cells;
01129 }
01130
01131 template<typename PointT>
01132 std::vector<NDTCell<PointT>*> NDTMapHMT<PointT>::getCellsForPoint(const PointT pt, int n_neigh, bool checkForGaussian) const
01133 {
01134 std::vector<NDTCell<PointT>*> cells, tmpcells;
01135 for(int i=0; i<3; ++i) {
01136 for(int j=0; j<3; ++j) {
01137 if(grid_[i][j]->isInside(pt)) {
01138 tmpcells = grid_[i][j]->getClosestNDTCells(pt,n_neigh,checkForGaussian);
01139 cells.insert(cells.begin(),tmpcells.begin(),tmpcells.end());
01140 }
01141 }
01142 }
01143 return cells;
01144 }
01145
01146 template<typename PointT>
01147 bool NDTMapHMT<PointT>::getCellForPoint(const PointT &pt, NDTCell<PointT>* &out_cell, bool checkForGaussian) const
01148 {
01149 out_cell = NULL;
01150 if(grid_[1][1]->isInside(pt)) {
01151 out_cell = grid_[1][1]->getClosestNDTCell(pt,checkForGaussian);
01152 return true;
01153 } else {
01154 for(int i=0; i<3; ++i) {
01155 for(int j=0; j<3; ++j) {
01156 if(grid_[i][j]->isInside(pt)) {
01157 out_cell = grid_[i][j]->getClosestNDTCell(pt,checkForGaussian);
01158 return true;
01159 }
01160 }
01161 }
01162 }
01163 return false;
01164 }
01165
01185
01201 template<typename PointT>
01202 std::vector<NDTCell<PointT>*> NDTMapHMT<PointT>::pseudoTransformNDT(Eigen::Transform<double,3,Eigen::Affine,Eigen::ColMajor> T)
01203 {
01204
01205 std::vector<NDTCell<PointT>*> ret;
01206 for(int i=0; i<3; ++i) {
01207 for(int j=0; j<3; ++j) {
01208 typename SpatialIndex<PointT>::CellVectorItr it = grid_[i][j]->begin();
01209 while (it != grid_[i][j]->end())
01210 {
01211 NDTCell<PointT> *cell = dynamic_cast<NDTCell<PointT>*> (*it);
01212 if(cell!=NULL)
01213 {
01214 if(cell->hasGaussian_)
01215 {
01216 Eigen::Vector3d mean = cell->getMean();
01217 Eigen::Matrix3d cov = cell->getCov();
01218 mean = T*mean;
01220 cov = T.rotation()*cov*T.rotation().transpose();
01221 NDTCell<PointT>* nd = (NDTCell<PointT>*)cell->clone();
01222 nd->setMean(mean);
01223 nd->setCov(cov);
01224 ret.push_back(nd);
01225 }
01226 }
01227 else
01228 {
01229
01230 }
01231 it++;
01232 }
01233 }
01234 }
01235 return ret;
01236 }
01237
01238 template<typename PointT>
01239 std::vector<lslgeneric::NDTCell<PointT>*> NDTMapHMT<PointT>::getAllCells() const
01240 {
01241
01242 std::vector<NDTCell<PointT>*> ret;
01243 for(int i=0; i<3; ++i) {
01244 for(int j=0; j<3; ++j) {
01245
01246 typename SpatialIndex<PointT>::CellVectorItr it = grid_[i][j]->begin();
01247 while (it != grid_[i][j]->end())
01248 {
01249 NDTCell<PointT> *cell = dynamic_cast<NDTCell<PointT>*> (*it);
01250 if(cell!=NULL)
01251 {
01252 if(cell->hasGaussian_)
01253 {
01254 NDTCell<PointT>* nd = (NDTCell<PointT>*)cell->copy();
01255 ret.push_back(nd);
01256 }
01257 }
01258 else
01259 {
01260 }
01261 it++;
01262 }
01263 }
01264 }
01265 return ret;
01266 }
01267
01268 template<typename PointT>
01269 std::vector<lslgeneric::NDTCell<PointT>*> NDTMapHMT<PointT>::getAllInitializedCells()
01270 {
01271
01272 std::vector<NDTCell<PointT>*> ret;
01273 for(int i=0; i<3; ++i) {
01274 for(int j=0; j<3; ++j) {
01275 typename SpatialIndex<PointT>::CellVectorItr it = grid_[i][j]->begin();
01276 while (it != grid_[i][j]->end())
01277 {
01278 NDTCell<PointT> *cell = dynamic_cast<NDTCell<PointT>*> (*it);
01279 if(cell!=NULL)
01280 {
01281 NDTCell<PointT>* nd = (NDTCell<PointT>*)cell->copy();
01282 ret.push_back(nd);
01283 }
01284 else
01285 {
01286 }
01287 it++;
01288 }
01289 }
01290 }
01291 return ret;
01292 }
01293
01294 template<typename PointT>
01295 int NDTMapHMT<PointT>::numberOfActiveCells()
01296 {
01297 int ret = 0;
01298 for(int i=0; i<3; ++i) {
01299 for(int j=0; j<3; ++j) {
01300 typename SpatialIndex<PointT>::CellVectorItr it = grid_[i][j]->begin();
01301 while (it != grid_[i][j]->end())
01302 {
01303 NDTCell<PointT> *cell = dynamic_cast<NDTCell<PointT>*> (*it);
01304 if(cell!=NULL)
01305 {
01306 if(cell->hasGaussian_)
01307 {
01308 ret++;
01309 }
01310 }
01311 it++;
01312 }
01313 }
01314 }
01315 return ret;
01316 }
01317
01318
01319
01320 }