VWDictionary.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/VWDictionary.h"
00029 #include "rtabmap/core/VisualWord.h"
00030 
00031 #include "rtabmap/core/Signature.h"
00032 #include "rtabmap/core/DBDriver.h"
00033 #include "rtabmap/core/Parameters.h"
00034 #include "rtabmap/core/FlannIndex.h"
00035 
00036 #include "rtabmap/utilite/UtiLite.h"
00037 
00038 #include <opencv2/opencv_modules.hpp>
00039 
00040 #if CV_MAJOR_VERSION < 3
00041 #ifdef HAVE_OPENCV_GPU
00042 #include <opencv2/gpu/gpu.hpp>
00043 #endif
00044 #else
00045 #include <opencv2/core/cuda.hpp>
00046 #ifdef HAVE_OPENCV_CUDAFEATURES2D
00047 #include <opencv2/cudafeatures2d.hpp>
00048 #endif
00049 #endif
00050 
00051 #include <fstream>
00052 #include <string>
00053 
00054 #define KDTREE_SIZE 4
00055 #define KNN_CHECKS 32
00056 
00057 namespace rtabmap
00058 {
00059 
00060 const int VWDictionary::ID_START = 1;
00061 const int VWDictionary::ID_INVALID = 0;
00062 
00063 VWDictionary::VWDictionary(const ParametersMap & parameters) :
00064         _totalActiveReferences(0),
00065         _incrementalDictionary(Parameters::defaultKpIncrementalDictionary()),
00066         _incrementalFlann(Parameters::defaultKpIncrementalFlann()),
00067         _rebalancingFactor(Parameters::defaultKpFlannRebalancingFactor()),
00068         _nndrRatio(Parameters::defaultKpNndrRatio()),
00069         _dictionaryPath(Parameters::defaultKpDictionaryPath()),
00070         _newWordsComparedTogether(Parameters::defaultKpNewWordsComparedTogether()),
00071         _lastWordId(0),
00072         useDistanceL1_(false),
00073         _flannIndex(new FlannIndex()),
00074         _strategy(kNNBruteForce)
00075 {
00076         this->setNNStrategy((NNStrategy)Parameters::defaultKpNNStrategy());
00077         this->parseParameters(parameters);
00078 }
00079 
00080 VWDictionary::~VWDictionary()
00081 {
00082         this->clear();
00083         delete _flannIndex;
00084 }
00085 
00086 void VWDictionary::parseParameters(const ParametersMap & parameters)
00087 {
00088         ParametersMap::const_iterator iter;
00089         Parameters::parse(parameters, Parameters::kKpNndrRatio(), _nndrRatio);
00090         Parameters::parse(parameters, Parameters::kKpNewWordsComparedTogether(), _newWordsComparedTogether);
00091         Parameters::parse(parameters, Parameters::kKpIncrementalFlann(), _incrementalFlann);
00092         Parameters::parse(parameters, Parameters::kKpFlannRebalancingFactor(), _rebalancingFactor);
00093 
00094         UASSERT_MSG(_nndrRatio > 0.0f, uFormat("String=%s value=%f", uContains(parameters, Parameters::kKpNndrRatio())?parameters.at(Parameters::kKpNndrRatio()).c_str():"", _nndrRatio).c_str());
00095 
00096         std::string dictionaryPath = _dictionaryPath;
00097         bool incrementalDictionary = _incrementalDictionary;
00098         if((iter=parameters.find(Parameters::kKpDictionaryPath())) != parameters.end())
00099         {
00100                 dictionaryPath = (*iter).second.c_str();
00101         }
00102         if((iter=parameters.find(Parameters::kKpIncrementalDictionary())) != parameters.end())
00103         {
00104                 incrementalDictionary = uStr2Bool((*iter).second.c_str());
00105         }
00106 
00107         // Verifying hypotheses strategy
00108         if((iter=parameters.find(Parameters::kKpNNStrategy())) != parameters.end())
00109         {
00110                 NNStrategy nnStrategy = (NNStrategy)std::atoi((*iter).second.c_str());
00111                 this->setNNStrategy(nnStrategy);
00112         }
00113 
00114         if(incrementalDictionary)
00115         {
00116                 this->setIncrementalDictionary();
00117         }
00118         else
00119         {
00120                 this->setFixedDictionary(dictionaryPath);
00121         }
00122 
00123 }
00124 
00125 void VWDictionary::setIncrementalDictionary()
00126 {
00127         if(!_incrementalDictionary)
00128         {
00129                 _incrementalDictionary = true;
00130                 if(_visualWords.size())
00131                 {
00132                         UWARN("Incremental dictionary set: already loaded visual words (%d) from the fixed dictionary will be included in the incremental one.", _visualWords.size());
00133                 }
00134         }
00135         _dictionaryPath = "";
00136 }
00137 
00138 void VWDictionary::setFixedDictionary(const std::string & dictionaryPath)
00139 {
00140         if(!dictionaryPath.empty())
00141         {
00142                 if((!_incrementalDictionary && _dictionaryPath.compare(dictionaryPath) != 0) ||
00143                    _visualWords.size() == 0)
00144                 {
00145                         UDEBUG("incremental=%d, oldPath=%s newPath=%s, visual words=%d",
00146                                         _incrementalDictionary?1:0, _dictionaryPath.c_str(), dictionaryPath.c_str(), (int)_visualWords.size());
00147 
00148                         if(UFile::getExtension(dictionaryPath).compare("db") == 0)
00149                         {
00150                                 UDEBUG("Loading fixed vocabulary \"%s\", this may take a while...", dictionaryPath.c_str());
00151                                 DBDriver * driver = DBDriver::create();
00152                                 if(driver->openConnection(dictionaryPath, false))
00153                                 {
00154                                         driver->load(this, false);
00155                                         for(std::map<int, VisualWord*>::iterator iter=_visualWords.begin(); iter!=_visualWords.end(); ++iter)
00156                                         {
00157                                                 iter->second->setSaved(true);
00158                                         }
00159                                         _incrementalDictionary = _visualWords.size()==0;
00160                                         driver->closeConnection(false);
00161                                 }
00162                                 else
00163                                 {
00164                                         UERROR("Could not load dictionary from database %s", dictionaryPath.c_str());
00165                                 }
00166                                 delete driver;
00167                         }
00168                         else
00169                         {
00170                                 UWARN("Loading fixed vocabulary \"%s\", this may take a while...", dictionaryPath.c_str());
00171                                 std::ifstream file;
00172                                 file.open(dictionaryPath.c_str(), std::ifstream::in);
00173                                 if(file.good())
00174                                 {
00175                                         UDEBUG("Deleting old dictionary and loading the new one from \"%s\"", dictionaryPath.c_str());
00176                                         UTimer timer;
00177 
00178                                         // first line is the header
00179                                         std::string str;
00180                                         std::list<std::string> strList;
00181                                         std::getline(file, str);
00182                                         strList = uSplitNumChar(str);
00183                                         int dimension  = 0;
00184                                         for(std::list<std::string>::iterator iter = strList.begin(); iter != strList.end(); ++iter)
00185                                         {
00186                                                 if(uIsDigit(iter->at(0)))
00187                                                 {
00188                                                         dimension = std::atoi(iter->c_str());
00189                                                         break;
00190                                                 }
00191                                         }
00192                                         UDEBUG("descriptor dimension = %d", dimension);
00193 
00194                                         if(dimension <= 0 || dimension > 1000)
00195                                         {
00196                                                 UERROR("Invalid dictionary file, visual word dimension (%d) is not valid, \"%s\"", dimension, dictionaryPath.c_str());
00197                                         }
00198                                         else
00199                                         {
00200                                                 // Process all words
00201                                                 while(file.good())
00202                                                 {
00203                                                         std::getline(file, str);
00204                                                         strList = uSplit(str);
00205                                                         if((int)strList.size() == dimension+1)
00206                                                         {
00207                                                                 //first one is the visual word id
00208                                                                 std::list<std::string>::iterator iter = strList.begin();
00209                                                                 int id = std::atoi(iter->c_str());
00210                                                                 cv::Mat descriptor(1, dimension, CV_32F);
00211                                                                 ++iter;
00212                                                                 int i=0;
00213 
00214                                                                 //get descriptor
00215                                                                 for(;i<dimension && iter != strList.end(); ++i, ++iter)
00216                                                                 {
00217                                                                         descriptor.at<float>(i) = uStr2Float(*iter);
00218                                                                 }
00219                                                                 if(i != dimension)
00220                                                                 {
00221                                                                         UERROR("Loaded word has not the same size (%d) than descriptor size previously detected (%d).", i, dimension);
00222                                                                 }
00223 
00224                                                                 VisualWord * vw = new VisualWord(id, descriptor, 0);
00225                                                                 vw->setSaved(true);
00226                                                                 _visualWords.insert(_visualWords.end(), std::pair<int, VisualWord*>(id, vw));
00227                                                                 _notIndexedWords.insert(_notIndexedWords.end(), id);
00228                                                                 _unusedWords.insert(_unusedWords.end(), std::pair<int, VisualWord*>(id, vw));
00229                                                         }
00230                                                         else if(!str.empty())
00231                                                         {
00232                                                                 UWARN("Cannot parse line \"%s\"", str.c_str());
00233                                                         }
00234                                                 }
00235                                                 if(_visualWords.size())
00236                                                 {
00237                                                         UWARN("Loaded %d words!", (int)_visualWords.size());
00238                                                 }
00239                                         }
00240                                 }
00241                                 else
00242                                 {
00243                                         UERROR("Cannot open dictionary file \"%s\"", dictionaryPath.c_str());
00244                                 }
00245                                 file.close();
00246                         }
00247 
00248                         if(_visualWords.size() == 0)
00249                         {
00250                                 _incrementalDictionary = _visualWords.size()==0;
00251                                 UWARN("No words loaded, cannot set a fixed dictionary.", (int)_visualWords.size());
00252                         }
00253                         else
00254                         {
00255                                 this->update();
00256                                 _incrementalDictionary = false;
00257                                 UDEBUG("Loaded %d words!", (int)_visualWords.size());
00258                         }
00259                 }
00260                 else if(!_incrementalDictionary)
00261                 {
00262                         UDEBUG("Dictionary \"%s\" already loaded...", dictionaryPath.c_str());
00263                 }
00264                 else
00265                 {
00266                         UERROR("Cannot change to a fixed dictionary if there are already words (%d) in the incremental one.", _visualWords.size());
00267                 }
00268         }
00269         else if(_incrementalDictionary && _visualWords.size())
00270         {
00271                 UWARN("Cannot change to fixed dictionary, %d words already loaded as incremental", (int)_visualWords.size());
00272         }
00273         else
00274         {
00275                 _incrementalDictionary = false;
00276         }
00277         _dictionaryPath = dictionaryPath;
00278 }
00279 
00280 void VWDictionary::setNNStrategy(NNStrategy strategy)
00281 {
00282         if(strategy!=kNNUndef)
00283         {
00284 #if CV_MAJOR_VERSION < 3
00285 #ifdef HAVE_OPENCV_GPU
00286                 if(strategy == kNNBruteForceGPU && !cv::gpu::getCudaEnabledDeviceCount())
00287                 {
00288                         UERROR("Nearest neighobr strategy \"kNNBruteForceGPU\" chosen but no CUDA devices found! Doing \"kNNBruteForce\" instead.");
00289                         strategy = kNNBruteForce;
00290                 }
00291 #else
00292                 if(strategy == kNNBruteForceGPU)
00293                 {
00294                         UERROR("Nearest neighobr strategy \"kNNBruteForceGPU\" chosen but OpenCV is not built with GPU/cuda module! Doing \"kNNBruteForce\" instead.");
00295                         strategy = kNNBruteForce;
00296                 }
00297 #endif
00298 #else
00299 #ifdef HAVE_OPENCV_CUDAFEATURES2D
00300                 if(strategy == kNNBruteForceGPU && !cv::cuda::getCudaEnabledDeviceCount())
00301                 {
00302                         UERROR("Nearest neighobr strategy \"kNNBruteForceGPU\" chosen but no CUDA devices found! Doing \"kNNBruteForce\" instead.");
00303                         strategy = kNNBruteForce;
00304                 }
00305 #else
00306                 if(strategy == kNNBruteForceGPU)
00307                 {
00308                         UERROR("Nearest neighobr strategy \"kNNBruteForceGPU\" chosen but OpenCV cudafeatures2d module is not found! Doing \"kNNBruteForce\" instead.");
00309                         strategy = kNNBruteForce;
00310                 }
00311 #endif
00312 #endif
00313 
00314                 bool update = _strategy != strategy;
00315                 _strategy = strategy;
00316                 if(update)
00317                 {
00318                         _dataTree = cv::Mat();
00319                         _notIndexedWords = uKeysSet(_visualWords);
00320                         _removedIndexedWords.clear();
00321                         this->update();
00322                 }
00323         }
00324 }
00325 
00326 int VWDictionary::getLastIndexedWordId() const
00327 {
00328         if(_mapIndexId.size())
00329         {
00330                 return _mapIndexId.rbegin()->second;
00331         }
00332         else
00333         {
00334                 return 0;
00335         }
00336 }
00337 
00338 unsigned int VWDictionary::getIndexedWordsCount() const
00339 {
00340         return _flannIndex->indexedFeatures();
00341 }
00342 
00343 unsigned int VWDictionary::getIndexMemoryUsed() const
00344 {
00345         return _flannIndex->memoryUsed();
00346 }
00347 
00348 void VWDictionary::update()
00349 {
00350         ULOGGER_DEBUG("");
00351         if(!_incrementalDictionary && !_notIndexedWords.size())
00352         {
00353                 // No need to update the search index if we
00354                 // use a fixed dictionary and the index is
00355                 // already built
00356                 return;
00357         }
00358 
00359         if(_notIndexedWords.size() || _visualWords.size() == 0 || _removedIndexedWords.size())
00360         {
00361                 if(_incrementalFlann &&
00362                    _strategy < kNNBruteForce &&
00363                    _visualWords.size())
00364                 {
00365                         ULOGGER_DEBUG("Incremental FLANN: Removing %d words...", (int)_removedIndexedWords.size());
00366                         for(std::set<int>::iterator iter=_removedIndexedWords.begin(); iter!=_removedIndexedWords.end(); ++iter)
00367                         {
00368                                 UASSERT(uContains(_mapIdIndex, *iter));
00369                                 UASSERT(uContains(_mapIndexId, _mapIdIndex.at(*iter)));
00370                                 _flannIndex->removePoint(_mapIdIndex.at(*iter));
00371                                 _mapIndexId.erase(_mapIdIndex.at(*iter));
00372                                 _mapIdIndex.erase(*iter);
00373                         }
00374                         ULOGGER_DEBUG("Incremental FLANN: Removing %d words... done!", (int)_removedIndexedWords.size());
00375 
00376                         if(_notIndexedWords.size())
00377                         {
00378                                 ULOGGER_DEBUG("Incremental FLANN: Inserting %d words...", (int)_notIndexedWords.size());
00379                                 for(std::set<int>::iterator iter=_notIndexedWords.begin(); iter!=_notIndexedWords.end(); ++iter)
00380                                 {
00381                                         VisualWord* w = uValue(_visualWords, *iter, (VisualWord*)0);
00382                                         UASSERT(w);
00383 
00384                                         cv::Mat descriptor;
00385                                         if(w->getDescriptor().type() == CV_8U)
00386                                         {
00387                                                 useDistanceL1_ = true;
00388                                                 if(_strategy == kNNFlannKdTree || _strategy == kNNFlannNaive)
00389                                                 {
00390                                                         w->getDescriptor().convertTo(descriptor, CV_32F);
00391                                                 }
00392                                                 else
00393                                                 {
00394                                                         descriptor = w->getDescriptor();
00395                                                 }
00396                                         }
00397                                         else
00398                                         {
00399                                                 descriptor = w->getDescriptor();
00400                                         }
00401 
00402                                         int index = 0;
00403                                         if(!_flannIndex->isBuilt())
00404                                         {
00405                                                 UDEBUG("Building FLANN index...");
00406                                                 switch(_strategy)
00407                                                 {
00408                                                 case kNNFlannNaive:
00409                                                         _flannIndex->buildLinearIndex(descriptor, useDistanceL1_, _rebalancingFactor);
00410                                                         break;
00411                                                 case kNNFlannKdTree:
00412                                                         UASSERT_MSG(descriptor.type() == CV_32F, "To use KdTree dictionary, float descriptors are required!");
00413                                                         _flannIndex->buildKDTreeIndex(descriptor, KDTREE_SIZE, useDistanceL1_, _rebalancingFactor);
00414                                                         break;
00415                                                 case kNNFlannLSH:
00416                                                         UASSERT_MSG(descriptor.type() == CV_8U, "To use LSH dictionary, binary descriptors are required!");
00417                                                         _flannIndex->buildLSHIndex(descriptor, 12, 20, 2, _rebalancingFactor);
00418                                                         break;
00419                                                 default:
00420                                                         UFATAL("Not supposed to be here!");
00421                                                         break;
00422                                                 }
00423                                                 UDEBUG("Building FLANN index... done!");
00424                                         }
00425                                         else
00426                                         {
00427                                                 UASSERT(descriptor.cols == _flannIndex->featuresDim());
00428                                                 UASSERT(descriptor.type() == _flannIndex->featuresType());
00429                                                 index = _flannIndex->addPoints(descriptor);
00430                                         }
00431                                         std::pair<std::map<int, int>::iterator, bool> inserted;
00432                                         inserted = _mapIndexId.insert(std::pair<int, int>(index, w->id()));
00433                                         UASSERT(inserted.second);
00434                                         inserted = _mapIdIndex.insert(std::pair<int, int>(w->id(), index));
00435                                         UASSERT(inserted.second);
00436                                 }
00437                                 ULOGGER_DEBUG("Incremental FLANN: Inserting %d words... done!", (int)_notIndexedWords.size());
00438                         }
00439                 }
00440                 else if(_strategy >= kNNBruteForce &&
00441                                 _notIndexedWords.size() &&
00442                                 _removedIndexedWords.size() == 0 &&
00443                                 _visualWords.size() &&
00444                                 _dataTree.rows)
00445                 {
00446                         //just add not indexed words
00447                         int i = _dataTree.rows;
00448                         _dataTree.reserve(_dataTree.rows + _notIndexedWords.size());
00449                         for(std::set<int>::iterator iter=_notIndexedWords.begin(); iter!=_notIndexedWords.end(); ++iter)
00450                         {
00451                                 VisualWord* w = uValue(_visualWords, *iter, (VisualWord*)0);
00452                                 UASSERT(w);
00453                                 UASSERT(w->getDescriptor().cols == _dataTree.cols);
00454                                 UASSERT(w->getDescriptor().type() == _dataTree.type());
00455                                 _dataTree.push_back(w->getDescriptor());
00456                                 _mapIndexId.insert(_mapIndexId.end(), std::pair<int, int>(i, w->id()));
00457                                 std::pair<std::map<int, int>::iterator, bool> inserted = _mapIdIndex.insert(std::pair<int, int>(w->id(), i));
00458                                 UASSERT(inserted.second);
00459                                 ++i;
00460                         }
00461                 }
00462                 else
00463                 {
00464                         _mapIndexId.clear();
00465                         _mapIdIndex.clear();
00466                         _dataTree = cv::Mat();
00467                         _flannIndex->release();
00468 
00469                         if(_visualWords.size())
00470                         {
00471                                 UTimer timer;
00472                                 timer.start();
00473 
00474                                 int type;
00475                                 if(_visualWords.begin()->second->getDescriptor().type() == CV_8U)
00476                                 {
00477                                         useDistanceL1_ = true;
00478                                         if(_strategy == kNNFlannKdTree || _strategy == kNNFlannNaive)
00479                                         {
00480                                                 type = CV_32F;
00481                                         }
00482                                         else
00483                                         {
00484                                                 type = _visualWords.begin()->second->getDescriptor().type();
00485                                         }
00486                                 }
00487                                 else
00488                                 {
00489                                         type = _visualWords.begin()->second->getDescriptor().type();
00490                                 }
00491                                 int dim = _visualWords.begin()->second->getDescriptor().cols;
00492 
00493                                 UASSERT(type == CV_32F || type == CV_8U);
00494                                 UASSERT(dim > 0);
00495 
00496                                 // Create the data matrix
00497                                 _dataTree = cv::Mat(_visualWords.size(), dim, type); // SURF descriptors are CV_32F
00498                                 std::map<int, VisualWord*>::const_iterator iter = _visualWords.begin();
00499                                 for(unsigned int i=0; i < _visualWords.size(); ++i, ++iter)
00500                                 {
00501                                         cv::Mat descriptor;
00502                                         if(iter->second->getDescriptor().type() == CV_8U)
00503                                         {
00504                                                 if(_strategy == kNNFlannKdTree || _strategy == kNNFlannNaive)
00505                                                 {
00506                                                         iter->second->getDescriptor().convertTo(descriptor, CV_32F);
00507                                                 }
00508                                                 else
00509                                                 {
00510                                                         descriptor = iter->second->getDescriptor();
00511                                                 }
00512                                         }
00513                                         else
00514                                         {
00515                                                 descriptor = iter->second->getDescriptor();
00516                                         }
00517 
00518                                         UASSERT(descriptor.cols == dim);
00519                                         UASSERT(descriptor.type() == type);
00520 
00521                                         descriptor.copyTo(_dataTree.row(i));
00522                                         _mapIndexId.insert(_mapIndexId.end(), std::pair<int, int>(i, iter->second->id()));
00523                                         _mapIdIndex.insert(_mapIdIndex.end(), std::pair<int, int>(iter->second->id(), i));
00524                                 }
00525 
00526                                 ULOGGER_DEBUG("_mapIndexId.size() = %d, words.size()=%d, _dim=%d",_mapIndexId.size(), _visualWords.size(), dim);
00527                                 ULOGGER_DEBUG("copying data = %f s", timer.ticks());
00528 
00529                                 switch(_strategy)
00530                                 {
00531                                 case kNNFlannNaive:
00532                                         _flannIndex->buildLinearIndex(_dataTree, useDistanceL1_, _rebalancingFactor);
00533                                         break;
00534                                 case kNNFlannKdTree:
00535                                         UASSERT_MSG(type == CV_32F, "To use KdTree dictionary, float descriptors are required!");
00536                                         _flannIndex->buildKDTreeIndex(_dataTree, KDTREE_SIZE, useDistanceL1_, _rebalancingFactor);
00537                                         break;
00538                                 case kNNFlannLSH:
00539                                         UASSERT_MSG(type == CV_8U, "To use LSH dictionary, binary descriptors are required!");
00540                                         _flannIndex->buildLSHIndex(_dataTree, 12, 20, 2, _rebalancingFactor);
00541                                         break;
00542                                 default:
00543                                         break;
00544                                 }
00545 
00546                                 ULOGGER_DEBUG("Time to create kd tree = %f s", timer.ticks());
00547                         }
00548                 }
00549                 UDEBUG("Dictionary updated! (size=%d added=%d removed=%d)",
00550                                 _dataTree.rows, _notIndexedWords.size(), _removedIndexedWords.size());
00551         }
00552         else
00553         {
00554                 UDEBUG("Dictionary has not changed, so no need to update it! (size=%d)", _dataTree.rows);
00555         }
00556         _notIndexedWords.clear();
00557         _removedIndexedWords.clear();
00558         UDEBUG("");
00559 }
00560 
00561 void VWDictionary::clear(bool printWarningsIfNotEmpty)
00562 {
00563         ULOGGER_DEBUG("");
00564         if(printWarningsIfNotEmpty)
00565         {
00566                 if(_visualWords.size() && _incrementalDictionary)
00567                 {
00568                         UWARN("Visual dictionary would be already empty here (%d words still in dictionary).", (int)_visualWords.size());
00569                 }
00570                 if(_notIndexedWords.size())
00571                 {
00572                         UWARN("Not indexed words should be empty here (%d words still not indexed)", (int)_notIndexedWords.size());
00573                 }
00574         }
00575         for(std::map<int, VisualWord *>::iterator i=_visualWords.begin(); i!=_visualWords.end(); ++i)
00576         {
00577                 delete (*i).second;
00578         }
00579         _visualWords.clear();
00580         _notIndexedWords.clear();
00581         _removedIndexedWords.clear();
00582         _totalActiveReferences = 0;
00583         _lastWordId = 0;
00584         _dataTree = cv::Mat();
00585         _mapIndexId.clear();
00586         _mapIdIndex.clear();
00587         _unusedWords.clear();
00588         _flannIndex->release();
00589         useDistanceL1_ = false;
00590 
00591         if(!_incrementalDictionary)
00592         {
00593                 // reload the fixed dictionary
00594                 this->setFixedDictionary(_dictionaryPath);
00595         }
00596 }
00597 
00598 int VWDictionary::getNextId()
00599 {
00600         return ++_lastWordId;
00601 }
00602 
00603 void VWDictionary::addWordRef(int wordId, int signatureId)
00604 {
00605         VisualWord * vw = 0;
00606         vw = uValue(_visualWords, wordId, vw);
00607         if(vw)
00608         {
00609                 vw->addRef(signatureId);
00610                 _totalActiveReferences += 1;
00611 
00612                 _unusedWords.erase(vw->id());
00613         }
00614         else
00615         {
00616                 UERROR("Not found word %d (dict size=%d)", wordId, (int)_visualWords.size());
00617         }
00618 }
00619 
00620 void VWDictionary::removeAllWordRef(int wordId, int signatureId)
00621 {
00622         VisualWord * vw = 0;
00623         vw = uValue(_visualWords, wordId, vw);
00624         if(vw)
00625         {
00626                 _totalActiveReferences -= vw->removeAllRef(signatureId);
00627                 if(vw->getReferences().size() == 0)
00628                 {
00629                         _unusedWords.insert(std::pair<int, VisualWord*>(vw->id(), vw));
00630                 }
00631         }
00632 }
00633 
00634 std::list<int> VWDictionary::addNewWords(const cv::Mat & descriptorsIn,
00635                                                            int signatureId)
00636 {
00637         UDEBUG("id=%d descriptors=%d", signatureId, descriptorsIn.rows);
00638         UTimer timer;
00639         std::list<int> wordIds;
00640         if(descriptorsIn.rows == 0 || descriptorsIn.cols == 0)
00641         {
00642                 UERROR("Descriptors size is null!");
00643                 return wordIds;
00644         }
00645 
00646         if(!_incrementalDictionary && _visualWords.empty())
00647         {
00648                 UERROR("Dictionary mode is set to fixed but no words are in it!");
00649                 return wordIds;
00650         }
00651 
00652         // verify we have the same features
00653         int dim = 0;
00654         int type = -1;
00655         if(_visualWords.size())
00656         {
00657                 dim = _visualWords.begin()->second->getDescriptor().cols;
00658                 type = _visualWords.begin()->second->getDescriptor().type();
00659                 UASSERT(type == CV_32F || type == CV_8U);
00660         }
00661         if(dim && dim != descriptorsIn.cols)
00662         {
00663                 UERROR("Descriptors (size=%d) are not the same size as already added words in dictionary(size=%d)", descriptorsIn.cols, dim);
00664                 return wordIds;
00665         }
00666         if(type>=0 && type != descriptorsIn.type())
00667         {
00668                 UERROR("Descriptors (type=%d) are not the same type as already added words in dictionary(type=%d)", descriptorsIn.type(), type);
00669                 return wordIds;
00670         }
00671 
00672         // now compare with the actual index
00673         cv::Mat descriptors;
00674         if(descriptorsIn.type() == CV_8U)
00675         {
00676                 useDistanceL1_ = true;
00677                 if(_strategy == kNNFlannKdTree || _strategy == kNNFlannNaive)
00678                 {
00679                         descriptorsIn.convertTo(descriptors, CV_32F);
00680                 }
00681                 else
00682                 {
00683                         descriptors = descriptorsIn;
00684                 }
00685         }
00686         else
00687         {
00688                 descriptors = descriptorsIn;
00689         }
00690         dim = 0;
00691         type = -1;
00692         if(_dataTree.rows || _flannIndex->isBuilt())
00693         {
00694                 dim = _flannIndex->isBuilt()?_flannIndex->featuresDim():_dataTree.cols;
00695                 type = _flannIndex->isBuilt()?_flannIndex->featuresType():_dataTree.type();
00696                 UASSERT(type == CV_32F || type == CV_8U);
00697         }
00698 
00699         if(dim && dim != descriptors.cols)
00700         {
00701                 UERROR("Descriptors (size=%d) are not the same size as already added words in dictionary(size=%d)", descriptors.cols, dim);
00702                 return wordIds;
00703         }
00704 
00705         if(type>=0 && type != descriptors.type())
00706         {
00707                 UERROR("Descriptors (type=%d) are not the same type as already added words in dictionary(type=%d)", descriptors.type(), type);
00708                 return wordIds;
00709         }
00710 
00711         int dupWordsCountFromDict= 0;
00712         int dupWordsCountFromLast= 0;
00713 
00714         unsigned int k=2; // k nearest neighbors
00715 
00716         cv::Mat newWords;
00717         std::vector<int> newWordsId;
00718 
00719         cv::Mat results;
00720         cv::Mat dists;
00721         std::vector<std::vector<cv::DMatch> > matches;
00722         bool bruteForce = false;
00723 
00724         UTimer timerLocal;
00725         timerLocal.start();
00726 
00727         if(_flannIndex->isBuilt() || (!_dataTree.empty() && _dataTree.rows >= (int)k))
00728         {
00729                 //Find nearest neighbors
00730                 UDEBUG("newPts.total()=%d ", descriptors.rows);
00731 
00732                 if(_strategy == kNNFlannNaive || _strategy == kNNFlannKdTree || _strategy == kNNFlannLSH)
00733                 {
00734                         _flannIndex->knnSearch(descriptors, results, dists, k, KNN_CHECKS);
00735                 }
00736                 else if(_strategy == kNNBruteForce)
00737                 {
00738                         bruteForce = true;
00739                         cv::BFMatcher matcher(descriptors.type()==CV_8U?cv::NORM_HAMMING:cv::NORM_L2SQR);
00740                         matcher.knnMatch(descriptors, _dataTree, matches, k);
00741                 }
00742                 else if(_strategy == kNNBruteForceGPU)
00743                 {
00744                         bruteForce = true;
00745 #if CV_MAJOR_VERSION < 3
00746 #ifdef HAVE_OPENCV_GPU
00747                         cv::gpu::GpuMat newDescriptorsGpu(descriptors);
00748                         cv::gpu::GpuMat lastDescriptorsGpu(_dataTree);
00749                         if(descriptors.type()==CV_8U)
00750                         {
00751                                 cv::gpu::BruteForceMatcher_GPU<cv::Hamming> gpuMatcher;
00752                                 gpuMatcher.knnMatch(newDescriptorsGpu, lastDescriptorsGpu, matches, k);
00753                         }
00754                         else
00755                         {
00756                                 cv::gpu::BruteForceMatcher_GPU<cv::L2<float> > gpuMatcher;
00757                                 gpuMatcher.knnMatch(newDescriptorsGpu, lastDescriptorsGpu, matches, k);
00758                         }
00759 #else
00760                         UERROR("Cannot use brute Force GPU because OpenCV is not built with gpu module.");
00761 #endif
00762 #else
00763 #ifdef HAVE_OPENCV_CUDAFEATURES2D
00764                         cv::cuda::GpuMat newDescriptorsGpu(descriptors);
00765                         cv::cuda::GpuMat lastDescriptorsGpu(_dataTree);
00766                         cv::Ptr<cv::cuda::DescriptorMatcher> gpuMatcher;
00767                         if(descriptors.type()==CV_8U)
00768                         {
00769                                 gpuMatcher = cv::cuda::DescriptorMatcher::createBFMatcher(cv::NORM_HAMMING);
00770                                 gpuMatcher->knnMatch(newDescriptorsGpu, lastDescriptorsGpu, matches, k);
00771                         }
00772                         else
00773                         {
00774                                 gpuMatcher = cv::cuda::DescriptorMatcher::createBFMatcher(cv::NORM_L2);
00775                                 gpuMatcher->knnMatch(newDescriptorsGpu, lastDescriptorsGpu, matches, k);
00776                         }
00777 #else
00778                         UERROR("Cannot use brute Force GPU because OpenCV is not built with cuda module.");
00779 #endif
00780 #endif
00781                 }
00782                 else
00783                 {
00784                         UFATAL("");
00785                 }
00786 
00787                 // In case of binary descriptors
00788                 if(dists.type() == CV_32S)
00789                 {
00790                         cv::Mat temp;
00791                         dists.convertTo(temp, CV_32F);
00792                         dists = temp;
00793                 }
00794 
00795                 UDEBUG("Time to find nn = %f s", timerLocal.ticks());
00796         }
00797 
00798         // Process results
00799         for(int i = 0; i < descriptors.rows; ++i)
00800         {
00801                 std::multimap<float, int> fullResults; // Contains results from the kd-tree search and the naive search in new words
00802                 if(!bruteForce && dists.cols)
00803                 {
00804                         for(int j=0; j<dists.cols; ++j)
00805                         {
00806                                 float d = dists.at<float>(i,j);
00807                                 int index;
00808                                 if (sizeof(size_t) == 8)
00809                                 {
00810                                         index = *((size_t*)&results.at<double>(i, j));
00811                                 }
00812                                 else
00813                                 {
00814                                         index = *((size_t*)&results.at<int>(i, j));
00815                                 }
00816                                 int id = uValue(_mapIndexId, index);
00817                                 if(d >= 0.0f && id != 0)
00818                                 {
00819                                         fullResults.insert(std::pair<float, int>(d, id));
00820                                 }
00821                                 else
00822                                 {
00823                                         break;
00824                                 }
00825                         }
00826                 }
00827                 else if(bruteForce && matches.size())
00828                 {
00829                         for(unsigned int j=0; j<matches.at(i).size(); ++j)
00830                         {
00831                                 float d = matches.at(i).at(j).distance;
00832                                 int id = uValue(_mapIndexId, matches.at(i).at(j).trainIdx);
00833                                 if(d >= 0.0f && id != 0)
00834                                 {
00835                                         fullResults.insert(std::pair<float, int>(d, id));
00836                                 }
00837                                 else
00838                                 {
00839                                         break;
00840                                 }
00841                         }
00842                 }
00843 
00844                 // Check if this descriptor matches with a word from the last signature (a word not already added to the tree)
00845                 if(_newWordsComparedTogether && newWords.rows)
00846                 {
00847                         std::vector<std::vector<cv::DMatch> > matchesNewWords;
00848                         cv::BFMatcher matcher(descriptors.type()==CV_8U?cv::NORM_HAMMING:useDistanceL1_?cv::NORM_L1:cv::NORM_L2SQR);
00849                         UASSERT(descriptors.cols == newWords.cols && descriptors.type() == newWords.type());
00850                         matcher.knnMatch(descriptors.row(i), newWords, matchesNewWords, newWords.rows>1?2:1);
00851                         UASSERT(matchesNewWords.size() == 1);
00852                         for(unsigned int j=0; j<matchesNewWords.at(0).size(); ++j)
00853                         {
00854                                 float d = matchesNewWords.at(0).at(j).distance;
00855                                 int id = newWordsId[matchesNewWords.at(0).at(j).trainIdx];
00856                                 if(d >= 0.0f && id != 0)
00857                                 {
00858                                         fullResults.insert(std::pair<float, int>(d, id));
00859                                 }
00860                                 else
00861                                 {
00862                                         break;
00863                                 }
00864                         }
00865                 }
00866 
00867                 if(_incrementalDictionary)
00868                 {
00869                         bool badDist = false;
00870                         if(fullResults.size() == 0)
00871                         {
00872                                 badDist = true;
00873                         }
00874                         if(!badDist)
00875                         {
00876                                 if(fullResults.size() >= 2)
00877                                 {
00878                                         // Apply NNDR
00879                                         if(fullResults.begin()->first > _nndrRatio * (++fullResults.begin())->first)
00880                                         {
00881                                                 badDist = true; // Rejected
00882                                         }
00883                                 }
00884                                 else
00885                                 {
00886                                         badDist = true; // Rejected
00887                                 }
00888                         }
00889 
00890                         if(badDist)
00891                         {
00892                                 // use original descriptor
00893                                 VisualWord * vw = new VisualWord(getNextId(), descriptorsIn.row(i), signatureId);
00894                                 _visualWords.insert(_visualWords.end(), std::pair<int, VisualWord *>(vw->id(), vw));
00895                                 _notIndexedWords.insert(_notIndexedWords.end(), vw->id());
00896                                 newWords.push_back(descriptors.row(i));
00897                                 newWordsId.push_back(vw->id());
00898                                 wordIds.push_back(vw->id());
00899                                 UASSERT(vw->id()>0);
00900                         }
00901                         else
00902                         {
00903                                 if(_notIndexedWords.find(fullResults.begin()->second) != _notIndexedWords.end())
00904                                 {
00905                                         ++dupWordsCountFromLast;
00906                                 }
00907                                 else
00908                                 {
00909                                         ++dupWordsCountFromDict;
00910                                 }
00911 
00912                                 this->addWordRef(fullResults.begin()->second, signatureId);
00913                                 wordIds.push_back(fullResults.begin()->second);
00914                         }
00915                 }
00916                 else if(fullResults.size())
00917                 {
00918                         // If the dictionary is not incremental, just take the nearest word
00919                         ++dupWordsCountFromDict;
00920                         this->addWordRef(fullResults.begin()->second, signatureId);
00921                         wordIds.push_back(fullResults.begin()->second);
00922                         UASSERT(fullResults.begin()->second>0);
00923                 }
00924         }
00925         ULOGGER_DEBUG("naive search and add ref/words time = %f s", timerLocal.ticks());
00926 
00927         ULOGGER_DEBUG("%d new words added...", _notIndexedWords.size());
00928         ULOGGER_DEBUG("%d duplicated words added (from current image = %d)...",
00929                         dupWordsCountFromDict+dupWordsCountFromLast, dupWordsCountFromLast);
00930         UDEBUG("total time %fs", timer.ticks());
00931 
00932         _totalActiveReferences += _notIndexedWords.size();
00933         return wordIds;
00934 }
00935 
00936 std::vector<int> VWDictionary::findNN(const std::list<VisualWord *> & vws) const
00937 {
00938         UTimer timer;
00939         timer.start();
00940 
00941         if(_visualWords.size() && vws.size())
00942         {
00943                 int type = (*vws.begin())->getDescriptor().type();
00944                 int dim = (*vws.begin())->getDescriptor().cols;
00945 
00946                 if(dim != _visualWords.begin()->second->getDescriptor().cols)
00947                 {
00948                         UERROR("Descriptors (size=%d) are not the same size as already added words in dictionary(size=%d)", (*vws.begin())->getDescriptor().cols, dim);
00949                         return std::vector<int>(vws.size(), 0);
00950                 }
00951 
00952                 if(type != _visualWords.begin()->second->getDescriptor().type())
00953                 {
00954                         UERROR("Descriptors (type=%d) are not the same type as already added words in dictionary(type=%d)", (*vws.begin())->getDescriptor().type(), type);
00955                         return std::vector<int>(vws.size(), 0);
00956                 }
00957 
00958                 // fill the request matrix
00959                 int index = 0;
00960                 VisualWord * vw;
00961                 cv::Mat query(vws.size(), dim, type);
00962                 for(std::list<VisualWord *>::const_iterator iter=vws.begin(); iter!=vws.end(); ++iter, ++index)
00963                 {
00964                         vw = *iter;
00965                         UASSERT(vw);
00966 
00967                         UASSERT(vw->getDescriptor().cols == dim);
00968                         UASSERT(vw->getDescriptor().type() == type);
00969 
00970                         vw->getDescriptor().copyTo(query.row(index));
00971                 }
00972                 ULOGGER_DEBUG("Preparation time = %fs", timer.ticks());
00973 
00974                 return findNN(query);
00975         }
00976         return std::vector<int>(vws.size(), 0);
00977 }
00978 std::vector<int> VWDictionary::findNN(const cv::Mat & queryIn) const
00979 {
00980         UTimer timer;
00981         timer.start();
00982         std::vector<int> resultIds(queryIn.rows, 0);
00983         unsigned int k=2; // k nearest neighbor
00984 
00985         if(_visualWords.size() && queryIn.rows)
00986         {
00987                 // verify we have the same features
00988                 int dim = _visualWords.begin()->second->getDescriptor().cols;
00989                 int type = _visualWords.begin()->second->getDescriptor().type();
00990                 UASSERT(type == CV_32F || type == CV_8U);
00991 
00992                 if(dim != queryIn.cols)
00993                 {
00994                         UERROR("Descriptors (size=%d) are not the same size as already added words in dictionary(size=%d)", queryIn.cols, dim);
00995                         return resultIds;
00996                 }
00997                 if(type != queryIn.type())
00998                 {
00999                         UERROR("Descriptors (type=%d) are not the same type as already added words in dictionary(type=%d)", queryIn.type(), type);
01000                         return resultIds;
01001                 }
01002 
01003                 // now compare with the actual index
01004                 cv::Mat query;
01005                 if(queryIn.type() == CV_8U)
01006                 {
01007                         if(_strategy == kNNFlannKdTree || _strategy == kNNFlannNaive)
01008                         {
01009                                 queryIn.convertTo(query, CV_32F);
01010                         }
01011                         else
01012                         {
01013                                 query = queryIn;
01014                         }
01015                 }
01016                 else
01017                 {
01018                         query = queryIn;
01019                 }
01020                 dim = 0;
01021                 type = -1;
01022                 if(_dataTree.rows || _flannIndex->isBuilt())
01023                 {
01024                         dim = _flannIndex->isBuilt()?_flannIndex->featuresDim():_dataTree.cols;
01025                         type = _flannIndex->isBuilt()?_flannIndex->featuresType():_dataTree.type();
01026                         UASSERT(type == CV_32F || type == CV_8U);
01027                 }
01028 
01029                 if(dim && dim != query.cols)
01030                 {
01031                         UERROR("Descriptors (size=%d) are not the same size as already added words in dictionary(size=%d)", query.cols, dim);
01032                         return resultIds;
01033                 }
01034 
01035                 if(type>=0 && type != query.type())
01036                 {
01037                         UERROR("Descriptors (type=%d) are not the same type as already added words in dictionary(type=%d)", query.type(), type);
01038                         return resultIds;
01039                 }
01040 
01041                 std::vector<std::vector<cv::DMatch> > matches;
01042                 bool bruteForce = false;
01043                 cv::Mat results;
01044                 cv::Mat dists;
01045 
01046                 if(_flannIndex->isBuilt() || (!_dataTree.empty() && _dataTree.rows >= (int)k))
01047                 {
01048                         //Find nearest neighbors
01049                         UDEBUG("query.rows=%d ", query.rows);
01050 
01051                         if(_strategy == kNNFlannNaive || _strategy == kNNFlannKdTree || _strategy == kNNFlannLSH)
01052                         {
01053                                 _flannIndex->knnSearch(query, results, dists, k, KNN_CHECKS);
01054                         }
01055                         else if(_strategy == kNNBruteForce)
01056                         {
01057                                 bruteForce = true;
01058                                 cv::BFMatcher matcher(query.type()==CV_8U?cv::NORM_HAMMING:cv::NORM_L2SQR);
01059                                 matcher.knnMatch(query, _dataTree, matches, k);
01060                         }
01061                         else if(_strategy == kNNBruteForceGPU)
01062                         {
01063                                 bruteForce = true;
01064 #if CV_MAJOR_VERSION < 3
01065 #ifdef HAVE_OPENCV_GPU
01066                                 cv::gpu::GpuMat newDescriptorsGpu(query);
01067                                 cv::gpu::GpuMat lastDescriptorsGpu(_dataTree);
01068                                 if(query.type()==CV_8U)
01069                                 {
01070                                         cv::gpu::BruteForceMatcher_GPU<cv::Hamming> gpuMatcher;
01071                                         gpuMatcher.knnMatch(newDescriptorsGpu, lastDescriptorsGpu, matches, k);
01072                                 }
01073                                 else
01074                                 {
01075                                         cv::gpu::BruteForceMatcher_GPU<cv::L2<float> > gpuMatcher;
01076                                         gpuMatcher.knnMatch(newDescriptorsGpu, lastDescriptorsGpu, matches, k);
01077                                 }
01078 #else
01079                         UERROR("Cannot use brute Force GPU because OpenCV is not built with gpu module.");
01080 #endif
01081 #else
01082 #ifdef HAVE_OPENCV_CUDAFEATURES2D
01083                                 cv::cuda::GpuMat newDescriptorsGpu(query);
01084                                 cv::cuda::GpuMat lastDescriptorsGpu(_dataTree);
01085                                 cv::Ptr<cv::cuda::DescriptorMatcher> gpuMatcher;
01086                                 if(query.type()==CV_8U)
01087                                 {
01088                                         gpuMatcher = cv::cuda::DescriptorMatcher::createBFMatcher(cv::NORM_HAMMING);
01089                                         gpuMatcher->knnMatchAsync(newDescriptorsGpu, lastDescriptorsGpu, matches, k);
01090                                 }
01091                                 else
01092                                 {
01093                                         gpuMatcher = cv::cuda::DescriptorMatcher::createBFMatcher(cv::NORM_L2);
01094                                         gpuMatcher->knnMatchAsync(newDescriptorsGpu, lastDescriptorsGpu, matches, k);
01095                                 }
01096 #else
01097                         UERROR("Cannot use brute Force GPU because OpenCV is not built with cuda module.");
01098 #endif
01099 #endif
01100                         }
01101                         else
01102                         {
01103                                 UFATAL("");
01104                         }
01105 
01106                         // In case of binary descriptors
01107                         if(dists.type() == CV_32S)
01108                         {
01109                                 cv::Mat temp;
01110                                 dists.convertTo(temp, CV_32F);
01111                                 dists = temp;
01112                         }
01113                 }
01114                 ULOGGER_DEBUG("Search dictionary time = %fs", timer.ticks());
01115 
01116                 std::map<int, int> mapIndexIdNotIndexed;
01117                 std::vector<std::vector<cv::DMatch> > matchesNotIndexed;
01118                 if(_notIndexedWords.size())
01119                 {
01120                         cv::Mat dataNotIndexed = cv::Mat::zeros(_notIndexedWords.size(), query.cols, query.type());
01121                         unsigned int index = 0;
01122                         VisualWord * vw;
01123                         for(std::set<int>::iterator iter = _notIndexedWords.begin(); iter != _notIndexedWords.end(); ++iter, ++index)
01124                         {
01125                                 vw = _visualWords.at(*iter);
01126 
01127                                 cv::Mat descriptor;
01128                                 if(vw->getDescriptor().type() == CV_8U)
01129                                 {
01130                                         if(_strategy == kNNFlannKdTree || _strategy == kNNFlannNaive)
01131                                         {
01132                                                 vw->getDescriptor().convertTo(descriptor, CV_32F);
01133                                         }
01134                                         else
01135                                         {
01136                                                 descriptor = vw->getDescriptor();
01137                                         }
01138                                 }
01139                                 else
01140                                 {
01141                                         descriptor = vw->getDescriptor();
01142                                 }
01143 
01144                                 UASSERT(vw != 0 && descriptor.cols == query.cols && descriptor.type() == query.type());
01145                                 vw->getDescriptor().copyTo(dataNotIndexed.row(index));
01146                                 mapIndexIdNotIndexed.insert(mapIndexIdNotIndexed.end(), std::pair<int,int>(index, vw->id()));
01147                         }
01148 
01149                         // Find nearest neighbor
01150                         ULOGGER_DEBUG("Searching in words not indexed...");
01151                         cv::BFMatcher matcher(query.type()==CV_8U?cv::NORM_HAMMING:useDistanceL1_?cv::NORM_L1:cv::NORM_L2SQR);
01152                         matcher.knnMatch(query, dataNotIndexed, matchesNotIndexed, dataNotIndexed.rows>1?2:1);
01153                 }
01154                 ULOGGER_DEBUG("Search not yet indexed words time = %fs", timer.ticks());
01155 
01156                 for(int i=0; i<query.rows; ++i)
01157                 {
01158                         std::multimap<float, int> fullResults; // Contains results from the kd-tree search [and the naive search in new words]
01159                         if(!bruteForce && dists.cols)
01160                         {
01161                                 for(int j=0; j<dists.cols; ++j)
01162                                 {
01163                                         float d = dists.at<float>(i,j);
01164                                         int index;
01165 
01166                                         if (sizeof(size_t) == 8)
01167                                         {
01168                                                 index = *((size_t*)&results.at<double>(i, j));
01169                                         }
01170                                         else
01171                                         {
01172                                                 index = *((size_t*)&results.at<int>(i, j));
01173                                         }
01174                                         int id = uValue(_mapIndexId, index);
01175                                         if(d >= 0.0f && id != 0)
01176                                         {
01177                                                 fullResults.insert(std::pair<float, int>(d, id));
01178                                         }
01179                                 }
01180                         }
01181                         else if(bruteForce && matches.size())
01182                         {
01183                                 for(unsigned int j=0; j<matches.at(i).size(); ++j)
01184                                 {
01185                                         float d = matches.at(i).at(j).distance;
01186                                         int id = uValue(_mapIndexId, matches.at(i).at(j).trainIdx);
01187                                         if(d >= 0.0f && id != 0)
01188                                         {
01189                                                 fullResults.insert(std::pair<float, int>(d, id));
01190                                         }
01191                                 }
01192                         }
01193 
01194                         // not indexed..
01195                         if(matchesNotIndexed.size())
01196                         {
01197                                 for(unsigned int j=0; j<matchesNotIndexed.at(i).size(); ++j)
01198                                 {
01199                                         float d = matchesNotIndexed.at(i).at(j).distance;
01200                                         int id = uValue(mapIndexIdNotIndexed, matchesNotIndexed.at(i).at(j).trainIdx);
01201                                         if(d >= 0.0f && id != 0)
01202                                         {
01203                                                 fullResults.insert(std::pair<float, int>(d, id));
01204                                         }
01205                                         else
01206                                         {
01207                                                 break;
01208                                         }
01209                                 }
01210                         }
01211 
01212                         if(_incrementalDictionary)
01213                         {
01214                                 bool badDist = false;
01215                                 if(fullResults.size() == 0)
01216                                 {
01217                                         badDist = true;
01218                                 }
01219                                 if(!badDist)
01220                                 {
01221                                         if(fullResults.size() >= 2)
01222                                         {
01223                                                 // Apply NNDR
01224                                                 if(fullResults.begin()->first > _nndrRatio * (++fullResults.begin())->first)
01225                                                 {
01226                                                         badDist = true; // Rejected
01227                                                 }
01228                                         }
01229                                         else
01230                                         {
01231                                                 badDist = true; // Rejected
01232                                         }
01233                                 }
01234 
01235                                 if(!badDist)
01236                                 {
01237                                         resultIds[i] = fullResults.begin()->second; // Accepted
01238                                 }
01239                         }
01240                         else if(fullResults.size())
01241                         {
01242                                 //Just take the nearest if the dictionary is not incremental
01243                                 resultIds[i] = fullResults.begin()->second; // Accepted
01244                         }
01245                 }
01246                 ULOGGER_DEBUG("badDist check time = %fs", timer.ticks());
01247         }
01248         return resultIds;
01249 }
01250 
01251 void VWDictionary::addWord(VisualWord * vw)
01252 {
01253         if(vw)
01254         {
01255                 _visualWords.insert(std::pair<int, VisualWord *>(vw->id(), vw));
01256                 _notIndexedWords.insert(vw->id());
01257                 if(vw->getReferences().size())
01258                 {
01259                         _totalActiveReferences += uSum(uValues(vw->getReferences()));
01260                 }
01261                 else
01262                 {
01263                         _unusedWords.insert(std::pair<int, VisualWord *>(vw->id(), vw));
01264                 }
01265                 if(_lastWordId < vw->id())
01266                 {
01267                         _lastWordId = vw->id();
01268                 }
01269         }
01270 }
01271 
01272 const VisualWord * VWDictionary::getWord(int id) const
01273 {
01274         return uValue(_visualWords, id, (VisualWord *)0);
01275 }
01276 
01277 VisualWord * VWDictionary::getUnusedWord(int id) const
01278 {
01279         return uValue(_unusedWords, id, (VisualWord *)0);
01280 }
01281 
01282 std::vector<VisualWord*> VWDictionary::getUnusedWords() const
01283 {
01284         return uValues(_unusedWords);
01285 }
01286 
01287 std::vector<int> VWDictionary::getUnusedWordIds() const
01288 {
01289         return uKeys(_unusedWords);
01290 }
01291 
01292 void VWDictionary::removeWords(const std::vector<VisualWord*> & words)
01293 {
01294         UDEBUG("Removing %d words from dictionary (current size=%d)", (int)words.size(), (int)_visualWords.size());
01295         for(unsigned int i=0; i<words.size(); ++i)
01296         {
01297                 _visualWords.erase(words[i]->id());
01298                 _unusedWords.erase(words[i]->id());
01299                 if(_notIndexedWords.erase(words[i]->id()) == 0)
01300                 {
01301                         _removedIndexedWords.insert(words[i]->id());
01302                 }
01303         }
01304 }
01305 
01306 void VWDictionary::deleteUnusedWords()
01307 {
01308         std::vector<VisualWord*> unusedWords = uValues(_unusedWords);
01309         removeWords(unusedWords);
01310         for(unsigned int i=0; i<unusedWords.size(); ++i)
01311         {
01312                 delete unusedWords[i];
01313         }
01314 }
01315 
01316 void VWDictionary::exportDictionary(const char * fileNameReferences, const char * fileNameDescriptors) const
01317 {
01318         UDEBUG("");
01319         if(_visualWords.empty())
01320         {
01321                 UWARN("Dictionary is empty, cannot export it!");
01322                 return;
01323         }
01324         if(_visualWords.begin()->second->getDescriptor().type() != CV_32FC1)
01325         {
01326                 UERROR("Exporting binary descriptors is not implemented!");
01327                 return;
01328         }
01329     FILE* foutRef = 0;
01330     FILE* foutDesc = 0;
01331 #ifdef _MSC_VER
01332     fopen_s(&foutRef, fileNameReferences, "w");
01333     fopen_s(&foutDesc, fileNameDescriptors, "w");
01334 #else
01335     foutRef = fopen(fileNameReferences, "w");
01336     foutDesc = fopen(fileNameDescriptors, "w");
01337 #endif
01338 
01339     if(foutRef)
01340     {
01341         fprintf(foutRef, "WordID SignaturesID...\n");
01342     }
01343         if(foutDesc)
01344         {
01345                 if(_visualWords.begin() == _visualWords.end())
01346                 {
01347                         fprintf(foutDesc, "WordID Descriptors...\n");
01348                 }
01349                 else
01350                 {
01351                         UDEBUG("");
01352                         fprintf(foutDesc, "WordID Descriptors...%d\n", (*_visualWords.begin()).second->getDescriptor().cols);
01353                 }
01354         }
01355 
01356         UDEBUG("Export %d words...", _visualWords.size());
01357     for(std::map<int, VisualWord *>::const_iterator iter=_visualWords.begin(); iter!=_visualWords.end(); ++iter)
01358     {
01359         // References
01360         if(foutRef)
01361         {
01362                         fprintf(foutRef, "%d ", (*iter).first);
01363                         const std::map<int, int> ref = (*iter).second->getReferences();
01364                         for(std::map<int, int>::const_iterator jter=ref.begin(); jter!=ref.end(); ++jter)
01365                         {
01366                                 for(int i=0; i<(*jter).second; ++i)
01367                                 {
01368                                         fprintf(foutRef, "%d ", (*jter).first);
01369                                 }
01370                         }
01371                         fprintf(foutRef, "\n");
01372         }
01373 
01374         //Descriptors
01375         if(foutDesc)
01376         {
01377                         fprintf(foutDesc, "%d ", (*iter).first);
01378                         const float * desc = (const float *)(*iter).second->getDescriptor().data;
01379                         int dim = (*iter).second->getDescriptor().cols;
01380 
01381                         for(int i=0; i<dim; i++)
01382                         {
01383                                 fprintf(foutDesc, "%f ", desc[i]);
01384                         }
01385                         fprintf(foutDesc, "\n");
01386         }
01387     }
01388 
01389         if(foutRef)
01390                 fclose(foutRef);
01391         if(foutDesc)
01392                 fclose(foutDesc);
01393 }
01394 
01395 } // namespace rtabmap


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