oc_tree.hpp
Go to the documentation of this file.
00001 #include<pointcloud_vrml/pointcloud_utils.h>
00002 
00003 namespace lslgeneric
00004 {
00005 
00006 template <typename PointT>
00007 void OctTree<PointT>::setParameters(double _BIG_CELL_SIZE       ,
00008                                     double _SMALL_CELL_SIZE     ,
00009                                     int _MAX_POINTS             ,
00010                                     int _MAX_DEPTH
00011                                    )
00012 {
00013 
00014     //defaults
00015     this->MAX_POINTS            = _MAX_POINTS           ;
00016     this->MAX_DEPTH             = _MAX_DEPTH            ;
00017     this->BIG_CELL_SIZE = _BIG_CELL_SIZE        ;
00018     this->SMALL_CELL_SIZE       = _SMALL_CELL_SIZE      ;
00019     this->parametersSet_ = true;
00020 
00021     if(!this->leaf_)
00022     {
00023         for(unsigned int it=0; it<8; it++)
00024         {
00025             if(this->children_[it]!=NULL)
00026             {
00027                 this->children_[it]->setParameters(_BIG_CELL_SIZE,_SMALL_CELL_SIZE,
00028                                                    _MAX_POINTS,_MAX_DEPTH);
00029             }
00030         }
00031     }
00032 }
00037 template <typename PointT>
00038 size_t OctTree<PointT>::getIndexForPoint(const PointT &pt) const
00039 {
00052     size_t ret = 0;
00053     if(pt.x < myCell_->getCenter().x)
00054     {
00055         ret += 4;
00056     }
00057     if(pt.y < myCell_->getCenter().y)
00058     {
00059         ret += 2;
00060     }
00061     if(ret%4==0)
00062     {
00063         if(pt.z < myCell_->getCenter().z)
00064         {
00065             ret += 1;
00066         }
00067     }
00068     else
00069     {
00070         if(pt.z > myCell_->getCenter().z)
00071         {
00072             ret += 1;
00073         }
00074     }
00075     return ret;
00076 }
00077 
00080 template <typename PointT>
00081 OctTree<PointT>::OctTree()
00082 {
00083 
00084     this->parent_=NULL;
00085     this->leaf_=true;
00086     this->depth_=0;
00087     for(unsigned int it=0; it<8; it++)
00088     {
00089         this->children_[it]=NULL;
00090     }
00091     myCell_ = NULL;
00092     leafsCached_ = false;
00093     this->setParameters();
00094 }
00095 
00098 template <typename PointT>
00099 OctTree<PointT>::OctTree(PointT center, double xsize, double ysize,
00100                          double zsize, NDTCell<PointT>* type, OctTree<PointT> *_parent, unsigned int _depth)
00101 {
00102 
00103     parent_=_parent;
00104     leaf_=true;
00105     depth_=_depth;
00106     for(unsigned int it=0; it<8; it++)
00107     {
00108         children_[it]=NULL;
00109     }
00110     NDTCell<PointT>* tmp = dynamic_cast<NDTCell<PointT>*>(type->clone());
00111     if(tmp==NULL)
00112     {
00113         //ERR("dynamic cast of cell failed!!\n");
00114         return;
00115     }
00116 
00117     tmp->setCenter(center);
00118     tmp->setDimensions(xsize,ysize,zsize);
00119     tmp->points_.clear();
00120 
00121     myCell_ = tmp;
00122     leafsCached_ = false;
00123     this->setParameters();
00124 }
00125 
00128 template <typename PointT>
00129 OctTree<PointT>::~OctTree()
00130 {
00131 
00132     if(!leaf_)
00133     {
00134         for(unsigned int it=0; it<8; it++)
00135         {
00136             if(children_[it]!=NULL)
00137             {
00138                 delete children_[it]; //calls destructor of child, so we are ok
00139                 children_[it]=NULL;
00140             }
00141         }
00142     }
00143     delete myCell_;
00144 }
00145 
00150 template <typename PointT>
00151 Cell<PointT>* OctTree<PointT>::addPoint(const PointT &point_c)
00152 {
00153 
00154     PointT point = point_c;
00155     if(std::isnan(point.x) ||std::isnan(point.y) ||std::isnan(point.z))
00156     {
00157         return NULL;
00158     }
00159     leafsCached_ = false;
00160     if(this->leaf_)
00161     {
00162         double xs,ys,zs;
00163         myCell_->getDimensions(xs,ys,zs);
00164 
00165         double cellSize = (xs+ys+zs)/3.; //average for now
00166 
00167         if(myCell_->points_.size()<(unsigned int)MAX_POINTS && cellSize <= BIG_CELL_SIZE)
00168         {
00169             if(!myCell_->isInside(point))
00170             {
00171                 //DBG(1,"OctTree: addPoint (%lf,%lf,%lf) not in boundary!\n",point.x,point.y,point.z);
00172                 return NULL;
00173             }
00174             myCell_->points_.push_back(point);
00175         }
00176         else
00177         {
00178             if(depth_>(unsigned int) MAX_DEPTH || cellSize <= 2*SMALL_CELL_SIZE )
00179             {
00180                 //TSV: we have to be sure we won't violate the space constraint if we split
00181                 //just store point, we can't split any more
00182                 if(!myCell_->isInside(point))
00183                 {
00184                     //DBG(1,"OctTree: addPoint (%lf,%lf,%lf) not in boundary!\n",point.x,point.y,point.z);
00185                     return NULL;
00186                 }
00187                 myCell_->points_.push_back(point);
00188                 return myCell_;
00189             }
00190 
00191             PointT myCenter = myCell_->getCenter();
00192 
00193             //branch leaf
00194             for(int it=0; it<8; it++)
00195             {
00196                 PointT newCenter;
00197 
00198                 //computes the center_ of the it'th child
00199                 newCenter.x = (myCenter.x + pow(-1.,it/4)*xs/4.);
00200                 newCenter.y = (myCenter.y + pow(-1.,it/2)*ys/4.);
00201                 newCenter.z = (myCenter.z + pow(-1.,(it+1)/2)*zs/4.);
00202 
00203                 children_[it] = new OctTree<PointT>(newCenter,xs/2,ys/2,
00204                                                     zs/2, myCell_, this, depth_+1);
00205                 children_[it]->setParameters(BIG_CELL_SIZE,SMALL_CELL_SIZE,
00206                                              MAX_POINTS,MAX_DEPTH);
00207             }
00208             //add current points
00209             for(unsigned int jt=0; jt<myCell_->points_.size(); jt++)
00210             {
00211                 size_t ind = getIndexForPoint(myCell_->points_[jt]);
00212                 children_[ind]->addPoint(myCell_->points_[jt]);
00213             }
00214             //finally add the new point
00215             size_t ind = getIndexForPoint(point);
00216             Cell<PointT>* ptcell = children_[ind]->addPoint(point);
00217             this->leaf_=false;
00218             this->myCell_->points_.clear();
00219             return ptcell;
00220         }
00221     }
00222     else
00223     {
00224         //pass down to correct child
00225         size_t ind = getIndexForPoint(point);
00226         return children_[ind]->addPoint(point);
00227     }
00228 }
00229 
00232 template <typename PointT>
00233 Cell<PointT>* OctTree<PointT>::getCellForPoint(const PointT &point)
00234 {
00235 
00236     OctTree<PointT>* pointLeaf = this->getLeafForPoint(point);
00237     return (pointLeaf==NULL) ? NULL : pointLeaf->myCell_;
00238 
00239 }
00240 
00243 template <typename PointT>
00244 OctTree<PointT>* OctTree<PointT>::getLeafForPoint(const PointT &point)
00245 {
00246 
00247     if(this->leaf_ && myCell_!= NULL)
00248     {
00249         if(myCell_->isInside(point))
00250         {
00251             return this;
00252         }
00253     }
00254     else
00255     {
00256         size_t ind = getIndexForPoint(point);
00257         if(children_[ind]!=NULL)
00258         {
00259             return children_[ind]->getLeafForPoint(point);
00260         }
00261     }
00262     return NULL;
00263 
00264 }
00265 
00268 template <typename PointT>
00269 void OctTree<PointT>::computeLeafCells()
00270 {
00271     if(this->isLeaf())
00272     {
00273         myLeafs_.push_back(this->myCell_);
00274         return;
00275     }
00276 
00277     myLeafs_.clear();
00278     std::vector<OctTree<PointT>*> next;
00279     next.push_back(this);
00280 
00281     while(next.size()>0)
00282     {
00283         OctTree<PointT> *cur = next.front();
00284         if(cur!=NULL)
00285         {
00286             if(cur->isLeaf())
00287             {
00288                 myLeafs_.push_back(cur->myCell_);
00289             }
00290             else
00291             {
00292                 for(int i=0; i<8; i++)
00293                 {
00294                     OctTree<PointT>* tmp = cur->getChild(i);
00295                     if(tmp!=NULL)
00296                     {
00297                         next.push_back(tmp);
00298                     }
00299                 }
00300             }
00301         }
00302         next.erase(next.begin());
00303     }
00304 }
00305 
00308 template <typename PointT>
00309 void OctTree<PointT>::setCellType(Cell<PointT> *type)
00310 {
00311 
00312     myCell_ = dynamic_cast<NDTCell<PointT>*>(type->clone());
00313     if(myCell_ == NULL)
00314     {
00315         //cast failed, it's not a derivative of oct cell
00316         myCell_ = new NDTCell<PointT>();
00317     }
00318 
00319 }
00320 
00324 template <typename PointT>
00325 typename SpatialIndex<PointT>::CellVectorItr OctTree<PointT>::begin()
00326 {
00327     if(!leafsCached_)
00328     {
00329         myLeafs_.clear();
00330         computeLeafCells();
00331     }
00332     leafsCached_ = true;
00333     return myLeafs_.begin();
00334 }
00335 
00338 template <typename PointT>
00339 typename SpatialIndex<PointT>::CellVectorItr OctTree<PointT>::end()
00340 {
00341     if(!leafsCached_)
00342     {
00343         myLeafs_.clear();
00344         computeLeafCells();
00345     }
00346     leafsCached_ = true;
00347     return myLeafs_.end();
00348 }
00349 
00352 template <typename PointT>
00353 void OctTree<PointT>::writeToVRML(const char* filename)
00354 {
00355     if(filename == NULL)
00356     {
00357         //ERR("OctTree: attempting to print to a null filename \n");
00358         return;
00359     }
00360 
00361     FILE* fout = fopen (filename,"w");
00362     if(fout == NULL)
00363     {
00364         //ERR("OctTree: attempting to write to a null file %s\n",filename);
00365         return;
00366     }
00367     fprintf(fout,"#VRML V2.0 utf8\n");
00368     this->writeToVRML(fout);
00369     fclose(fout);
00370 }
00371 
00374 template <typename PointT>
00375 void OctTree<PointT>::writeToVRML(FILE* fout)
00376 {
00377 
00378     this->computeLeafCells();
00379     typename SpatialIndex<PointT>::CellVectorItr it = this->begin();
00380     Eigen::Vector3d col;
00381     col<<0,0,0;
00382     while(it!= this->end())
00383     {
00384         NDTCell<PointT>* cell = dynamic_cast<NDTCell<PointT>*>(*it);
00385         if(cell!=NULL)
00386         {
00387             cell->writeToVRML(fout,col);
00388         }
00389         it++;
00390     }
00391 }
00392 
00395 template <typename PointT>
00396 SpatialIndex<PointT>* OctTree<PointT>::clone() const
00397 {
00398     OctTree<PointT> *tr = new OctTree<PointT>();
00399     tr->setParameters(BIG_CELL_SIZE,SMALL_CELL_SIZE,MAX_POINTS,MAX_DEPTH);
00400     if(myCell_ != NULL)
00401     {
00402         tr->setCellType(myCell_);
00403     }
00404     return tr;
00405 }
00406 
00409 template <typename PointT>
00410 SpatialIndex<PointT>* OctTree<PointT>::copy() const
00411 {
00412     OctTree<PointT> *tr;
00413     if(myCell_ != NULL)
00414     {
00415         PointT center = myCell_->getCenter();
00416         double sx,sy,sz;
00417         myCell_->getDimensions(sx,sy,sz);
00418         tr = new OctTree<PointT>(center,sx,sy,sz,myCell_);
00419     }
00420     else
00421     {
00422         tr = new OctTree<PointT>();
00423     }
00424     tr->setParameters(BIG_CELL_SIZE,SMALL_CELL_SIZE,MAX_POINTS,MAX_DEPTH);
00425     return tr;
00426 }
00427 
00431 template <typename PointT>
00432 void OctTree<PointT>::setCenter(const double &cx, const double &cy, const double &cz)
00433 {
00434     if(myCell_ == NULL)
00435     {
00436         return;
00437     }
00438     PointT center_;
00439     center_.x = cx;
00440     center_.y = cy;
00441     center_.z = cz;
00442 
00443     myCell_->setCenter(center_);
00444 }
00445 
00449 template <typename PointT>
00450 void OctTree<PointT>::setSize(const double &sx, const double &sy, const double &sz)
00451 {
00452     if(myCell_ == NULL)
00453     {
00454         return;
00455     }
00456     myCell_->setDimensions(sx,sy,sz);
00457 }
00458 
00464 template <typename PointT>
00465 void OctTree<PointT>::getNeighbors(const PointT &point, const double &radius, std::vector<Cell<PointT>*> &cells)
00466 {
00467 
00468     cells.clear();
00469     //first find the leaf that contains the point
00470     OctTree<PointT> *target = this->getLeafForPoint(point);
00471     if(target==NULL) return;
00472 
00473     OctTree<PointT> *mparent = target->parent_;
00474     OctTree<PointT> *mthis = target;
00475     std::vector<OctTree<PointT>*> toExpand;
00476     //check if any of the siblings intersect the sphere (key,constraint)
00477 
00478     while(mparent!=NULL)
00479     {
00480         for(unsigned int it=0; it<8; it++)
00481         {
00482             if(mparent->children_[it] == NULL) continue;
00483             if(mparent->children_[it]->intersectSphere(point,radius)
00484                     && mparent->children_[it]!=mthis )
00485             {
00486                 //if yes, add them to the list to expand
00487                 toExpand.push_back(mparent->children_[it]);
00488             }
00489         }
00490         //go up to parent
00491         mthis=mparent;
00492         mparent=mparent->parent_;
00493         //for all nodes in list, go down to leafs that intersect
00494         for(unsigned int nt=0; nt<toExpand.size(); nt++)
00495         {
00496             if(toExpand[nt] == NULL )
00497             {
00498                 //ERR("ERROR in nearest neighbor!!\n");
00499                 continue;
00500             }
00501 
00502             PointT center_ = (toExpand[nt]->myCell_->getCenter());
00503             Eigen::Vector3d d;
00504             d<<center_.x-point.x, center_.y-point.y, center_.z-point.z;
00505             if(toExpand[nt]->isLeaf() &&
00506                     d.norm() < radius)
00507             {
00508                 cells.push_back(toExpand[nt]->myCell_);
00509             }
00510             else
00511             {
00512                 for(unsigned int it=0; it<8; it++)
00513                 {
00514                     if(toExpand[nt]->children_[it]==NULL) continue;
00515                     if(toExpand[nt]->children_[it]->intersectSphere(point,radius))
00516                     {
00517                         toExpand.push_back(toExpand[nt]->children_[it]);
00518                     }
00519                 }
00520             }
00521         }
00522 
00523         toExpand.clear();
00524     }
00525 
00526 }
00527 
00530 template <typename PointT>
00531 bool OctTree<PointT>::intersectSphere(PointT center_, const double &radius) const
00532 {
00533 
00534     PointT mcenter_ = myCell_->getCenter();
00535     Eigen::Vector3d d;
00536     d<<center_.x-mcenter_.x, center_.y-mcenter_.y, center_.z-mcenter_.z;
00537     double dist = d.norm();
00538     Eigen::Vector3d localRadius;
00539     myCell_->getDimensions(localRadius(0),localRadius(1),localRadius(2));
00540     double lRad = localRadius.norm()/2;
00541     double interDist = lRad+radius;
00542     return (interDist>dist);
00543 
00544 }
00545 
00546 template <typename PointT>
00547 Cell<PointT>* OctTree<PointT>::getClosestLeafCell(const PointT &point)
00548 {
00549     if(this->leaf_ && myCell_!= NULL)
00550     {
00551         if(myCell_->isInside(point))
00552         {
00553             return myCell_;
00554         }
00555     }
00556     else
00557     {
00558         size_t ind = getIndexForPoint(point);
00559         if(children_[ind]!=NULL)
00560         {
00561             return children_[ind]->getClosestLeafCell(point);
00562         }
00563         else
00564         {
00565             //the leaf we should be in is empty
00566             //start from here and find closest neighbor
00567             double minDist = INT_MAX;
00568             int index = -1;
00569             for(int i=0; i<8; i++)
00570             {
00571                 if(children_[i]==NULL) continue;
00572                 PointT center = children_[i]->myCell_->getCenter();
00573                 Eigen::Vector3d d;
00574                 d <<center.x-point.x, center.y-point.y, center.z-point.z;
00575                 double dist = d.norm();
00576 
00577                 if(dist<minDist)
00578                 {
00579                     index = i;
00580                     minDist = dist;
00581                 }
00582             }
00583             //std::cout<<"minDist"<<minDist<<std::endl;
00584             if(index>=0 && index<8)
00585             {
00586                 return children_[index]->getClosestLeafCell(point);
00587             }
00588         }
00589     }
00590     return myCell_;
00591 }
00592 
00593 template <typename PointT>
00594 NDTCell<PointT>* OctTree<PointT>::getClosestNDTCell(const PointT &point)
00595 {
00596     if(this->leaf_)
00597     {
00598         //we have reached the bottom of the tree.
00599         //if we have a valid ndt cell, return it.
00600         if(myCell_->isInside(point))
00601         {
00602             NDTCell<PointT>* nd = dynamic_cast<NDTCell<PointT>*>(myCell_);
00603             if(nd!=NULL)
00604             {
00605                 if(nd->hasGaussian_)
00606                 {
00607                     return nd;
00608                 }
00609             }
00610         }
00611     }
00612 
00613     //we go down the tree recursively
00614     size_t ind = getIndexForPoint(point);
00615     if(children_[ind]!=NULL)
00616     {
00617         return children_[ind]->getClosestNDTCell(point);
00618     }
00619 
00620 
00621     //the leaf we should be in is empty
00622     //iterate through all leafs connected to current node, find closest ndt cell
00623     OctTree<PointT> *my_parent = this->parent_;
00624     OctTree<PointT> *me = this;
00625     typename SpatialIndex<PointT>::CellVectorItr it;
00626     NDTCell<PointT> *closest = NULL, *temp = NULL;
00627     double minDist = INT_MAX, dist = INT_MAX;
00628 
00629     while(true)
00630     {
00631         it = me->begin();
00632         while(it!=me->end())
00633         {
00634             temp = dynamic_cast<NDTCell<PointT>*> (*it);
00635             if(temp!=NULL)
00636             {
00637                 if(temp->hasGaussian_)
00638                 {
00639                     dist = lslgeneric::geomDist<PointT>(temp->getCenter(),point);
00640                     if(dist < minDist)
00641                     {
00642                         minDist = dist;
00643                         closest = temp;
00644                     }
00645                 }
00646             }
00647             it++;
00648         }
00649         if(closest!=NULL)
00650         {
00651 //          cout<<"got it!\n";
00652             break;
00653         }
00654         if(my_parent != NULL)
00655         {
00656             me = my_parent;
00657             my_parent = me->parent_;
00658         }
00659         else
00660         {
00661             //nothing more can be done...
00662             break;
00663         }
00664     }
00665 
00666     return closest;
00667 }
00668 }


ndt_map
Author(s): Todor Stoyanov, Jari Saarinen, Henrik Andreasson
autogenerated on Mon Oct 6 2014 03:18:54