VWDictionary.h
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 #pragma once
00029 
00030 #include "rtabmap/core/RtabmapExp.h" // DLL export/import defines
00031 
00032 #include <opencv2/highgui/highgui.hpp>
00033 #include <opencv2/core/core.hpp>
00034 #include <opencv2/features2d/features2d.hpp>
00035 #include <list>
00036 #include <set>
00037 #include "rtabmap/core/Parameters.h"
00038 
00039 namespace rtabmap
00040 {
00041 
00042 class DBDriver;
00043 class VisualWord;
00044 class FlannIndex;
00045 
00046 class RTABMAP_EXP VWDictionary
00047 {
00048 public:
00049         enum NNStrategy{
00050                 kNNFlannNaive,
00051                 kNNFlannKdTree,
00052                 kNNFlannLSH,
00053                 kNNBruteForce,
00054                 kNNBruteForceGPU,
00055                 kNNUndef};
00056         static const int ID_START;
00057         static const int ID_INVALID;
00058 
00059 public:
00060         VWDictionary(const ParametersMap & parameters = ParametersMap());
00061         virtual ~VWDictionary();
00062 
00063         virtual void parseParameters(const ParametersMap & parameters);
00064 
00065         virtual void update();
00066 
00067         virtual std::list<int> addNewWords(
00068                         const cv::Mat & descriptors,
00069                         int signatureId);
00070         virtual void addWord(VisualWord * vw);
00071 
00072         std::vector<int> findNN(const std::list<VisualWord *> & vws) const;
00073         std::vector<int> findNN(const cv::Mat & descriptors) const;
00074 
00075         void addWordRef(int wordId, int signatureId);
00076         void removeAllWordRef(int wordId, int signatureId);
00077         const VisualWord * getWord(int id) const;
00078         VisualWord * getUnusedWord(int id) const;
00079         void setLastWordId(int id) {_lastWordId = id;}
00080         const std::map<int, VisualWord *> & getVisualWords() const {return _visualWords;}
00081         float getNndrRatio() const {return _nndrRatio;}
00082         unsigned int getNotIndexedWordsCount() const {return (int)_notIndexedWords.size();}
00083         int getLastIndexedWordId() const;
00084         int getTotalActiveReferences() const {return _totalActiveReferences;}
00085         unsigned int getIndexedWordsCount() const;
00086         unsigned int getIndexMemoryUsed() const;
00087         void setNNStrategy(NNStrategy strategy);
00088         bool isIncremental() const {return _incrementalDictionary;}
00089         bool isIncrementalFlann() const {return _incrementalFlann;}
00090         void setIncrementalDictionary();
00091         void setFixedDictionary(const std::string & dictionaryPath);
00092 
00093         void exportDictionary(const char * fileNameReferences, const char * fileNameDescriptors) const;
00094 
00095         void clear(bool printWarningsIfNotEmpty = true);
00096         std::vector<VisualWord *> getUnusedWords() const;
00097         std::vector<int> getUnusedWordIds() const;
00098         unsigned int getUnusedWordsSize() const {return (int)_unusedWords.size();}
00099         void removeWords(const std::vector<VisualWord*> & words); // caller must delete the words
00100         void deleteUnusedWords();
00101 
00102 protected:
00103         int getNextId();
00104 
00105 protected:
00106         std::map<int, VisualWord *> _visualWords; //<id,VisualWord*>
00107         int _totalActiveReferences; // keep track of all references for updating the common signature
00108 
00109 private:
00110         bool _incrementalDictionary;
00111         bool _incrementalFlann;
00112         float _nndrRatio;
00113         std::string _dictionaryPath; // a pre-computed dictionary (.txt)
00114         bool _newWordsComparedTogether;
00115         int _lastWordId;
00116         bool useDistanceL1_;
00117         FlannIndex * _flannIndex;
00118         cv::Mat _dataTree;
00119         NNStrategy _strategy;
00120         std::map<int ,int> _mapIndexId;
00121         std::map<int ,int> _mapIdIndex;
00122         std::map<int, VisualWord*> _unusedWords; //<id,VisualWord*>, note that these words stay in _visualWords
00123         std::set<int> _notIndexedWords; // Words that are not indexed in the dictionary
00124         std::set<int> _removedIndexedWords; // Words not anymore in the dictionary but still indexed in the dictionary
00125 };
00126 
00127 } // namespace rtabmap


rtabmap
Author(s): Mathieu Labbe
autogenerated on Sat Jul 23 2016 11:44:28