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