FlannIndex.cpp
Go to the documentation of this file.
00001 /*
00002 Copyright (c) 2010-2016, Mathieu Labbe - IntRoLab - Universite de Sherbrooke
00003 All rights reserved.
00004 
00005 Redistribution and use in source and binary forms, with or without
00006 modification, are permitted provided that the following conditions are met:
00007     * Redistributions of source code must retain the above copyright
00008       notice, this list of conditions and the following disclaimer.
00009     * Redistributions in binary form must reproduce the above copyright
00010       notice, this list of conditions and the following disclaimer in the
00011       documentation and/or other materials provided with the distribution.
00012     * Neither the name of the Universite de Sherbrooke nor the
00013       names of its contributors may be used to endorse or promote products
00014       derived from this software without specific prior written permission.
00015 
00016 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
00017 ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
00018 WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
00019 DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY
00020 DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
00021 (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00022 LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
00023 ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
00024 (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
00025 SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
00026 */
00027 
00028 #include <rtabmap/core/FlannIndex.h>
00029 #include <rtabmap/utilite/ULogger.h>
00030 
00031 #include "rtflann/flann.hpp"
00032 
00033 namespace rtabmap {
00034 
00035 FlannIndex::FlannIndex():
00036                 index_(0),
00037                 nextIndex_(0),
00038                 featuresType_(0),
00039                 featuresDim_(0),
00040                 isLSH_(false),
00041                 useDistanceL1_(false),
00042                 rebalancingFactor_(2.0f)
00043 {
00044 }
00045 FlannIndex::~FlannIndex()
00046 {
00047         this->release();
00048 }
00049 
00050 void FlannIndex::release()
00051 {
00052         if(index_)
00053         {
00054                 if(featuresType_ == CV_8UC1)
00055                 {
00056                         delete (rtflann::Index<rtflann::Hamming<unsigned char> >*)index_;
00057                 }
00058                 else
00059                 {
00060                         if(useDistanceL1_)
00061                         {
00062                                 delete (rtflann::Index<rtflann::L1<float> >*)index_;
00063                         }
00064                         else if(featuresDim_ <= 3)
00065                         {
00066                                 delete (rtflann::Index<rtflann::L2_Simple<float> >*)index_;
00067                         }
00068                         else
00069                         {
00070                                 delete (rtflann::Index<rtflann::L2<float> >*)index_;
00071                         }
00072                 }
00073                 index_ = 0;
00074         }
00075         nextIndex_ = 0;
00076         isLSH_ = false;
00077         addedDescriptors_.clear();
00078         removedIndexes_.clear();
00079 }
00080 
00081 unsigned int FlannIndex::indexedFeatures() const
00082 {
00083         if(!index_)
00084         {
00085                 return 0;
00086         }
00087         if(featuresType_ == CV_8UC1)
00088         {
00089                 return ((const rtflann::Index<rtflann::Hamming<unsigned char> >*)index_)->size();
00090         }
00091         else
00092         {
00093                 if(useDistanceL1_)
00094                 {
00095                         return ((const rtflann::Index<rtflann::L1<float> >*)index_)->size();
00096                 }
00097                 else if(featuresDim_ <= 3)
00098                 {
00099                         return ((const rtflann::Index<rtflann::L2_Simple<float> >*)index_)->size();
00100                 }
00101                 else
00102                 {
00103                         return ((const rtflann::Index<rtflann::L2<float> >*)index_)->size();
00104                 }
00105         }
00106 }
00107 
00108 // return KB
00109 unsigned int FlannIndex::memoryUsed() const
00110 {
00111         if(!index_)
00112         {
00113                 return 0;
00114         }
00115         if(featuresType_ == CV_8UC1)
00116         {
00117                 return ((const rtflann::Index<rtflann::Hamming<unsigned char> >*)index_)->usedMemory()/1000;
00118         }
00119         else
00120         {
00121                 if(useDistanceL1_)
00122                 {
00123                         return ((const rtflann::Index<rtflann::L1<float> >*)index_)->usedMemory()/1000;
00124                 }
00125                 else if(featuresDim_ <= 3)
00126                 {
00127                         return ((const rtflann::Index<rtflann::L2_Simple<float> >*)index_)->usedMemory()/1000;
00128                 }
00129                 else
00130                 {
00131                         return ((const rtflann::Index<rtflann::L2<float> >*)index_)->usedMemory()/1000;
00132                 }
00133         }
00134 }
00135 
00136 void FlannIndex::buildLinearIndex(
00137                 const cv::Mat & features,
00138                 bool useDistanceL1,
00139                 float rebalancingFactor)
00140 {
00141         this->release();
00142         UASSERT(index_ == 0);
00143         UASSERT(features.type() == CV_32FC1 || features.type() == CV_8UC1);
00144         featuresType_ = features.type();
00145         featuresDim_ = features.cols;
00146         useDistanceL1_ = useDistanceL1;
00147         rebalancingFactor_ = rebalancingFactor;
00148 
00149         rtflann::LinearIndexParams params;
00150 
00151         if(featuresType_ == CV_8UC1)
00152         {
00153                 rtflann::Matrix<unsigned char> dataset(features.data, features.rows, features.cols);
00154                 index_ = new rtflann::Index<rtflann::Hamming<unsigned char> >(dataset, params);
00155                 ((rtflann::Index<rtflann::Hamming<unsigned char> >*)index_)->buildIndex();
00156         }
00157         else
00158         {
00159                 rtflann::Matrix<float> dataset((float*)features.data, features.rows, features.cols);
00160                 if(useDistanceL1_)
00161                 {
00162                         index_ = new rtflann::Index<rtflann::L1<float> >(dataset, params);
00163                         ((rtflann::Index<rtflann::L1<float> >*)index_)->buildIndex();
00164                 }
00165                 else if(featuresDim_ <=3)
00166                 {
00167                         index_ = new rtflann::Index<rtflann::L2_Simple<float> >(dataset, params);
00168                         ((rtflann::Index<rtflann::L2_Simple<float> >*)index_)->buildIndex();
00169                 }
00170                 else
00171                 {
00172                         index_ = new rtflann::Index<rtflann::L2<float> >(dataset, params);
00173                         ((rtflann::Index<rtflann::L2<float> >*)index_)->buildIndex();
00174                 }
00175         }
00176 
00177         // incremental FLANN
00178         addedDescriptors_.insert(std::make_pair(nextIndex_, features));
00179 
00180         nextIndex_ = features.rows;
00181 }
00182 
00183 void FlannIndex::buildKDTreeIndex(
00184                 const cv::Mat & features,
00185                 int trees,
00186                 bool useDistanceL1,
00187                 float rebalancingFactor)
00188 {
00189         this->release();
00190         UASSERT(index_ == 0);
00191         UASSERT(features.type() == CV_32FC1 || features.type() == CV_8UC1);
00192         featuresType_ = features.type();
00193         featuresDim_ = features.cols;
00194         useDistanceL1_ = useDistanceL1;
00195         rebalancingFactor_ = rebalancingFactor;
00196 
00197         rtflann::KDTreeIndexParams params(trees);
00198 
00199         if(featuresType_ == CV_8UC1)
00200         {
00201                 rtflann::Matrix<unsigned char> dataset(features.data, features.rows, features.cols);
00202                 index_ = new rtflann::Index<rtflann::Hamming<unsigned char> >(dataset, params);
00203                 ((rtflann::Index<rtflann::Hamming<unsigned char> >*)index_)->buildIndex();
00204         }
00205         else
00206         {
00207                 rtflann::Matrix<float> dataset((float*)features.data, features.rows, features.cols);
00208                 if(useDistanceL1_)
00209                 {
00210                         index_ = new rtflann::Index<rtflann::L1<float> >(dataset, params);
00211                         ((rtflann::Index<rtflann::L1<float> >*)index_)->buildIndex();
00212                 }
00213                 else if(featuresDim_ <=3)
00214                 {
00215                         index_ = new rtflann::Index<rtflann::L2_Simple<float> >(dataset, params);
00216                         ((rtflann::Index<rtflann::L2_Simple<float> >*)index_)->buildIndex();
00217                 }
00218                 else
00219                 {
00220                         index_ = new rtflann::Index<rtflann::L2<float> >(dataset, params);
00221                         ((rtflann::Index<rtflann::L2<float> >*)index_)->buildIndex();
00222                 }
00223         }
00224 
00225         // incremental FLANN
00226         addedDescriptors_.insert(std::make_pair(nextIndex_, features));
00227 
00228         nextIndex_ = features.rows;
00229 }
00230 
00231 void FlannIndex::buildKDTreeSingleIndex(
00232                 const cv::Mat & features,
00233                 int leafMaxSize,
00234                 bool reorder,
00235                 bool useDistanceL1,
00236                 float rebalancingFactor)
00237 {
00238         this->release();
00239         UASSERT(index_ == 0);
00240         UASSERT(features.type() == CV_32FC1 || features.type() == CV_8UC1);
00241         featuresType_ = features.type();
00242         featuresDim_ = features.cols;
00243         useDistanceL1_ = useDistanceL1;
00244         rebalancingFactor_ = rebalancingFactor;
00245 
00246         rtflann::KDTreeSingleIndexParams params(leafMaxSize, reorder);
00247 
00248         if(featuresType_ == CV_8UC1)
00249         {
00250                 rtflann::Matrix<unsigned char> dataset(features.data, features.rows, features.cols);
00251                 index_ = new rtflann::Index<rtflann::Hamming<unsigned char> >(dataset, params);
00252                 ((rtflann::Index<rtflann::Hamming<unsigned char> >*)index_)->buildIndex();
00253         }
00254         else
00255         {
00256                 rtflann::Matrix<float> dataset((float*)features.data, features.rows, features.cols);
00257                 if(useDistanceL1_)
00258                 {
00259                         index_ = new rtflann::Index<rtflann::L1<float> >(dataset, params);
00260                         ((rtflann::Index<rtflann::L1<float> >*)index_)->buildIndex();
00261                 }
00262                 else if(featuresDim_ <=3)
00263                 {
00264                         index_ = new rtflann::Index<rtflann::L2_Simple<float> >(dataset, params);
00265                         ((rtflann::Index<rtflann::L2_Simple<float> >*)index_)->buildIndex();
00266                 }
00267                 else
00268                 {
00269                         index_ = new rtflann::Index<rtflann::L2<float> >(dataset, params);
00270                         ((rtflann::Index<rtflann::L2<float> >*)index_)->buildIndex();
00271                 }
00272         }
00273 
00274         // incremental FLANN
00275         addedDescriptors_.insert(std::make_pair(nextIndex_, features));
00276 
00277         nextIndex_ = features.rows;
00278 }
00279 
00280 void FlannIndex::buildLSHIndex(
00281                 const cv::Mat & features,
00282                 unsigned int table_number,
00283                 unsigned int key_size,
00284                 unsigned int multi_probe_level,
00285                 float rebalancingFactor)
00286 {
00287         this->release();
00288         UASSERT(index_ == 0);
00289         UASSERT(features.type() == CV_8UC1);
00290         featuresType_ = features.type();
00291         featuresDim_ = features.cols;
00292         useDistanceL1_ = true;
00293         rebalancingFactor_ = rebalancingFactor;
00294 
00295         rtflann::Matrix<unsigned char> dataset(features.data, features.rows, features.cols);
00296         index_ = new rtflann::Index<rtflann::Hamming<unsigned char> >(dataset, rtflann::LshIndexParams(12, 20, 2));
00297         ((rtflann::Index<rtflann::Hamming<unsigned char> >*)index_)->buildIndex();
00298 
00299         // incremental FLANN
00300         addedDescriptors_.insert(std::make_pair(nextIndex_, features));
00301 
00302         nextIndex_ = features.rows;
00303 }
00304 
00305 bool FlannIndex::isBuilt()
00306 {
00307         return index_!=0;
00308 }
00309 
00310 unsigned int FlannIndex::addPoints(const cv::Mat & features)
00311 {
00312         if(!index_)
00313         {
00314                 UERROR("Flann index not yet created!");
00315                 return 0;
00316         }
00317         UASSERT(features.type() == featuresType_);
00318         UASSERT(features.cols == featuresDim_);
00319         bool indexRebuilt = false;
00320         size_t removedPts = 0;
00321         if(featuresType_ == CV_8UC1)
00322         {
00323                 rtflann::Matrix<unsigned char> points(features.data, features.rows, features.cols);
00324                 rtflann::Index<rtflann::Hamming<unsigned char> > * index = (rtflann::Index<rtflann::Hamming<unsigned char> >*)index_;
00325                 removedPts = index->removedCount();
00326                 index->addPoints(points, 0);
00327                 // Rebuild index if it is now X times in size
00328                 if(rebalancingFactor_ > 1.0f && size_t(float(index->sizeAtBuild()) * rebalancingFactor_) < index->size()+index->removedCount())
00329                 {
00330                         UDEBUG("Rebuilding FLANN index: %d -> %d", (int)index->sizeAtBuild(), (int)(index->size()+index->removedCount()));
00331                         index->buildIndex();
00332                 }
00333                 // if no more removed points, the index has been rebuilt
00334                 indexRebuilt = index->removedCount() == 0 && removedPts>0;
00335         }
00336         else
00337         {
00338                 rtflann::Matrix<float> points((float*)features.data, features.rows, features.cols);
00339                 if(useDistanceL1_)
00340                 {
00341                         rtflann::Index<rtflann::L1<float> > * index = (rtflann::Index<rtflann::L1<float> >*)index_;
00342                         removedPts = index->removedCount();
00343                         index->addPoints(points, 0);
00344                         // Rebuild index if it doubles in size
00345                         if(rebalancingFactor_ > 1.0f && size_t(float(index->sizeAtBuild()) * rebalancingFactor_) < index->size()+index->removedCount())
00346                         {
00347                                 UDEBUG("Rebuilding FLANN index: %d -> %d", (int)index->sizeAtBuild(), (int)(index->size()+index->removedCount()));
00348                                 index->buildIndex();
00349                         }
00350                         // if no more removed points, the index has been rebuilt
00351                         indexRebuilt = index->removedCount() == 0 && removedPts>0;
00352                 }
00353                 else if(featuresDim_ <= 3)
00354                 {
00355                         rtflann::Index<rtflann::L2_Simple<float> > * index = (rtflann::Index<rtflann::L2_Simple<float> >*)index_;
00356                         removedPts = index->removedCount();
00357                         index->addPoints(points, 0);
00358                         // Rebuild index if it doubles in size
00359                         if(rebalancingFactor_ > 1.0f && size_t(float(index->sizeAtBuild()) * rebalancingFactor_) < index->size()+index->removedCount())
00360                         {
00361                                 UDEBUG("Rebuilding FLANN index: %d -> %d", (int)index->sizeAtBuild(), (int)(index->size()+index->removedCount()));
00362                                 index->buildIndex();
00363                         }
00364                         // if no more removed points, the index has been rebuilt
00365                         indexRebuilt = index->removedCount() == 0 && removedPts>0;
00366                 }
00367                 else
00368                 {
00369                         rtflann::Index<rtflann::L2<float> > * index = (rtflann::Index<rtflann::L2<float> >*)index_;
00370                         removedPts = index->removedCount();
00371                         index->addPoints(points, 0);
00372                         // Rebuild index if it doubles in size
00373                         if(rebalancingFactor_ > 1.0f && size_t(float(index->sizeAtBuild()) * rebalancingFactor_) < index->size()+index->removedCount())
00374                         {
00375                                 UDEBUG("Rebuilding FLANN index: %d -> %d", (int)index->sizeAtBuild(), (int)(index->size()+index->removedCount()));
00376                                 index->buildIndex();
00377                         }
00378                         // if no more removed points, the index has been rebuilt
00379                         indexRebuilt = index->removedCount() == 0 && removedPts>0;
00380                 }
00381         }
00382 
00383         if(indexRebuilt)
00384         {
00385                 UASSERT(removedPts == removedIndexes_.size());
00386                 // clean not used features
00387                 for(std::list<int>::iterator iter=removedIndexes_.begin(); iter!=removedIndexes_.end(); ++iter)
00388                 {
00389                         addedDescriptors_.erase(*iter);
00390                 }
00391                 removedIndexes_.clear();
00392         }
00393 
00394         addedDescriptors_.insert(std::make_pair(nextIndex_, features));
00395 
00396         int r = nextIndex_;
00397         nextIndex_ += features.rows;
00398         return r;
00399 }
00400 
00401 void FlannIndex::removePoint(unsigned int index)
00402 {
00403         if(!index_)
00404         {
00405                 UERROR("Flann index not yet created!");
00406                 return;
00407         }
00408 
00409         // If a Segmentation fault occurs in removePoint(), verify that you have this fix in your installed "flann/algorithms/nn_index.h":
00410         // 707 - if (ids_[id]==id) {
00411         // 707 + if (id < ids_.size() && ids_[id]==id) {
00412         // ref: https://github.com/mariusmuja/flann/commit/23051820b2314f07cf40ba633a4067782a982ff3#diff-33762b7383f957c2df17301639af5151
00413 
00414         if(featuresType_ == CV_8UC1)
00415         {
00416                 ((rtflann::Index<rtflann::Hamming<unsigned char> >*)index_)->removePoint(index);
00417         }
00418         else if(useDistanceL1_)
00419         {
00420                 ((rtflann::Index<rtflann::L1<float> >*)index_)->removePoint(index);
00421         }
00422         else if(featuresDim_ <= 3)
00423         {
00424                 ((rtflann::Index<rtflann::L2_Simple<float> >*)index_)->removePoint(index);
00425         }
00426         else
00427         {
00428                 ((rtflann::Index<rtflann::L2<float> >*)index_)->removePoint(index);
00429         }
00430 
00431         removedIndexes_.push_back(index);
00432 }
00433 
00434 void FlannIndex::knnSearch(
00435                 const cv::Mat & query,
00436                 cv::Mat & indices,
00437                 cv::Mat & dists,
00438                 int knn,
00439                 int checks,
00440                 float eps,
00441                 bool sorted) const
00442 {
00443         if(!index_)
00444         {
00445                 UERROR("Flann index not yet created!");
00446                 return;
00447         }
00448         indices.create(query.rows, knn, sizeof(size_t)==8?CV_64F:CV_32S);
00449         dists.create(query.rows, knn, featuresType_ == CV_8UC1?CV_32S:CV_32F);
00450 
00451         rtflann::Matrix<size_t> indicesF((size_t*)indices.data, indices.rows, indices.cols);
00452 
00453         rtflann::SearchParams params = rtflann::SearchParams(checks, eps, sorted);
00454 
00455         if(featuresType_ == CV_8UC1)
00456         {
00457                 rtflann::Matrix<unsigned int> distsF((unsigned int*)dists.data, dists.rows, dists.cols);
00458                 rtflann::Matrix<unsigned char> queryF(query.data, query.rows, query.cols);
00459                 ((rtflann::Index<rtflann::Hamming<unsigned char> >*)index_)->knnSearch(queryF, indicesF, distsF, knn, params);
00460         }
00461         else
00462         {
00463                 rtflann::Matrix<float> distsF((float*)dists.data, dists.rows, dists.cols);
00464                 rtflann::Matrix<float> queryF((float*)query.data, query.rows, query.cols);
00465                 if(useDistanceL1_)
00466                 {
00467                         ((rtflann::Index<rtflann::L1<float> >*)index_)->knnSearch(queryF, indicesF, distsF, knn, params);
00468                 }
00469                 else if(featuresDim_ <= 3)
00470                 {
00471                         ((rtflann::Index<rtflann::L2_Simple<float> >*)index_)->knnSearch(queryF, indicesF, distsF, knn, params);
00472                 }
00473                 else
00474                 {
00475                         ((rtflann::Index<rtflann::L2<float> >*)index_)->knnSearch(queryF, indicesF, distsF, knn, params);
00476                 }
00477         }
00478 }
00479 
00480 void FlannIndex::radiusSearch(
00481                 const cv::Mat & query,
00482                 std::vector<std::vector<size_t> > & indices,
00483                 std::vector<std::vector<float> > & dists,
00484                 float radius,
00485                 int maxNeighbors,
00486                 int checks,
00487                 float eps,
00488                 bool sorted) const
00489 {
00490         if(!index_)
00491         {
00492                 UERROR("Flann index not yet created!");
00493                 return;
00494         }
00495 
00496         rtflann::SearchParams params = rtflann::SearchParams(checks, eps, sorted);
00497         params.max_neighbors = maxNeighbors<=0?-1:maxNeighbors; // -1 is all in radius
00498 
00499         if(featuresType_ == CV_8UC1)
00500         {
00501                 std::vector<std::vector<unsigned int> > distsF;
00502                 rtflann::Matrix<unsigned char> queryF(query.data, query.rows, query.cols);
00503                 ((rtflann::Index<rtflann::Hamming<unsigned char> >*)index_)->radiusSearch(queryF, indices, distsF, radius*radius, params);
00504                 dists.resize(distsF.size());
00505                 for(unsigned int i=0; i<dists.size(); ++i)
00506                 {
00507                         dists[i].resize(distsF[i].size());
00508                         for(unsigned int j=0; j<distsF[i].size(); ++j)
00509                         {
00510                                 dists[i][j] = (float)distsF[i][j];
00511                         }
00512                 }
00513         }
00514         else
00515         {
00516                 rtflann::Matrix<float> queryF((float*)query.data, query.rows, query.cols);
00517                 if(useDistanceL1_)
00518                 {
00519                         ((rtflann::Index<rtflann::L1<float> >*)index_)->radiusSearch(queryF, indices, dists, radius*radius, params);
00520                 }
00521                 else if(featuresDim_ <= 3)
00522                 {
00523                         ((rtflann::Index<rtflann::L2_Simple<float> >*)index_)->radiusSearch(queryF, indices, dists, radius*radius, params);
00524                 }
00525                 else
00526                 {
00527                         ((rtflann::Index<rtflann::L2<float> >*)index_)->radiusSearch(queryF, indices, dists, radius*radius, params);
00528                 }
00529         }
00530 }
00531 
00532 } /* namespace rtabmap */


rtabmap
Author(s): Mathieu Labbe
autogenerated on Thu Jun 6 2019 21:59:20