├── voc ├── images │ ├── 0.png │ ├── 1.png │ ├── 2.png │ ├── 3.png │ ├── 4.png │ ├── 5.png │ ├── 6.png │ ├── 7.png │ ├── 8.png │ └── 9.png └── voc.cpp ├── src ├── DBoW2.cmake.in ├── QueryResults.cpp ├── FeatureVector.cpp ├── FBrief.cpp ├── FSurf64.cpp ├── BowVector.cpp ├── FORB.cpp └── ScoringObject.cpp ├── README.md ├── include └── DBoW2 │ ├── FeatureVector.h │ ├── FBrief.h │ ├── FClass.h │ ├── DBoW2.h │ ├── FSurf64.h │ ├── BowVector.h │ ├── FORB.h │ ├── ScoringObject.h │ ├── QueryResults.h │ ├── TemplatedDatabase.h │ └── TemplatedVocabulary.h ├── LICENSE.txt ├── CMakeLists.txt └── .gitignore /voc/images/0.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/itswcg/DBow/HEAD/voc/images/0.png -------------------------------------------------------------------------------- /voc/images/1.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/itswcg/DBow/HEAD/voc/images/1.png -------------------------------------------------------------------------------- /voc/images/2.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/itswcg/DBow/HEAD/voc/images/2.png -------------------------------------------------------------------------------- /voc/images/3.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/itswcg/DBow/HEAD/voc/images/3.png -------------------------------------------------------------------------------- /voc/images/4.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/itswcg/DBow/HEAD/voc/images/4.png -------------------------------------------------------------------------------- /voc/images/5.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/itswcg/DBow/HEAD/voc/images/5.png -------------------------------------------------------------------------------- /voc/images/6.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/itswcg/DBow/HEAD/voc/images/6.png -------------------------------------------------------------------------------- /voc/images/7.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/itswcg/DBow/HEAD/voc/images/7.png -------------------------------------------------------------------------------- /voc/images/8.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/itswcg/DBow/HEAD/voc/images/8.png -------------------------------------------------------------------------------- /voc/images/9.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/itswcg/DBow/HEAD/voc/images/9.png -------------------------------------------------------------------------------- /src/DBoW2.cmake.in: -------------------------------------------------------------------------------- 1 | FIND_LIBRARY(DBoW2_LIBRARY DBoW2 2 | PATHS @CMAKE_INSTALL_PREFIX@/lib 3 | ) 4 | FIND_PATH(DBoW2_INCLUDE_DIR DBoW2Config.cmake 5 | PATHS @CMAKE_INSTALL_PREFIX@/include/@PROJECT_NAME@ 6 | ) 7 | SET(DBoW2_LIBRARIES ${DBoW2_LIBRARY}) 8 | SET(DBoW2_LIBS ${DBoW2_LIBRARY}) 9 | SET(DBoW2_INCLUDE_DIRS ${DBoW2_INCLUDE_DIR}) -------------------------------------------------------------------------------- /README.md: -------------------------------------------------------------------------------- 1 | ## DBow2 2 | Fork 3 | 4 | #### 做了一些改动: 5 | * 创建离线词典(txt格式),能直接应用于ORB SLAM2 6 | * 能直接用的DBow3,在[DBow3](https://github.com/itswcg/DBow/tree/DBow3)分支 7 | * 详细说明: 8 | 9 | #### 使用 10 | ``` 11 | $ git clone git@github.com:itswcg/DBow.git 12 | $ mkdir build 13 | $ cd build 14 | $ cmake .. 15 | $ make 16 | $ ./voc 17 | ``` 18 | -------------------------------------------------------------------------------- /include/DBoW2/FeatureVector.h: -------------------------------------------------------------------------------- 1 | /** 2 | * File: FeatureVector.h 3 | * Date: November 2011 4 | * Author: Dorian Galvez-Lopez 5 | * Description: feature vector 6 | * License: see the LICENSE.txt file 7 | * 8 | */ 9 | 10 | #ifndef __D_T_FEATURE_VECTOR__ 11 | #define __D_T_FEATURE_VECTOR__ 12 | 13 | #include "BowVector.h" 14 | #include 15 | #include 16 | #include 17 | 18 | namespace DBoW2 { 19 | 20 | /// Vector of nodes with indexes of local features 21 | class FeatureVector: 22 | public std::map > 23 | { 24 | public: 25 | 26 | /** 27 | * Constructor 28 | */ 29 | FeatureVector(void); 30 | 31 | /** 32 | * Destructor 33 | */ 34 | ~FeatureVector(void); 35 | 36 | /** 37 | * Adds a feature to an existing node, or adds a new node with an initial 38 | * feature 39 | * @param id node id to add or to modify 40 | * @param i_feature index of feature to add to the given node 41 | */ 42 | void addFeature(NodeId id, unsigned int i_feature); 43 | 44 | /** 45 | * Sends a string versions of the feature vector through the stream 46 | * @param out stream 47 | * @param v feature vector 48 | */ 49 | friend std::ostream& operator<<(std::ostream &out, const FeatureVector &v); 50 | 51 | }; 52 | 53 | } // namespace DBoW2 54 | 55 | #endif 56 | 57 | -------------------------------------------------------------------------------- /src/QueryResults.cpp: -------------------------------------------------------------------------------- 1 | /** 2 | * File: QueryResults.cpp 3 | * Date: March, November 2011 4 | * Author: Dorian Galvez-Lopez 5 | * Description: structure to store results of database queries 6 | * License: see the LICENSE.txt file 7 | * 8 | */ 9 | 10 | #include 11 | #include 12 | #include "QueryResults.h" 13 | 14 | using namespace std; 15 | 16 | namespace DBoW2 17 | { 18 | 19 | // --------------------------------------------------------------------------- 20 | 21 | ostream & operator<<(ostream& os, const Result& ret ) 22 | { 23 | os << ""; 24 | return os; 25 | } 26 | 27 | // --------------------------------------------------------------------------- 28 | 29 | ostream & operator<<(ostream& os, const QueryResults& ret ) 30 | { 31 | if(ret.size() == 1) 32 | os << "1 result:" << endl; 33 | else 34 | os << ret.size() << " results:" << endl; 35 | 36 | QueryResults::const_iterator rit; 37 | for(rit = ret.begin(); rit != ret.end(); ++rit) 38 | { 39 | os << *rit; 40 | if(rit + 1 != ret.end()) os << endl; 41 | } 42 | return os; 43 | } 44 | 45 | // --------------------------------------------------------------------------- 46 | 47 | void QueryResults::saveM(const std::string &filename) const 48 | { 49 | fstream f(filename.c_str(), ios::out); 50 | 51 | QueryResults::const_iterator qit; 52 | for(qit = begin(); qit != end(); ++qit) 53 | { 54 | f << qit->Id << " " << qit->Score << endl; 55 | } 56 | 57 | f.close(); 58 | } 59 | 60 | // --------------------------------------------------------------------------- 61 | 62 | } // namespace DBoW2 63 | 64 | -------------------------------------------------------------------------------- /include/DBoW2/FBrief.h: -------------------------------------------------------------------------------- 1 | /** 2 | * File: FBrief.h 3 | * Date: November 2011 4 | * Author: Dorian Galvez-Lopez 5 | * Description: functions for BRIEF descriptors 6 | * License: see the LICENSE.txt file 7 | * 8 | */ 9 | 10 | #ifndef __D_T_F_BRIEF__ 11 | #define __D_T_F_BRIEF__ 12 | 13 | #include 14 | #include 15 | #include 16 | 17 | #include "FClass.h" 18 | #include 19 | 20 | namespace DBoW2 { 21 | 22 | /// Functions to manipulate BRIEF descriptors 23 | class FBrief: protected FClass 24 | { 25 | public: 26 | 27 | typedef DVision::BRIEF::bitset TDescriptor; 28 | typedef const TDescriptor *pDescriptor; 29 | 30 | /** 31 | * Calculates the mean value of a set of descriptors 32 | * @param descriptors 33 | * @param mean mean descriptor 34 | */ 35 | static void meanValue(const std::vector &descriptors, 36 | TDescriptor &mean); 37 | 38 | /** 39 | * Calculates the distance between two descriptors 40 | * @param a 41 | * @param b 42 | * @return distance 43 | */ 44 | static double distance(const TDescriptor &a, const TDescriptor &b); 45 | 46 | /** 47 | * Returns a string version of the descriptor 48 | * @param a descriptor 49 | * @return string version 50 | */ 51 | static std::string toString(const TDescriptor &a); 52 | 53 | /** 54 | * Returns a descriptor from a string 55 | * @param a descriptor 56 | * @param s string version 57 | */ 58 | static void fromString(TDescriptor &a, const std::string &s); 59 | 60 | /** 61 | * Returns a mat with the descriptors in float format 62 | * @param descriptors 63 | * @param mat (out) NxL 32F matrix 64 | */ 65 | static void toMat32F(const std::vector &descriptors, 66 | cv::Mat &mat); 67 | 68 | }; 69 | 70 | } // namespace DBoW2 71 | 72 | #endif 73 | 74 | -------------------------------------------------------------------------------- /include/DBoW2/FClass.h: -------------------------------------------------------------------------------- 1 | /** 2 | * File: FClass.h 3 | * Date: November 2011 4 | * Author: Dorian Galvez-Lopez 5 | * Description: generic FClass to instantiate templated classes 6 | * License: see the LICENSE.txt file 7 | * 8 | */ 9 | 10 | #ifndef __D_T_FCLASS__ 11 | #define __D_T_FCLASS__ 12 | 13 | #include 14 | #include 15 | #include 16 | 17 | namespace DBoW2 { 18 | 19 | /// Generic class to encapsulate functions to manage descriptors. 20 | /** 21 | * This class must be inherited. Derived classes can be used as the 22 | * parameter F when creating Templated structures 23 | * (TemplatedVocabulary, TemplatedDatabase, ...) 24 | */ 25 | class FClass 26 | { 27 | class TDescriptor; 28 | typedef const TDescriptor *pDescriptor; 29 | 30 | /** 31 | * Calculates the mean value of a set of descriptors 32 | * @param descriptors 33 | * @param mean mean descriptor 34 | */ 35 | virtual void meanValue(const std::vector &descriptors, 36 | TDescriptor &mean) = 0; 37 | 38 | /** 39 | * Calculates the distance between two descriptors 40 | * @param a 41 | * @param b 42 | * @return distance 43 | */ 44 | static double distance(const TDescriptor &a, const TDescriptor &b); 45 | 46 | /** 47 | * Returns a string version of the descriptor 48 | * @param a descriptor 49 | * @return string version 50 | */ 51 | static std::string toString(const TDescriptor &a); 52 | 53 | /** 54 | * Returns a descriptor from a string 55 | * @param a descriptor 56 | * @param s string version 57 | */ 58 | static void fromString(TDescriptor &a, const std::string &s); 59 | 60 | /** 61 | * Returns a mat with the descriptors in float format 62 | * @param descriptors 63 | * @param mat (out) NxL 32F matrix 64 | */ 65 | static void toMat32F(const std::vector &descriptors, 66 | cv::Mat &mat); 67 | }; 68 | 69 | } // namespace DBoW2 70 | 71 | #endif 72 | -------------------------------------------------------------------------------- /src/FeatureVector.cpp: -------------------------------------------------------------------------------- 1 | /** 2 | * File: FeatureVector.cpp 3 | * Date: November 2011 4 | * Author: Dorian Galvez-Lopez 5 | * Description: feature vector 6 | * License: see the LICENSE.txt file 7 | * 8 | */ 9 | 10 | #include "FeatureVector.h" 11 | #include 12 | #include 13 | #include 14 | 15 | namespace DBoW2 { 16 | 17 | // --------------------------------------------------------------------------- 18 | 19 | FeatureVector::FeatureVector(void) 20 | { 21 | } 22 | 23 | // --------------------------------------------------------------------------- 24 | 25 | FeatureVector::~FeatureVector(void) 26 | { 27 | } 28 | 29 | // --------------------------------------------------------------------------- 30 | 31 | void FeatureVector::addFeature(NodeId id, unsigned int i_feature) 32 | { 33 | FeatureVector::iterator vit = this->lower_bound(id); 34 | 35 | if(vit != this->end() && vit->first == id) 36 | { 37 | vit->second.push_back(i_feature); 38 | } 39 | else 40 | { 41 | vit = this->insert(vit, FeatureVector::value_type(id, 42 | std::vector() )); 43 | vit->second.push_back(i_feature); 44 | } 45 | } 46 | 47 | // --------------------------------------------------------------------------- 48 | 49 | std::ostream& operator<<(std::ostream &out, 50 | const FeatureVector &v) 51 | { 52 | if(!v.empty()) 53 | { 54 | FeatureVector::const_iterator vit = v.begin(); 55 | 56 | const std::vector* f = &vit->second; 57 | 58 | out << "<" << vit->first << ": ["; 59 | if(!f->empty()) out << (*f)[0]; 60 | for(unsigned int i = 1; i < f->size(); ++i) 61 | { 62 | out << ", " << (*f)[i]; 63 | } 64 | out << "]>"; 65 | 66 | for(++vit; vit != v.end(); ++vit) 67 | { 68 | f = &vit->second; 69 | 70 | out << ", <" << vit->first << ": ["; 71 | if(!f->empty()) out << (*f)[0]; 72 | for(unsigned int i = 1; i < f->size(); ++i) 73 | { 74 | out << ", " << (*f)[i]; 75 | } 76 | out << "]>"; 77 | } 78 | } 79 | 80 | return out; 81 | } 82 | 83 | // --------------------------------------------------------------------------- 84 | 85 | } // namespace DBoW2 86 | -------------------------------------------------------------------------------- /include/DBoW2/DBoW2.h: -------------------------------------------------------------------------------- 1 | /* 2 | * File: DBoW2.h 3 | * Date: November 2011 4 | * Author: Dorian Galvez-Lopez 5 | * Description: Generic include file for the DBoW2 classes and 6 | * the specialized vocabularies and databases 7 | * License: see the LICENSE.txt file 8 | * 9 | */ 10 | 11 | /*! \mainpage DBoW2 Library 12 | * 13 | * DBoW2 library for C++: 14 | * Bag-of-word image database for image retrieval. 15 | * 16 | * Written by Dorian Galvez-Lopez, 17 | * University of Zaragoza 18 | * 19 | * Check my website to obtain updates: http://doriangalvez.com 20 | * 21 | * \section requirements Requirements 22 | * This library requires the DUtils, DUtilsCV, DVision and OpenCV libraries, 23 | * as well as the boost::dynamic_bitset class. 24 | * 25 | * \section citation Citation 26 | * If you use this software in academic works, please cite: 27 |
28 |    @@ARTICLE{GalvezTRO12,
29 |     author={Galvez-Lopez, Dorian and Tardos, J. D.}, 
30 |     journal={IEEE Transactions on Robotics},
31 |     title={Bags of Binary Words for Fast Place Recognition in Image Sequences},
32 |     year={2012},
33 |     month={October},
34 |     volume={28},
35 |     number={5},
36 |     pages={1188--1197},
37 |     doi={10.1109/TRO.2012.2197158},
38 |     ISSN={1552-3098}
39 |   }
40 |  
41 | * 42 | */ 43 | 44 | #ifndef __D_T_DBOW2__ 45 | #define __D_T_DBOW2__ 46 | 47 | /// Includes all the data structures to manage vocabularies and image databases 48 | namespace DBoW2 49 | { 50 | } 51 | 52 | #include "TemplatedVocabulary.h" 53 | #include "TemplatedDatabase.h" 54 | #include "BowVector.h" 55 | #include "FeatureVector.h" 56 | #include "QueryResults.h" 57 | #include "FBrief.h" 58 | #include "FORB.h" 59 | 60 | /// ORB Vocabulary 61 | typedef DBoW2::TemplatedVocabulary 62 | OrbVocabulary; 63 | 64 | /// FORB Database 65 | typedef DBoW2::TemplatedDatabase 66 | OrbDatabase; 67 | 68 | /// BRIEF Vocabulary 69 | typedef DBoW2::TemplatedVocabulary 70 | BriefVocabulary; 71 | 72 | /// BRIEF Database 73 | typedef DBoW2::TemplatedDatabase 74 | BriefDatabase; 75 | 76 | #endif 77 | 78 | -------------------------------------------------------------------------------- /include/DBoW2/FSurf64.h: -------------------------------------------------------------------------------- 1 | /** 2 | * File: FSurf64.h 3 | * Date: November 2011 4 | * Author: Dorian Galvez-Lopez 5 | * Description: functions for Surf64 descriptors 6 | * License: see the LICENSE.txt file 7 | * 8 | */ 9 | 10 | #ifndef __D_T_F_SURF_64__ 11 | #define __D_T_F_SURF_64__ 12 | 13 | #include 14 | #include 15 | #include 16 | 17 | #include "FClass.h" 18 | 19 | namespace DBoW2 { 20 | 21 | /// Functions to manipulate SURF64 descriptors 22 | class FSurf64: protected FClass 23 | { 24 | public: 25 | 26 | /// Descriptor type 27 | typedef std::vector TDescriptor; 28 | /// Pointer to a single descriptor 29 | typedef const TDescriptor *pDescriptor; 30 | /// Descriptor length 31 | static const int L = 64; 32 | 33 | /** 34 | * Returns the number of dimensions of the descriptor space 35 | * @return dimensions 36 | */ 37 | inline static int dimensions() 38 | { 39 | return L; 40 | } 41 | 42 | /** 43 | * Calculates the mean value of a set of descriptors 44 | * @param descriptors vector of pointers to descriptors 45 | * @param mean mean descriptor 46 | */ 47 | static void meanValue(const std::vector &descriptors, 48 | TDescriptor &mean); 49 | 50 | /** 51 | * Calculates the (squared) distance between two descriptors 52 | * @param a 53 | * @param b 54 | * @return (squared) distance 55 | */ 56 | static double distance(const TDescriptor &a, const TDescriptor &b); 57 | 58 | /** 59 | * Returns a string version of the descriptor 60 | * @param a descriptor 61 | * @return string version 62 | */ 63 | static std::string toString(const TDescriptor &a); 64 | 65 | /** 66 | * Returns a descriptor from a string 67 | * @param a descriptor 68 | * @param s string version 69 | */ 70 | static void fromString(TDescriptor &a, const std::string &s); 71 | 72 | /** 73 | * Returns a mat with the descriptors in float format 74 | * @param descriptors 75 | * @param mat (out) NxL 32F matrix 76 | */ 77 | static void toMat32F(const std::vector &descriptors, 78 | cv::Mat &mat); 79 | 80 | }; 81 | 82 | } // namespace DBoW2 83 | 84 | #endif 85 | -------------------------------------------------------------------------------- /LICENSE.txt: -------------------------------------------------------------------------------- 1 | DBoW2: bag-of-words library for C++ with generic descriptors 2 | 3 | Copyright (c) 2015 Dorian Galvez-Lopez. http://doriangalvez.com 4 | All rights reserved. 5 | 6 | Redistribution and use in source and binary forms, with or without 7 | modification, are permitted provided that the following conditions 8 | are met: 9 | 1. Redistributions of source code must retain the above copyright 10 | notice, this list of conditions and the following disclaimer. 11 | 2. Redistributions in binary form must reproduce the above copyright 12 | notice, this list of conditions and the following disclaimer in the 13 | documentation and/or other materials provided with the distribution. 14 | 3. The original author of the work must be notified of any 15 | redistribution of source code or in binary form. 16 | 4. Neither the name of copyright holders nor the names of its 17 | contributors may be used to endorse or promote products derived 18 | from this software without specific prior written permission. 19 | 20 | THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 21 | ''AS IS'' AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED 22 | TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR 23 | PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL COPYRIGHT HOLDERS OR CONTRIBUTORS 24 | BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR 25 | CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 26 | SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 27 | INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 28 | CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 29 | ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 30 | POSSIBILITY OF SUCH DAMAGE. 31 | 32 | If you use it in an academic work, please cite: 33 | 34 | @ARTICLE{GalvezTRO12, 35 | author={G\'alvez-L\'opez, Dorian and Tard\'os, J. D.}, 36 | journal={IEEE Transactions on Robotics}, 37 | title={Bags of Binary Words for Fast Place Recognition in Image Sequences}, 38 | year={2012}, 39 | month={October}, 40 | volume={28}, 41 | number={5}, 42 | pages={1188--1197}, 43 | doi={10.1109/TRO.2012.2197158}, 44 | ISSN={1552-3098} 45 | } 46 | 47 | -------------------------------------------------------------------------------- /include/DBoW2/BowVector.h: -------------------------------------------------------------------------------- 1 | /** 2 | * File: BowVector.h 3 | * Date: March 2011 4 | * Author: Dorian Galvez-Lopez 5 | * Description: bag of words vector 6 | * License: see the LICENSE.txt file 7 | * 8 | */ 9 | 10 | #ifndef __D_T_BOW_VECTOR__ 11 | #define __D_T_BOW_VECTOR__ 12 | 13 | #include 14 | #include 15 | #include 16 | 17 | namespace DBoW2 { 18 | 19 | /// Id of words 20 | typedef unsigned int WordId; 21 | 22 | /// Value of a word 23 | typedef double WordValue; 24 | 25 | /// Id of nodes in the vocabulary treee 26 | typedef unsigned int NodeId; 27 | 28 | /// L-norms for normalization 29 | enum LNorm 30 | { 31 | L1, 32 | L2 33 | }; 34 | 35 | /// Weighting type 36 | enum WeightingType 37 | { 38 | TF_IDF, 39 | TF, 40 | IDF, 41 | BINARY 42 | }; 43 | 44 | /// Scoring type 45 | enum ScoringType 46 | { 47 | L1_NORM, 48 | L2_NORM, 49 | CHI_SQUARE, 50 | KL, 51 | BHATTACHARYYA, 52 | DOT_PRODUCT 53 | }; 54 | 55 | /// Vector of words to represent images 56 | class BowVector: 57 | public std::map 58 | { 59 | public: 60 | 61 | /** 62 | * Constructor 63 | */ 64 | BowVector(void); 65 | 66 | /** 67 | * Destructor 68 | */ 69 | ~BowVector(void); 70 | 71 | /** 72 | * Adds a value to a word value existing in the vector, or creates a new 73 | * word with the given value 74 | * @param id word id to look for 75 | * @param v value to create the word with, or to add to existing word 76 | */ 77 | void addWeight(WordId id, WordValue v); 78 | 79 | /** 80 | * Adds a word with a value to the vector only if this does not exist yet 81 | * @param id word id to look for 82 | * @param v value to give to the word if this does not exist 83 | */ 84 | void addIfNotExist(WordId id, WordValue v); 85 | 86 | /** 87 | * L1-Normalizes the values in the vector 88 | * @param norm_type norm used 89 | */ 90 | void normalize(LNorm norm_type); 91 | 92 | /** 93 | * Prints the content of the bow vector 94 | * @param out stream 95 | * @param v 96 | */ 97 | friend std::ostream& operator<<(std::ostream &out, const BowVector &v); 98 | 99 | /** 100 | * Saves the bow vector as a vector in a matlab file 101 | * @param filename 102 | * @param W number of words in the vocabulary 103 | */ 104 | void saveM(const std::string &filename, size_t W) const; 105 | }; 106 | 107 | } // namespace DBoW2 108 | 109 | #endif 110 | -------------------------------------------------------------------------------- /include/DBoW2/FORB.h: -------------------------------------------------------------------------------- 1 | /** 2 | * File: FORB.h 3 | * Date: June 2012 4 | * Author: Dorian Galvez-Lopez 5 | * Description: functions for ORB descriptors 6 | * License: see the LICENSE.txt file 7 | * 8 | */ 9 | 10 | #ifndef __D_T_F_ORB__ 11 | #define __D_T_F_ORB__ 12 | 13 | #include 14 | #include 15 | #include 16 | 17 | #include "FClass.h" 18 | 19 | namespace DBoW2 { 20 | 21 | /// Functions to manipulate BRIEF descriptors 22 | class FORB: protected FClass 23 | { 24 | public: 25 | 26 | /// Descriptor type 27 | typedef cv::Mat TDescriptor; // CV_8U 28 | /// Pointer to a single descriptor 29 | typedef const TDescriptor *pDescriptor; 30 | /// Descriptor length (in bytes) 31 | static const int L = 32; 32 | 33 | /** 34 | * Calculates the mean value of a set of descriptors 35 | * @param descriptors 36 | * @param mean mean descriptor 37 | */ 38 | static void meanValue(const std::vector &descriptors, 39 | TDescriptor &mean); 40 | 41 | /** 42 | * Calculates the distance between two descriptors 43 | * @param a 44 | * @param b 45 | * @return distance 46 | */ 47 | static double distance(const TDescriptor &a, const TDescriptor &b); 48 | 49 | /** 50 | * Returns a string version of the descriptor 51 | * @param a descriptor 52 | * @return string version 53 | */ 54 | static std::string toString(const TDescriptor &a); 55 | 56 | /** 57 | * Returns a descriptor from a string 58 | * @param a descriptor 59 | * @param s string version 60 | */ 61 | static void fromString(TDescriptor &a, const std::string &s); 62 | 63 | /** 64 | * Returns a mat with the descriptors in float format 65 | * @param descriptors 66 | * @param mat (out) NxL 32F matrix 67 | */ 68 | static void toMat32F(const std::vector &descriptors, 69 | cv::Mat &mat); 70 | 71 | /** 72 | * Returns a mat with the descriptors in float format 73 | * @param descriptors NxL CV_8U matrix 74 | * @param mat (out) NxL 32F matrix 75 | */ 76 | static void toMat32F(const cv::Mat &descriptors, cv::Mat &mat); 77 | 78 | /** 79 | * Returns a matrix with the descriptor in OpenCV format 80 | * @param descriptors vector of N row descriptors 81 | * @param mat (out) NxL CV_8U matrix 82 | */ 83 | static void toMat8U(const std::vector &descriptors, 84 | cv::Mat &mat); 85 | 86 | }; 87 | 88 | } // namespace DBoW2 89 | 90 | #endif 91 | 92 | -------------------------------------------------------------------------------- /include/DBoW2/ScoringObject.h: -------------------------------------------------------------------------------- 1 | /** 2 | * File: ScoringObject.h 3 | * Date: November 2011 4 | * Author: Dorian Galvez-Lopez 5 | * Description: functions to compute bow scores 6 | * License: see the LICENSE.txt file 7 | * 8 | */ 9 | 10 | #ifndef __D_T_SCORING_OBJECT__ 11 | #define __D_T_SCORING_OBJECT__ 12 | 13 | #include "BowVector.h" 14 | 15 | namespace DBoW2 { 16 | 17 | /// Base class of scoring functions 18 | class GeneralScoring 19 | { 20 | public: 21 | /** 22 | * Computes the score between two vectors. Vectors must be sorted and 23 | * normalized if necessary 24 | * @param v (in/out) 25 | * @param w (in/out) 26 | * @return score 27 | */ 28 | virtual double score(const BowVector &v, const BowVector &w) const = 0; 29 | 30 | /** 31 | * Returns whether a vector must be normalized before scoring according 32 | * to the scoring scheme 33 | * @param norm norm to use 34 | * @return true iff must normalize 35 | */ 36 | virtual bool mustNormalize(LNorm &norm) const = 0; 37 | 38 | /// Log of epsilon 39 | static const double LOG_EPS; 40 | // If you change the type of WordValue, make sure you change also the 41 | // epsilon value (this is needed by the KL method) 42 | 43 | virtual ~GeneralScoring() {} //!< Required for virtual base classes 44 | }; 45 | 46 | /** 47 | * Macro for defining Scoring classes 48 | * @param NAME name of class 49 | * @param MUSTNORMALIZE if vectors must be normalized to compute the score 50 | * @param NORM type of norm to use when MUSTNORMALIZE 51 | */ 52 | #define __SCORING_CLASS(NAME, MUSTNORMALIZE, NORM) \ 53 | NAME: public GeneralScoring \ 54 | { public: \ 55 | /** \ 56 | * Computes score between two vectors \ 57 | * @param v \ 58 | * @param w \ 59 | * @return score between v and w \ 60 | */ \ 61 | virtual double score(const BowVector &v, const BowVector &w) const; \ 62 | \ 63 | /** \ 64 | * Says if a vector must be normalized according to the scoring function \ 65 | * @param norm (out) if true, norm to use 66 | * @return true iff vectors must be normalized \ 67 | */ \ 68 | virtual inline bool mustNormalize(LNorm &norm) const \ 69 | { norm = NORM; return MUSTNORMALIZE; } \ 70 | } 71 | 72 | /// L1 Scoring object 73 | class __SCORING_CLASS(L1Scoring, true, L1); 74 | 75 | /// L2 Scoring object 76 | class __SCORING_CLASS(L2Scoring, true, L2); 77 | 78 | /// Chi square Scoring object 79 | class __SCORING_CLASS(ChiSquareScoring, true, L1); 80 | 81 | /// KL divergence Scoring object 82 | class __SCORING_CLASS(KLScoring, true, L1); 83 | 84 | /// Bhattacharyya Scoring object 85 | class __SCORING_CLASS(BhattacharyyaScoring, true, L1); 86 | 87 | /// Dot product Scoring object 88 | class __SCORING_CLASS(DotProductScoring, false, L1); 89 | 90 | #undef __SCORING_CLASS 91 | 92 | } // namespace DBoW2 93 | 94 | #endif 95 | 96 | -------------------------------------------------------------------------------- /src/FBrief.cpp: -------------------------------------------------------------------------------- 1 | /** 2 | * File: FBrief.cpp 3 | * Date: November 2011 4 | * Author: Dorian Galvez-Lopez 5 | * Description: functions for BRIEF descriptors 6 | * License: see the LICENSE.txt file 7 | * 8 | */ 9 | 10 | #include 11 | #include 12 | #include 13 | 14 | #include 15 | #include "FBrief.h" 16 | 17 | using namespace std; 18 | 19 | namespace DBoW2 { 20 | 21 | // -------------------------------------------------------------------------- 22 | 23 | void FBrief::meanValue(const std::vector &descriptors, 24 | FBrief::TDescriptor &mean) 25 | { 26 | mean.reset(); 27 | 28 | if(descriptors.empty()) return; 29 | 30 | const int N2 = descriptors.size() / 2; 31 | const int L = descriptors[0]->size(); 32 | 33 | vector counters(L, 0); 34 | 35 | vector::const_iterator it; 36 | for(it = descriptors.begin(); it != descriptors.end(); ++it) 37 | { 38 | const FBrief::TDescriptor &desc = **it; 39 | for(int i = 0; i < L; ++i) 40 | { 41 | if(desc[i]) counters[i]++; 42 | } 43 | } 44 | 45 | for(int i = 0; i < L; ++i) 46 | { 47 | if(counters[i] > N2) mean.set(i); 48 | } 49 | 50 | } 51 | 52 | // -------------------------------------------------------------------------- 53 | 54 | double FBrief::distance(const FBrief::TDescriptor &a, 55 | const FBrief::TDescriptor &b) 56 | { 57 | return (double)DVision::BRIEF::distance(a, b); 58 | } 59 | 60 | // -------------------------------------------------------------------------- 61 | 62 | std::string FBrief::toString(const FBrief::TDescriptor &a) 63 | { 64 | // from boost::bitset 65 | string s; 66 | to_string(a, s); // reversed 67 | return s; 68 | } 69 | 70 | // -------------------------------------------------------------------------- 71 | 72 | void FBrief::fromString(FBrief::TDescriptor &a, const std::string &s) 73 | { 74 | // from boost::bitset 75 | stringstream ss(s); 76 | ss >> a; 77 | } 78 | 79 | // -------------------------------------------------------------------------- 80 | 81 | void FBrief::toMat32F(const std::vector &descriptors, 82 | cv::Mat &mat) 83 | { 84 | if(descriptors.empty()) 85 | { 86 | mat.release(); 87 | return; 88 | } 89 | 90 | const int N = descriptors.size(); 91 | const int L = descriptors[0].size(); 92 | 93 | mat.create(N, L, CV_32F); 94 | 95 | for(int i = 0; i < N; ++i) 96 | { 97 | const TDescriptor& desc = descriptors[i]; 98 | float *p = mat.ptr(i); 99 | for(int j = 0; j < L; ++j, ++p) 100 | { 101 | *p = (desc[j] ? 1 : 0); 102 | } 103 | } 104 | } 105 | 106 | // -------------------------------------------------------------------------- 107 | 108 | } // namespace DBoW2 109 | 110 | -------------------------------------------------------------------------------- /src/FSurf64.cpp: -------------------------------------------------------------------------------- 1 | /** 2 | * File: FSurf64.cpp 3 | * Date: November 2011 4 | * Author: Dorian Galvez-Lopez 5 | * Description: functions for Surf64 descriptors 6 | * License: see the LICENSE.txt file 7 | * 8 | */ 9 | 10 | #include 11 | #include 12 | #include 13 | 14 | #include "FClass.h" 15 | #include "FSurf64.h" 16 | 17 | using namespace std; 18 | 19 | namespace DBoW2 { 20 | 21 | // -------------------------------------------------------------------------- 22 | 23 | void FSurf64::meanValue(const std::vector &descriptors, 24 | FSurf64::TDescriptor &mean) 25 | { 26 | mean.resize(0); 27 | mean.resize(FSurf64::L, 0); 28 | 29 | float s = descriptors.size(); 30 | 31 | vector::const_iterator it; 32 | for(it = descriptors.begin(); it != descriptors.end(); ++it) 33 | { 34 | const FSurf64::TDescriptor &desc = **it; 35 | for(int i = 0; i < FSurf64::L; i += 4) 36 | { 37 | mean[i ] += desc[i ] / s; 38 | mean[i+1] += desc[i+1] / s; 39 | mean[i+2] += desc[i+2] / s; 40 | mean[i+3] += desc[i+3] / s; 41 | } 42 | } 43 | } 44 | 45 | // -------------------------------------------------------------------------- 46 | 47 | double FSurf64::distance(const FSurf64::TDescriptor &a, const FSurf64::TDescriptor &b) 48 | { 49 | double sqd = 0.; 50 | for(int i = 0; i < FSurf64::L; i += 4) 51 | { 52 | sqd += (a[i ] - b[i ])*(a[i ] - b[i ]); 53 | sqd += (a[i+1] - b[i+1])*(a[i+1] - b[i+1]); 54 | sqd += (a[i+2] - b[i+2])*(a[i+2] - b[i+2]); 55 | sqd += (a[i+3] - b[i+3])*(a[i+3] - b[i+3]); 56 | } 57 | return sqd; 58 | } 59 | 60 | // -------------------------------------------------------------------------- 61 | 62 | std::string FSurf64::toString(const FSurf64::TDescriptor &a) 63 | { 64 | stringstream ss; 65 | for(int i = 0; i < FSurf64::L; ++i) 66 | { 67 | ss << a[i] << " "; 68 | } 69 | return ss.str(); 70 | } 71 | 72 | // -------------------------------------------------------------------------- 73 | 74 | void FSurf64::fromString(FSurf64::TDescriptor &a, const std::string &s) 75 | { 76 | a.resize(FSurf64::L); 77 | 78 | stringstream ss(s); 79 | for(int i = 0; i < FSurf64::L; ++i) 80 | { 81 | ss >> a[i]; 82 | } 83 | } 84 | 85 | // -------------------------------------------------------------------------- 86 | 87 | void FSurf64::toMat32F(const std::vector &descriptors, 88 | cv::Mat &mat) 89 | { 90 | if(descriptors.empty()) 91 | { 92 | mat.release(); 93 | return; 94 | } 95 | 96 | const int N = descriptors.size(); 97 | const int L = FSurf64::L; 98 | 99 | mat.create(N, L, CV_32F); 100 | 101 | for(int i = 0; i < N; ++i) 102 | { 103 | const TDescriptor& desc = descriptors[i]; 104 | float *p = mat.ptr(i); 105 | for(int j = 0; j < L; ++j, ++p) 106 | { 107 | *p = desc[j]; 108 | } 109 | } 110 | } 111 | 112 | // -------------------------------------------------------------------------- 113 | 114 | } // namespace DBoW2 115 | 116 | -------------------------------------------------------------------------------- /src/BowVector.cpp: -------------------------------------------------------------------------------- 1 | /** 2 | * File: BowVector.cpp 3 | * Date: March 2011 4 | * Author: Dorian Galvez-Lopez 5 | * Description: bag of words vector 6 | * License: see the LICENSE.txt file 7 | * 8 | */ 9 | 10 | #include 11 | #include 12 | #include 13 | #include 14 | #include 15 | 16 | #include "BowVector.h" 17 | 18 | namespace DBoW2 { 19 | 20 | // -------------------------------------------------------------------------- 21 | 22 | BowVector::BowVector(void) 23 | { 24 | } 25 | 26 | // -------------------------------------------------------------------------- 27 | 28 | BowVector::~BowVector(void) 29 | { 30 | } 31 | 32 | // -------------------------------------------------------------------------- 33 | 34 | void BowVector::addWeight(WordId id, WordValue v) 35 | { 36 | BowVector::iterator vit = this->lower_bound(id); 37 | 38 | if(vit != this->end() && !(this->key_comp()(id, vit->first))) 39 | { 40 | vit->second += v; 41 | } 42 | else 43 | { 44 | this->insert(vit, BowVector::value_type(id, v)); 45 | } 46 | } 47 | 48 | // -------------------------------------------------------------------------- 49 | 50 | void BowVector::addIfNotExist(WordId id, WordValue v) 51 | { 52 | BowVector::iterator vit = this->lower_bound(id); 53 | 54 | if(vit == this->end() || (this->key_comp()(id, vit->first))) 55 | { 56 | this->insert(vit, BowVector::value_type(id, v)); 57 | } 58 | } 59 | 60 | // -------------------------------------------------------------------------- 61 | 62 | void BowVector::normalize(LNorm norm_type) 63 | { 64 | double norm = 0.0; 65 | BowVector::iterator it; 66 | 67 | if(norm_type == DBoW2::L1) 68 | { 69 | for(it = begin(); it != end(); ++it) 70 | norm += fabs(it->second); 71 | } 72 | else 73 | { 74 | for(it = begin(); it != end(); ++it) 75 | norm += it->second * it->second; 76 | norm = sqrt(norm); 77 | } 78 | 79 | if(norm > 0.0) 80 | { 81 | for(it = begin(); it != end(); ++it) 82 | it->second /= norm; 83 | } 84 | } 85 | 86 | // -------------------------------------------------------------------------- 87 | 88 | std::ostream& operator<< (std::ostream &out, const BowVector &v) 89 | { 90 | BowVector::const_iterator vit; 91 | std::vector::const_iterator iit; 92 | unsigned int i = 0; 93 | const unsigned int N = v.size(); 94 | for(vit = v.begin(); vit != v.end(); ++vit, ++i) 95 | { 96 | out << "<" << vit->first << ", " << vit->second << ">"; 97 | 98 | if(i < N-1) out << ", "; 99 | } 100 | return out; 101 | } 102 | 103 | // -------------------------------------------------------------------------- 104 | 105 | void BowVector::saveM(const std::string &filename, size_t W) const 106 | { 107 | std::fstream f(filename.c_str(), std::ios::out); 108 | 109 | WordId last = 0; 110 | BowVector::const_iterator bit; 111 | for(bit = this->begin(); bit != this->end(); ++bit) 112 | { 113 | for(; last < bit->first; ++last) 114 | { 115 | f << "0 "; 116 | } 117 | f << bit->second << " "; 118 | 119 | last = bit->first + 1; 120 | } 121 | for(; last < (WordId)W; ++last) 122 | f << "0 "; 123 | 124 | f.close(); 125 | } 126 | 127 | // -------------------------------------------------------------------------- 128 | 129 | } // namespace DBoW2 130 | 131 | -------------------------------------------------------------------------------- /CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 2.8) 2 | project(DBoW2) 3 | include(ExternalProject) 4 | 5 | option(BUILD_DBoW2 "Build DBoW2" ON) 6 | option(BUILD_voc "Build voc application" ON) 7 | 8 | if(NOT CMAKE_BUILD_TYPE AND NOT CMAKE_CONFIGURATION_TYPES) 9 | set(CMAKE_BUILD_TYPE Release CACHE STRING "Choose the type of build." FORCE) 10 | set_property(CACHE CMAKE_BUILD_TYPE PROPERTY STRINGS "Debug" "Release" 11 | "MinSizeRel" "RelWithDebInfo") 12 | endif() 13 | 14 | if(MSVC) 15 | if(CMAKE_CXX_FLAGS MATCHES "/W[0-4]") 16 | string(REGEX REPLACE "/W[0-4]" "/W4" CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS}") 17 | else() 18 | set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} /W4") 19 | endif() 20 | elseif(CMAKE_COMPILER_IS_GNUCC OR CMAKE_COMPILER_IS_GNUCXX) 21 | set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -Wall -pedantic") 22 | endif() 23 | 24 | set(HDRS 25 | include/DBoW2/BowVector.h include/DBoW2/FBrief.h 26 | include/DBoW2/QueryResults.h include/DBoW2/TemplatedDatabase.h include/DBoW2/FORB.h 27 | include/DBoW2/DBoW2.h include/DBoW2/FClass.h include/DBoW2/FeatureVector.h 28 | include/DBoW2/ScoringObject.h include/DBoW2/TemplatedVocabulary.h) 29 | set(SRCS 30 | src/BowVector.cpp src/FBrief.cpp src/FORB.cpp 31 | src/FeatureVector.cpp src/QueryResults.cpp src/ScoringObject.cpp) 32 | 33 | set(DEPENDENCY_DIR ${CMAKE_CURRENT_BINARY_DIR}/dependencies) 34 | set(DEPENDENCY_INSTALL_DIR ${DEPENDENCY_DIR}/install) 35 | 36 | find_package(OpenCV REQUIRED) 37 | include_directories(${OpenCV_INCLUDE_DIRS}) 38 | 39 | find_package(Boost REQUIRED) 40 | include_directories(${Boost_INCLUDE_DIR}) 41 | 42 | find_package(DLib QUIET 43 | PATHS ${DEPENDENCY_INSTALL_DIR}) 44 | if(${DLib_FOUND}) 45 | message("DLib library found, using it from the system") 46 | include_directories(${DLib_INCLUDE_DIRS}) 47 | add_custom_target(Dependencies) 48 | else(${DLib_FOUND}) 49 | message("DLib library not found in the system, it will be downloaded on build") 50 | option(DOWNLOAD_DLib_dependency "Download DLib dependency" ON) 51 | if(${DOWNLOAD_DLib_dependency}) 52 | ExternalProject_Add(DLib 53 | PREFIX ${DEPENDENCY_DIR} 54 | GIT_REPOSITORY http://github.com/dorian3d/DLib 55 | GIT_TAG master 56 | INSTALL_DIR ${DEPENDENCY_INSTALL_DIR} 57 | CMAKE_ARGS -DCMAKE_INSTALL_PREFIX=) 58 | add_custom_target(Dependencies ${CMAKE_COMMAND} ${CMAKE_SOURCE_DIR} DEPENDS DLib) 59 | else() 60 | message(SEND_ERROR "Please, activate DOWNLOAD_DLib_dependency option or download manually") 61 | endif(${DOWNLOAD_DLib_dependency}) 62 | endif(${DLib_FOUND}) 63 | 64 | if(BUILD_DBoW2) 65 | add_library(${PROJECT_NAME} SHARED ${SRCS}) 66 | include_directories(include/DBoW2/) 67 | add_dependencies(${PROJECT_NAME} Dependencies) 68 | target_link_libraries(${PROJECT_NAME} ${OpenCV_LIBS} ${DLib_LIBS}) 69 | endif(BUILD_DBoW2) 70 | 71 | if(BUILD_voc) 72 | add_executable(voc voc/voc.cpp) 73 | target_link_libraries(voc ${PROJECT_NAME} ${OpenCV_LIBS} ${DLib_LIBS}) 74 | file(COPY voc/images DESTINATION ${CMAKE_BINARY_DIR}/) 75 | endif(BUILD_voc) 76 | 77 | configure_file(src/DBoW2.cmake.in 78 | "${PROJECT_BINARY_DIR}/DBoW2Config.cmake" @ONLY) 79 | 80 | install(TARGETS ${PROJECT_NAME} DESTINATION ${CMAKE_INSTALL_PREFIX}/lib) 81 | if(BUILD_DBoW2) 82 | install(DIRECTORY include/DBoW2 DESTINATION ${CMAKE_INSTALL_PREFIX}/include) 83 | endif() 84 | install(FILES "${CMAKE_CURRENT_BINARY_DIR}/DBoW2Config.cmake" 85 | DESTINATION ${CMAKE_INSTALL_PREFIX}/include/${PROJECT_NAME}) 86 | install(FILES "${PROJECT_BINARY_DIR}/DBoW2Config.cmake" 87 | DESTINATION ${CMAKE_INSTALL_PREFIX}/lib/cmake/DBoW2/) 88 | install(DIRECTORY ${DEPENDENCY_INSTALL_DIR}/ DESTINATION ${CMAKE_INSTALL_PREFIX} OPTIONAL) 89 | -------------------------------------------------------------------------------- /include/DBoW2/QueryResults.h: -------------------------------------------------------------------------------- 1 | /** 2 | * File: QueryResults.h 3 | * Date: March, November 2011 4 | * Author: Dorian Galvez-Lopez 5 | * Description: structure to store results of database queries 6 | * License: see the LICENSE.txt file 7 | * 8 | */ 9 | 10 | #ifndef __D_T_QUERY_RESULTS__ 11 | #define __D_T_QUERY_RESULTS__ 12 | 13 | #include 14 | 15 | namespace DBoW2 { 16 | 17 | /// Id of entries of the database 18 | typedef unsigned int EntryId; 19 | 20 | /// Single result of a query 21 | class Result 22 | { 23 | public: 24 | 25 | /// Entry id 26 | EntryId Id; 27 | 28 | /// Score obtained 29 | double Score; 30 | 31 | /// debug 32 | int nWords; // words in common 33 | // !!! this is filled only by Bhatt score! 34 | // (and for BCMatching, BCThresholding then) 35 | 36 | double bhatScore, chiScore; 37 | /// debug 38 | 39 | // only done by ChiSq and BCThresholding 40 | double sumCommonVi; 41 | double sumCommonWi; 42 | double expectedChiScore; 43 | /// debug 44 | 45 | /** 46 | * Empty constructors 47 | */ 48 | inline Result(){} 49 | 50 | /** 51 | * Creates a result with the given data 52 | * @param _id entry id 53 | * @param _score score 54 | */ 55 | inline Result(EntryId _id, double _score): Id(_id), Score(_score){} 56 | 57 | /** 58 | * Compares the scores of two results 59 | * @return true iff this.score < r.score 60 | */ 61 | inline bool operator<(const Result &r) const 62 | { 63 | return this->Score < r.Score; 64 | } 65 | 66 | /** 67 | * Compares the scores of two results 68 | * @return true iff this.score > r.score 69 | */ 70 | inline bool operator>(const Result &r) const 71 | { 72 | return this->Score > r.Score; 73 | } 74 | 75 | /** 76 | * Compares the entry id of the result 77 | * @return true iff this.id == id 78 | */ 79 | inline bool operator==(EntryId id) const 80 | { 81 | return this->Id == id; 82 | } 83 | 84 | /** 85 | * Compares the score of this entry with a given one 86 | * @param s score to compare with 87 | * @return true iff this score < s 88 | */ 89 | inline bool operator<(double s) const 90 | { 91 | return this->Score < s; 92 | } 93 | 94 | /** 95 | * Compares the score of this entry with a given one 96 | * @param s score to compare with 97 | * @return true iff this score > s 98 | */ 99 | inline bool operator>(double s) const 100 | { 101 | return this->Score > s; 102 | } 103 | 104 | /** 105 | * Compares the score of two results 106 | * @param a 107 | * @param b 108 | * @return true iff a.Score > b.Score 109 | */ 110 | static inline bool gt(const Result &a, const Result &b) 111 | { 112 | return a.Score > b.Score; 113 | } 114 | 115 | /** 116 | * Compares the scores of two results 117 | * @return true iff a.Score > b.Score 118 | */ 119 | inline static bool ge(const Result &a, const Result &b) 120 | { 121 | return a.Score > b.Score; 122 | } 123 | 124 | /** 125 | * Returns true iff a.Score >= b.Score 126 | * @param a 127 | * @param b 128 | * @return true iff a.Score >= b.Score 129 | */ 130 | static inline bool geq(const Result &a, const Result &b) 131 | { 132 | return a.Score >= b.Score; 133 | } 134 | 135 | /** 136 | * Returns true iff a.Score >= s 137 | * @param a 138 | * @param s 139 | * @return true iff a.Score >= s 140 | */ 141 | static inline bool geqv(const Result &a, double s) 142 | { 143 | return a.Score >= s; 144 | } 145 | 146 | 147 | /** 148 | * Returns true iff a.Id < b.Id 149 | * @param a 150 | * @param b 151 | * @return true iff a.Id < b.Id 152 | */ 153 | static inline bool ltId(const Result &a, const Result &b) 154 | { 155 | return a.Id < b.Id; 156 | } 157 | 158 | /** 159 | * Prints a string version of the result 160 | * @param os ostream 161 | * @param ret Result to print 162 | */ 163 | friend std::ostream & operator<<(std::ostream& os, const Result& ret ); 164 | }; 165 | 166 | /// Multiple results from a query 167 | class QueryResults: public std::vector 168 | { 169 | public: 170 | 171 | /** 172 | * Multiplies all the scores in the vector by factor 173 | * @param factor 174 | */ 175 | inline void scaleScores(double factor); 176 | 177 | /** 178 | * Prints a string version of the results 179 | * @param os ostream 180 | * @param ret QueryResults to print 181 | */ 182 | friend std::ostream & operator<<(std::ostream& os, const QueryResults& ret ); 183 | 184 | /** 185 | * Saves a matlab file with the results 186 | * @param filename 187 | */ 188 | void saveM(const std::string &filename) const; 189 | 190 | }; 191 | 192 | // -------------------------------------------------------------------------- 193 | 194 | inline void QueryResults::scaleScores(double factor) 195 | { 196 | for(QueryResults::iterator qit = begin(); qit != end(); ++qit) 197 | qit->Score *= factor; 198 | } 199 | 200 | // -------------------------------------------------------------------------- 201 | 202 | } // namespace TemplatedBoW 203 | 204 | #endif 205 | 206 | -------------------------------------------------------------------------------- /.gitignore: -------------------------------------------------------------------------------- 1 | ## Ignore Visual Studio temporary files, build results, and 2 | ## files generated by popular Visual Studio add-ons. 3 | 4 | # User-specific files 5 | *.suo 6 | *.user 7 | *.userosscache 8 | *.sln.docstates 9 | 10 | # User-specific files (MonoDevelop/Xamarin Studio) 11 | *.userprefs 12 | 13 | # Build results 14 | [Dd]ebug/ 15 | [Dd]ebugPublic/ 16 | [Rr]elease/ 17 | [Rr]eleases/ 18 | [Xx]64/ 19 | [Xx]86/ 20 | [Bb]uild/ 21 | bld/ 22 | [Bb]in/ 23 | [Oo]bj/ 24 | 25 | # Visual Studio 2015 cache/options directory 26 | .vs/ 27 | # Uncomment if you have tasks that create the project's static files in wwwroot 28 | #wwwroot/ 29 | 30 | # MSTest test Results 31 | [Tt]est[Rr]esult*/ 32 | [Bb]uild[Ll]og.* 33 | 34 | # NUNIT 35 | *.VisualState.xml 36 | TestResult.xml 37 | 38 | # Build Results of an ATL Project 39 | [Dd]ebugPS/ 40 | [Rr]eleasePS/ 41 | dlldata.c 42 | 43 | # DNX 44 | project.lock.json 45 | artifacts/ 46 | 47 | *_i.c 48 | *_p.c 49 | *_i.h 50 | *.ilk 51 | *.meta 52 | *.obj 53 | *.pch 54 | *.pdb 55 | *.pgc 56 | *.pgd 57 | *.rsp 58 | *.sbr 59 | *.tlb 60 | *.tli 61 | *.tlh 62 | *.tmp 63 | *.tmp_proj 64 | *.log 65 | *.vspscc 66 | *.vssscc 67 | .builds 68 | *.pidb 69 | *.svclog 70 | *.scc 71 | 72 | # Chutzpah Test files 73 | _Chutzpah* 74 | 75 | # Visual C++ cache files 76 | ipch/ 77 | *.aps 78 | *.ncb 79 | *.opendb 80 | *.opensdf 81 | *.sdf 82 | *.cachefile 83 | *.VC.db 84 | 85 | # Visual Studio profiler 86 | *.psess 87 | *.vsp 88 | *.vspx 89 | *.sap 90 | 91 | # TFS 2012 Local Workspace 92 | $tf/ 93 | 94 | # Guidance Automation Toolkit 95 | *.gpState 96 | 97 | # ReSharper is a .NET coding add-in 98 | _ReSharper*/ 99 | *.[Rr]e[Ss]harper 100 | *.DotSettings.user 101 | 102 | # JustCode is a .NET coding add-in 103 | .JustCode 104 | 105 | # TeamCity is a build add-in 106 | _TeamCity* 107 | 108 | # DotCover is a Code Coverage Tool 109 | *.dotCover 110 | 111 | # NCrunch 112 | _NCrunch_* 113 | .*crunch*.local.xml 114 | nCrunchTemp_* 115 | 116 | # MightyMoose 117 | *.mm.* 118 | AutoTest.Net/ 119 | 120 | # Web workbench (sass) 121 | .sass-cache/ 122 | 123 | # Installshield output folder 124 | [Ee]xpress/ 125 | 126 | # DocProject is a documentation generator add-in 127 | DocProject/buildhelp/ 128 | DocProject/Help/*.HxT 129 | DocProject/Help/*.HxC 130 | DocProject/Help/*.hhc 131 | DocProject/Help/*.hhk 132 | DocProject/Help/*.hhp 133 | DocProject/Help/Html2 134 | DocProject/Help/html 135 | 136 | # Click-Once directory 137 | publish/ 138 | 139 | # Publish Web Output 140 | *.[Pp]ublish.xml 141 | *.azurePubxml 142 | 143 | # TODO: Un-comment the next line if you do not want to checkin 144 | # your web deploy settings because they may include unencrypted 145 | # passwords 146 | #*.pubxml 147 | *.publishproj 148 | 149 | # NuGet Packages 150 | *.nupkg 151 | # The packages folder can be ignored because of Package Restore 152 | **/packages/* 153 | # except build/, which is used as an MSBuild target. 154 | !**/packages/build/ 155 | # Uncomment if necessary however generally it will be regenerated when needed 156 | #!**/packages/repositories.config 157 | # NuGet v3's project.json files produces more ignoreable files 158 | *.nuget.props 159 | *.nuget.targets 160 | 161 | # Microsoft Azure Build Output 162 | csx/ 163 | *.build.csdef 164 | 165 | # Microsoft Azure Emulator 166 | ecf/ 167 | rcf/ 168 | 169 | # Windows Store app package directory 170 | AppPackages/ 171 | BundleArtifacts/ 172 | 173 | # Visual Studio cache files 174 | # files ending in .cache can be ignored 175 | *.[Cc]ache 176 | # but keep track of directories ending in .cache 177 | !*.[Cc]ache/ 178 | 179 | # Others 180 | ClientBin/ 181 | [Ss]tyle[Cc]op.* 182 | ~$* 183 | *~ 184 | *.dbmdl 185 | *.dbproj.schemaview 186 | *.pfx 187 | *.publishsettings 188 | node_modules/ 189 | orleans.codegen.cs 190 | 191 | # RIA/Silverlight projects 192 | Generated_Code/ 193 | 194 | # Backup & report files from converting an old project file 195 | # to a newer Visual Studio version. Backup files are not needed, 196 | # because we have git ;-) 197 | _UpgradeReport_Files/ 198 | Backup*/ 199 | UpgradeLog*.XML 200 | UpgradeLog*.htm 201 | 202 | # SQL Server files 203 | *.mdf 204 | *.ldf 205 | 206 | # Business Intelligence projects 207 | *.rdl.data 208 | *.bim.layout 209 | *.bim_*.settings 210 | 211 | # Microsoft Fakes 212 | FakesAssemblies/ 213 | 214 | # GhostDoc plugin setting file 215 | *.GhostDoc.xml 216 | 217 | # Node.js Tools for Visual Studio 218 | .ntvs_analysis.dat 219 | 220 | # Visual Studio 6 build log 221 | *.plg 222 | 223 | # Visual Studio 6 workspace options file 224 | *.opt 225 | 226 | # Visual Studio LightSwitch build output 227 | **/*.HTMLClient/GeneratedArtifacts 228 | **/*.DesktopClient/GeneratedArtifacts 229 | **/*.DesktopClient/ModelManifest.xml 230 | **/*.Server/GeneratedArtifacts 231 | **/*.Server/ModelManifest.xml 232 | _Pvt_Extensions 233 | 234 | # LightSwitch generated files 235 | GeneratedArtifacts/ 236 | ModelManifest.xml 237 | 238 | # Paket dependency manager 239 | .paket/paket.exe 240 | 241 | # FAKE - F# Make 242 | .fake/ 243 | -------------------------------------------------------------------------------- /voc/voc.cpp: -------------------------------------------------------------------------------- 1 | #include 2 | #include 3 | 4 | // DBoW2 5 | #include "DBoW2.h" // defines OrbVocabulary and OrbDatabase 6 | 7 | #include 8 | #include 9 | 10 | // OpenCV 11 | #include 12 | #include 13 | #include 14 | 15 | 16 | using namespace DBoW2; 17 | using namespace DUtils; 18 | using namespace std; 19 | 20 | // - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - 21 | 22 | void loadFeatures(vector > &features); 23 | void changeStructure(const cv::Mat &plain, vector &out); 24 | void testVocCreation(const vector > &features); 25 | void testDatabase(const vector > &features); 26 | 27 | 28 | // - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - 29 | 30 | // number of training images 31 | const int NIMAGES = 10; 32 | 33 | // - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - 34 | 35 | void wait() 36 | { 37 | cout << endl << "Press enter to continue" << endl; 38 | getchar(); 39 | } 40 | 41 | // ---------------------------------------------------------------------------- 42 | 43 | int main() 44 | { 45 | vector > features; 46 | loadFeatures(features); 47 | 48 | testVocCreation(features); 49 | 50 | wait(); 51 | 52 | testDatabase(features); 53 | 54 | return 0; 55 | } 56 | 57 | // ---------------------------------------------------------------------------- 58 | 59 | void loadFeatures(vector > &features) 60 | { 61 | features.clear(); 62 | features.reserve(NIMAGES); 63 | 64 | cv::Ptr orb = cv::ORB::create(); 65 | 66 | cout << "Extracting ORB features..." << endl; 67 | for(int i = 0; i < NIMAGES; ++i) 68 | { 69 | stringstream ss; 70 | ss << "images/" << i << ".png"; 71 | 72 | cv::Mat image = cv::imread(ss.str(), 0); 73 | cv::Mat mask; 74 | vector keypoints; 75 | cv::Mat descriptors; 76 | 77 | orb->detectAndCompute(image, mask, keypoints, descriptors); 78 | 79 | features.push_back(vector()); 80 | changeStructure(descriptors, features.back()); 81 | } 82 | } 83 | 84 | // ---------------------------------------------------------------------------- 85 | 86 | void changeStructure(const cv::Mat &plain, vector &out) 87 | { 88 | out.resize(plain.rows); 89 | 90 | for(int i = 0; i < plain.rows; ++i) 91 | { 92 | out[i] = plain.row(i); 93 | } 94 | } 95 | 96 | // ---------------------------------------------------------------------------- 97 | 98 | void testVocCreation(const vector > &features) 99 | { 100 | // branching factor and depth levels 101 | const int k = 10; 102 | const int L = 5; 103 | const WeightingType weight = TF_IDF; 104 | const ScoringType score = L1_NORM; 105 | 106 | OrbVocabulary voc(k, L, weight, score); 107 | 108 | cout << "Creating a " << k << "^" << L << " vocabulary..." << endl; 109 | voc.create(features); 110 | cout << "... done!" << endl; 111 | 112 | cout << "Vocabulary information: " << endl 113 | << voc << endl << endl; 114 | 115 | // lets do something with this vocabulary 116 | cout << "Matching images against themselves: " << endl; 117 | BowVector v1, v2; 118 | for(int i = 0; i < NIMAGES; i++) 119 | { 120 | voc.transform(features[i], v1); 121 | for(int j = 0; j < NIMAGES; j++) 122 | { 123 | voc.transform(features[j], v2); 124 | 125 | double score = voc.score(v1, v2); 126 | cout << "Image " << i << " vs Image " << j << ": " << score << endl; 127 | } 128 | } 129 | 130 | // save the vocabulary to disk 131 | cout << endl << "Saving vocabulary..." << endl; 132 | voc.save("voc.yml.gz"); 133 | voc.saveToTextFile("Myvoc.txt"); 134 | cout << "Done" << endl; 135 | } 136 | 137 | // ---------------------------------------------------------------------------- 138 | 139 | void testDatabase(const vector > &features) 140 | { 141 | cout << "Creating a database..." << endl; 142 | 143 | // load the vocabulary from disk 144 | OrbVocabulary voc("voc.yml.gz"); 145 | 146 | OrbDatabase db(voc, false, 0); // false = do not use direct index 147 | // (so ignore the last param) 148 | // The direct index is useful if we want to retrieve the features that 149 | // belong to some vocabulary node. 150 | // db creates a copy of the vocabulary, we may get rid of "voc" now 151 | 152 | // add images to the database 153 | for(int i = 0; i < NIMAGES; i++) 154 | { 155 | db.add(features[i]); 156 | } 157 | 158 | cout << "... done!" << endl; 159 | 160 | cout << "Database information: " << endl << db << endl; 161 | 162 | // and query the database 163 | cout << "Querying the database: " << endl; 164 | 165 | QueryResults ret; 166 | for(int i = 0; i < NIMAGES; i++) 167 | { 168 | db.query(features[i], ret, 4); 169 | 170 | // ret[0] is always the same image in this case, because we added it to the 171 | // database. ret[1] is the second best match. 172 | 173 | cout << "Searching for Image " << i << ". " << ret << endl; 174 | } 175 | 176 | cout << endl; 177 | 178 | // we can save the database. The created file includes the vocabulary 179 | // and the entries added 180 | cout << "Saving database..." << endl; 181 | db.save("db_voc.yml.gz"); 182 | cout << "... done!" << endl; 183 | 184 | // once saved, we can load it again 185 | cout << "Retrieving database once again..." << endl; 186 | OrbDatabase db2("db_voc.yml.gz"); 187 | cout << "... done! This is: " << endl << db2 << endl; 188 | } 189 | -------------------------------------------------------------------------------- /src/FORB.cpp: -------------------------------------------------------------------------------- 1 | /** 2 | * File: FORB.cpp 3 | * Date: June 2012 4 | * Author: Dorian Galvez-Lopez 5 | * Description: functions for ORB descriptors 6 | * License: see the LICENSE.txt file 7 | * 8 | */ 9 | 10 | #include 11 | #include 12 | #include 13 | #include 14 | #include 15 | 16 | #include 17 | #include 18 | #include "FORB.h" 19 | 20 | using namespace std; 21 | 22 | namespace DBoW2 { 23 | 24 | // -------------------------------------------------------------------------- 25 | 26 | void FORB::meanValue(const std::vector &descriptors, 27 | FORB::TDescriptor &mean) 28 | { 29 | if(descriptors.empty()) 30 | { 31 | mean.release(); 32 | return; 33 | } 34 | else if(descriptors.size() == 1) 35 | { 36 | mean = descriptors[0]->clone(); 37 | } 38 | else 39 | { 40 | vector sum(FORB::L * 8, 0); 41 | 42 | for(size_t i = 0; i < descriptors.size(); ++i) 43 | { 44 | const cv::Mat &d = *descriptors[i]; 45 | const unsigned char *p = d.ptr(); 46 | 47 | for(int j = 0; j < d.cols; ++j, ++p) 48 | { 49 | if(*p & (1 << 7)) ++sum[ j*8 ]; 50 | if(*p & (1 << 6)) ++sum[ j*8 + 1 ]; 51 | if(*p & (1 << 5)) ++sum[ j*8 + 2 ]; 52 | if(*p & (1 << 4)) ++sum[ j*8 + 3 ]; 53 | if(*p & (1 << 3)) ++sum[ j*8 + 4 ]; 54 | if(*p & (1 << 2)) ++sum[ j*8 + 5 ]; 55 | if(*p & (1 << 1)) ++sum[ j*8 + 6 ]; 56 | if(*p & (1)) ++sum[ j*8 + 7 ]; 57 | } 58 | } 59 | 60 | mean = cv::Mat::zeros(1, FORB::L, CV_8U); 61 | unsigned char *p = mean.ptr(); 62 | 63 | const int N2 = (int)descriptors.size() / 2 + descriptors.size() % 2; 64 | for(size_t i = 0; i < sum.size(); ++i) 65 | { 66 | if(sum[i] >= N2) 67 | { 68 | // set bit 69 | *p |= 1 << (7 - (i % 8)); 70 | } 71 | 72 | if(i % 8 == 7) ++p; 73 | } 74 | } 75 | } 76 | 77 | // -------------------------------------------------------------------------- 78 | 79 | double FORB::distance(const FORB::TDescriptor &a, 80 | const FORB::TDescriptor &b) 81 | { 82 | // Bit count function got from: 83 | // http://graphics.stanford.edu/~seander/bithacks.html#CountBitsSetKernighan 84 | // This implementation assumes that a.cols (CV_8U) % sizeof(uint64_t) == 0 85 | 86 | const uint64_t *pa, *pb; 87 | pa = a.ptr(); // a & b are actually CV_8U 88 | pb = b.ptr(); 89 | 90 | uint64_t v, ret = 0; 91 | for(size_t i = 0; i < a.cols / sizeof(uint64_t); ++i, ++pa, ++pb) 92 | { 93 | v = *pa ^ *pb; 94 | v = v - ((v >> 1) & (uint64_t)~(uint64_t)0/3); 95 | v = (v & (uint64_t)~(uint64_t)0/15*3) + ((v >> 2) & 96 | (uint64_t)~(uint64_t)0/15*3); 97 | v = (v + (v >> 4)) & (uint64_t)~(uint64_t)0/255*15; 98 | ret += (uint64_t)(v * ((uint64_t)~(uint64_t)0/255)) >> 99 | (sizeof(uint64_t) - 1) * CHAR_BIT; 100 | } 101 | 102 | return ret; 103 | 104 | // // If uint64_t is not defined in your system, you can try this 105 | // // portable approach 106 | // const unsigned char *pa, *pb; 107 | // pa = a.ptr(); 108 | // pb = b.ptr(); 109 | // 110 | // int ret = 0; 111 | // for(int i = 0; i < a.cols; ++i, ++pa, ++pb) 112 | // { 113 | // ret += DUtils::LUT::ones8bits[ *pa ^ *pb ]; 114 | // } 115 | // 116 | // return ret; 117 | } 118 | 119 | // -------------------------------------------------------------------------- 120 | 121 | std::string FORB::toString(const FORB::TDescriptor &a) 122 | { 123 | stringstream ss; 124 | const unsigned char *p = a.ptr(); 125 | 126 | for(int i = 0; i < a.cols; ++i, ++p) 127 | { 128 | ss << (int)*p << " "; 129 | } 130 | 131 | return ss.str(); 132 | } 133 | 134 | // -------------------------------------------------------------------------- 135 | 136 | void FORB::fromString(FORB::TDescriptor &a, const std::string &s) 137 | { 138 | a.create(1, FORB::L, CV_8U); 139 | unsigned char *p = a.ptr(); 140 | 141 | stringstream ss(s); 142 | for(int i = 0; i < FORB::L; ++i, ++p) 143 | { 144 | int n; 145 | ss >> n; 146 | 147 | if(!ss.fail()) 148 | *p = (unsigned char)n; 149 | } 150 | 151 | } 152 | 153 | // -------------------------------------------------------------------------- 154 | 155 | void FORB::toMat32F(const std::vector &descriptors, 156 | cv::Mat &mat) 157 | { 158 | if(descriptors.empty()) 159 | { 160 | mat.release(); 161 | return; 162 | } 163 | 164 | const size_t N = descriptors.size(); 165 | 166 | mat.create(N, FORB::L*8, CV_32F); 167 | float *p = mat.ptr(); 168 | 169 | for(size_t i = 0; i < N; ++i) 170 | { 171 | const int C = descriptors[i].cols; 172 | const unsigned char *desc = descriptors[i].ptr(); 173 | 174 | for(int j = 0; j < C; ++j, p += 8) 175 | { 176 | p[0] = (desc[j] & (1 << 7) ? 1 : 0); 177 | p[1] = (desc[j] & (1 << 6) ? 1 : 0); 178 | p[2] = (desc[j] & (1 << 5) ? 1 : 0); 179 | p[3] = (desc[j] & (1 << 4) ? 1 : 0); 180 | p[4] = (desc[j] & (1 << 3) ? 1 : 0); 181 | p[5] = (desc[j] & (1 << 2) ? 1 : 0); 182 | p[6] = (desc[j] & (1 << 1) ? 1 : 0); 183 | p[7] = desc[j] & (1); 184 | } 185 | } 186 | } 187 | 188 | // -------------------------------------------------------------------------- 189 | 190 | void FORB::toMat32F(const cv::Mat &descriptors, cv::Mat &mat) 191 | { 192 | 193 | descriptors.convertTo(mat, CV_32F); 194 | return; 195 | 196 | if(descriptors.empty()) 197 | { 198 | mat.release(); 199 | return; 200 | } 201 | 202 | const int N = descriptors.rows; 203 | const int C = descriptors.cols; 204 | 205 | mat.create(N, FORB::L*8, CV_32F); 206 | float *p = mat.ptr(); // p[i] == 1 or 0 207 | 208 | const unsigned char *desc = descriptors.ptr(); 209 | 210 | for(int i = 0; i < N; ++i, desc += C) 211 | { 212 | for(int j = 0; j < C; ++j, p += 8) 213 | { 214 | p[0] = (desc[j] & (1 << 7) ? 1 : 0); 215 | p[1] = (desc[j] & (1 << 6) ? 1 : 0); 216 | p[2] = (desc[j] & (1 << 5) ? 1 : 0); 217 | p[3] = (desc[j] & (1 << 4) ? 1 : 0); 218 | p[4] = (desc[j] & (1 << 3) ? 1 : 0); 219 | p[5] = (desc[j] & (1 << 2) ? 1 : 0); 220 | p[6] = (desc[j] & (1 << 1) ? 1 : 0); 221 | p[7] = desc[j] & (1); 222 | } 223 | } 224 | } 225 | 226 | // -------------------------------------------------------------------------- 227 | 228 | void FORB::toMat8U(const std::vector &descriptors, 229 | cv::Mat &mat) 230 | { 231 | mat.create(descriptors.size(), FORB::L, CV_8U); 232 | 233 | unsigned char *p = mat.ptr(); 234 | 235 | for(size_t i = 0; i < descriptors.size(); ++i, p += FORB::L) 236 | { 237 | const unsigned char *d = descriptors[i].ptr(); 238 | std::copy(d, d + FORB::L, p); 239 | } 240 | 241 | } 242 | 243 | // -------------------------------------------------------------------------- 244 | 245 | } // namespace DBoW2 246 | 247 | -------------------------------------------------------------------------------- /src/ScoringObject.cpp: -------------------------------------------------------------------------------- 1 | /** 2 | * File: ScoringObject.cpp 3 | * Date: November 2011 4 | * Author: Dorian Galvez-Lopez 5 | * Description: functions to compute bow scores 6 | * License: see the LICENSE.txt file 7 | * 8 | */ 9 | 10 | #include 11 | #include "TemplatedVocabulary.h" 12 | #include "BowVector.h" 13 | 14 | using namespace DBoW2; 15 | 16 | // If you change the type of WordValue, make sure you change also the 17 | // epsilon value (this is needed by the KL method) 18 | const double GeneralScoring::LOG_EPS = log(DBL_EPSILON); // FLT_EPSILON 19 | 20 | // --------------------------------------------------------------------------- 21 | // --------------------------------------------------------------------------- 22 | 23 | double L1Scoring::score(const BowVector &v1, const BowVector &v2) const 24 | { 25 | BowVector::const_iterator v1_it, v2_it; 26 | const BowVector::const_iterator v1_end = v1.end(); 27 | const BowVector::const_iterator v2_end = v2.end(); 28 | 29 | v1_it = v1.begin(); 30 | v2_it = v2.begin(); 31 | 32 | double score = 0; 33 | 34 | while(v1_it != v1_end && v2_it != v2_end) 35 | { 36 | const WordValue& vi = v1_it->second; 37 | const WordValue& wi = v2_it->second; 38 | 39 | if(v1_it->first == v2_it->first) 40 | { 41 | score += fabs(vi - wi) - fabs(vi) - fabs(wi); 42 | 43 | // move v1 and v2 forward 44 | ++v1_it; 45 | ++v2_it; 46 | } 47 | else if(v1_it->first < v2_it->first) 48 | { 49 | // move v1 forward 50 | v1_it = v1.lower_bound(v2_it->first); 51 | // v1_it = (first element >= v2_it.id) 52 | } 53 | else 54 | { 55 | // move v2 forward 56 | v2_it = v2.lower_bound(v1_it->first); 57 | // v2_it = (first element >= v1_it.id) 58 | } 59 | } 60 | 61 | // ||v - w||_{L1} = 2 + Sum(|v_i - w_i| - |v_i| - |w_i|) 62 | // for all i | v_i != 0 and w_i != 0 63 | // (Nister, 2006) 64 | // scaled_||v - w||_{L1} = 1 - 0.5 * ||v - w||_{L1} 65 | score = -score/2.0; 66 | 67 | return score; // [0..1] 68 | } 69 | 70 | // --------------------------------------------------------------------------- 71 | // --------------------------------------------------------------------------- 72 | 73 | double L2Scoring::score(const BowVector &v1, const BowVector &v2) const 74 | { 75 | BowVector::const_iterator v1_it, v2_it; 76 | const BowVector::const_iterator v1_end = v1.end(); 77 | const BowVector::const_iterator v2_end = v2.end(); 78 | 79 | v1_it = v1.begin(); 80 | v2_it = v2.begin(); 81 | 82 | double score = 0; 83 | 84 | while(v1_it != v1_end && v2_it != v2_end) 85 | { 86 | const WordValue& vi = v1_it->second; 87 | const WordValue& wi = v2_it->second; 88 | 89 | if(v1_it->first == v2_it->first) 90 | { 91 | score += vi * wi; 92 | 93 | // move v1 and v2 forward 94 | ++v1_it; 95 | ++v2_it; 96 | } 97 | else if(v1_it->first < v2_it->first) 98 | { 99 | // move v1 forward 100 | v1_it = v1.lower_bound(v2_it->first); 101 | // v1_it = (first element >= v2_it.id) 102 | } 103 | else 104 | { 105 | // move v2 forward 106 | v2_it = v2.lower_bound(v1_it->first); 107 | // v2_it = (first element >= v1_it.id) 108 | } 109 | } 110 | 111 | // ||v - w||_{L2} = sqrt( 2 - 2 * Sum(v_i * w_i) ) 112 | // for all i | v_i != 0 and w_i != 0 ) 113 | // (Nister, 2006) 114 | if(score >= 1) // rounding errors 115 | score = 1.0; 116 | else 117 | score = 1.0 - sqrt(1.0 - score); // [0..1] 118 | 119 | return score; 120 | } 121 | 122 | // --------------------------------------------------------------------------- 123 | // --------------------------------------------------------------------------- 124 | 125 | double ChiSquareScoring::score(const BowVector &v1, const BowVector &v2) 126 | const 127 | { 128 | BowVector::const_iterator v1_it, v2_it; 129 | const BowVector::const_iterator v1_end = v1.end(); 130 | const BowVector::const_iterator v2_end = v2.end(); 131 | 132 | v1_it = v1.begin(); 133 | v2_it = v2.begin(); 134 | 135 | double score = 0; 136 | 137 | // all the items are taken into account 138 | 139 | while(v1_it != v1_end && v2_it != v2_end) 140 | { 141 | const WordValue& vi = v1_it->second; 142 | const WordValue& wi = v2_it->second; 143 | 144 | if(v1_it->first == v2_it->first) 145 | { 146 | // (v-w)^2/(v+w) - v - w = -4 vw/(v+w) 147 | // we move the -4 out 148 | if(vi + wi != 0.0) score += vi * wi / (vi + wi); 149 | 150 | // move v1 and v2 forward 151 | ++v1_it; 152 | ++v2_it; 153 | } 154 | else if(v1_it->first < v2_it->first) 155 | { 156 | // move v1 forward 157 | v1_it = v1.lower_bound(v2_it->first); 158 | } 159 | else 160 | { 161 | // move v2 forward 162 | v2_it = v2.lower_bound(v1_it->first); 163 | } 164 | } 165 | 166 | // this takes the -4 into account 167 | score = 2. * score; // [0..1] 168 | 169 | return score; 170 | } 171 | 172 | // --------------------------------------------------------------------------- 173 | // --------------------------------------------------------------------------- 174 | 175 | double KLScoring::score(const BowVector &v1, const BowVector &v2) const 176 | { 177 | BowVector::const_iterator v1_it, v2_it; 178 | const BowVector::const_iterator v1_end = v1.end(); 179 | const BowVector::const_iterator v2_end = v2.end(); 180 | 181 | v1_it = v1.begin(); 182 | v2_it = v2.begin(); 183 | 184 | double score = 0; 185 | 186 | // all the items or v are taken into account 187 | 188 | while(v1_it != v1_end && v2_it != v2_end) 189 | { 190 | const WordValue& vi = v1_it->second; 191 | const WordValue& wi = v2_it->second; 192 | 193 | if(v1_it->first == v2_it->first) 194 | { 195 | if(vi != 0 && wi != 0) score += vi * log(vi/wi); 196 | 197 | // move v1 and v2 forward 198 | ++v1_it; 199 | ++v2_it; 200 | } 201 | else if(v1_it->first < v2_it->first) 202 | { 203 | // move v1 forward 204 | score += vi * (log(vi) - LOG_EPS); 205 | ++v1_it; 206 | } 207 | else 208 | { 209 | // move v2_it forward, do not add any score 210 | v2_it = v2.lower_bound(v1_it->first); 211 | // v2_it = (first element >= v1_it.id) 212 | } 213 | } 214 | 215 | // sum rest of items of v 216 | for(; v1_it != v1_end; ++v1_it) 217 | if(v1_it->second != 0) 218 | score += v1_it->second * (log(v1_it->second) - LOG_EPS); 219 | 220 | return score; // cannot be scaled 221 | } 222 | 223 | // --------------------------------------------------------------------------- 224 | // --------------------------------------------------------------------------- 225 | 226 | double BhattacharyyaScoring::score(const BowVector &v1, 227 | const BowVector &v2) const 228 | { 229 | BowVector::const_iterator v1_it, v2_it; 230 | const BowVector::const_iterator v1_end = v1.end(); 231 | const BowVector::const_iterator v2_end = v2.end(); 232 | 233 | v1_it = v1.begin(); 234 | v2_it = v2.begin(); 235 | 236 | double score = 0; 237 | 238 | while(v1_it != v1_end && v2_it != v2_end) 239 | { 240 | const WordValue& vi = v1_it->second; 241 | const WordValue& wi = v2_it->second; 242 | 243 | if(v1_it->first == v2_it->first) 244 | { 245 | score += sqrt(vi * wi); 246 | 247 | // move v1 and v2 forward 248 | ++v1_it; 249 | ++v2_it; 250 | } 251 | else if(v1_it->first < v2_it->first) 252 | { 253 | // move v1 forward 254 | v1_it = v1.lower_bound(v2_it->first); 255 | // v1_it = (first element >= v2_it.id) 256 | } 257 | else 258 | { 259 | // move v2 forward 260 | v2_it = v2.lower_bound(v1_it->first); 261 | // v2_it = (first element >= v1_it.id) 262 | } 263 | } 264 | 265 | return score; // already scaled 266 | } 267 | 268 | // --------------------------------------------------------------------------- 269 | // --------------------------------------------------------------------------- 270 | 271 | double DotProductScoring::score(const BowVector &v1, 272 | const BowVector &v2) const 273 | { 274 | BowVector::const_iterator v1_it, v2_it; 275 | const BowVector::const_iterator v1_end = v1.end(); 276 | const BowVector::const_iterator v2_end = v2.end(); 277 | 278 | v1_it = v1.begin(); 279 | v2_it = v2.begin(); 280 | 281 | double score = 0; 282 | 283 | while(v1_it != v1_end && v2_it != v2_end) 284 | { 285 | const WordValue& vi = v1_it->second; 286 | const WordValue& wi = v2_it->second; 287 | 288 | if(v1_it->first == v2_it->first) 289 | { 290 | score += vi * wi; 291 | 292 | // move v1 and v2 forward 293 | ++v1_it; 294 | ++v2_it; 295 | } 296 | else if(v1_it->first < v2_it->first) 297 | { 298 | // move v1 forward 299 | v1_it = v1.lower_bound(v2_it->first); 300 | // v1_it = (first element >= v2_it.id) 301 | } 302 | else 303 | { 304 | // move v2 forward 305 | v2_it = v2.lower_bound(v1_it->first); 306 | // v2_it = (first element >= v1_it.id) 307 | } 308 | } 309 | 310 | return score; // cannot scale 311 | } 312 | 313 | // --------------------------------------------------------------------------- 314 | // --------------------------------------------------------------------------- 315 | 316 | -------------------------------------------------------------------------------- /include/DBoW2/TemplatedDatabase.h: -------------------------------------------------------------------------------- 1 | /** 2 | * File: TemplatedDatabase.h 3 | * Date: March 2011 4 | * Author: Dorian Galvez-Lopez 5 | * Description: templated database of images 6 | * License: see the LICENSE.txt file 7 | * 8 | */ 9 | 10 | #ifndef __D_T_TEMPLATED_DATABASE__ 11 | #define __D_T_TEMPLATED_DATABASE__ 12 | 13 | #include 14 | #include 15 | #include 16 | #include 17 | #include 18 | #include 19 | 20 | #include "TemplatedVocabulary.h" 21 | #include "QueryResults.h" 22 | #include "ScoringObject.h" 23 | #include "BowVector.h" 24 | #include "FeatureVector.h" 25 | 26 | #include 27 | 28 | namespace DBoW2 { 29 | 30 | // For query functions 31 | static int MIN_COMMON_WORDS = 5; 32 | 33 | /// @param TDescriptor class of descriptor 34 | /// @param F class of descriptor functions 35 | template 36 | /// Generic Database 37 | class TemplatedDatabase 38 | { 39 | public: 40 | 41 | /** 42 | * Creates an empty database without vocabulary 43 | * @param use_di a direct index is used to store feature indexes 44 | * @param di_levels levels to go up the vocabulary tree to select the 45 | * node id to store in the direct index when adding images 46 | */ 47 | explicit TemplatedDatabase(bool use_di = true, int di_levels = 0); 48 | 49 | /** 50 | * Creates a database with the given vocabulary 51 | * @param T class inherited from TemplatedVocabulary 52 | * @param voc vocabulary 53 | * @param use_di a direct index is used to store feature indexes 54 | * @param di_levels levels to go up the vocabulary tree to select the 55 | * node id to store in the direct index when adding images 56 | */ 57 | template 58 | explicit TemplatedDatabase(const T &voc, bool use_di = true, 59 | int di_levels = 0); 60 | 61 | /** 62 | * Copy constructor. Copies the vocabulary too 63 | * @param db object to copy 64 | */ 65 | TemplatedDatabase(const TemplatedDatabase &db); 66 | 67 | /** 68 | * Creates the database from a file 69 | * @param filename 70 | */ 71 | TemplatedDatabase(const std::string &filename); 72 | 73 | /** 74 | * Creates the database from a file 75 | * @param filename 76 | */ 77 | TemplatedDatabase(const char *filename); 78 | 79 | /** 80 | * Destructor 81 | */ 82 | virtual ~TemplatedDatabase(void); 83 | 84 | /** 85 | * Copies the given database and its vocabulary 86 | * @param db database to copy 87 | */ 88 | TemplatedDatabase& operator=( 89 | const TemplatedDatabase &db); 90 | 91 | /** 92 | * Sets the vocabulary to use and clears the content of the database. 93 | * @param T class inherited from TemplatedVocabulary 94 | * @param voc vocabulary to copy 95 | */ 96 | template 97 | inline void setVocabulary(const T &voc); 98 | 99 | /** 100 | * Sets the vocabulary to use and the direct index parameters, and clears 101 | * the content of the database 102 | * @param T class inherited from TemplatedVocabulary 103 | * @param voc vocabulary to copy 104 | * @param use_di a direct index is used to store feature indexes 105 | * @param di_levels levels to go up the vocabulary tree to select the 106 | * node id to store in the direct index when adding images 107 | */ 108 | template 109 | void setVocabulary(const T& voc, bool use_di, int di_levels = 0); 110 | 111 | /** 112 | * Returns a pointer to the vocabulary used 113 | * @return vocabulary 114 | */ 115 | inline const TemplatedVocabulary* getVocabulary() const; 116 | 117 | /** 118 | * Allocates some memory for the direct and inverted indexes 119 | * @param nd number of expected image entries in the database 120 | * @param ni number of expected words per image 121 | * @note Use 0 to ignore a parameter 122 | */ 123 | void allocate(int nd = 0, int ni = 0); 124 | 125 | /** 126 | * Adds an entry to the database and returns its index 127 | * @param features features of the new entry 128 | * @param bowvec if given, the bow vector of these features is returned 129 | * @param fvec if given, the vector of nodes and feature indexes is returned 130 | * @return id of new entry 131 | */ 132 | EntryId add(const std::vector &features, 133 | BowVector *bowvec = NULL, FeatureVector *fvec = NULL); 134 | 135 | /** 136 | * Adss an entry to the database and returns its index 137 | * @param vec bow vector 138 | * @param fec feature vector to add the entry. Only necessary if using the 139 | * direct index 140 | * @return id of new entry 141 | */ 142 | EntryId add(const BowVector &vec, 143 | const FeatureVector &fec = FeatureVector() ); 144 | 145 | /** 146 | * Empties the database 147 | */ 148 | inline void clear(); 149 | 150 | /** 151 | * Returns the number of entries in the database 152 | * @return number of entries in the database 153 | */ 154 | inline unsigned int size() const; 155 | 156 | /** 157 | * Checks if the direct index is being used 158 | * @return true iff using direct index 159 | */ 160 | inline bool usingDirectIndex() const; 161 | 162 | /** 163 | * Returns the di levels when using direct index 164 | * @return di levels 165 | */ 166 | inline int getDirectIndexLevels() const; 167 | 168 | /** 169 | * Queries the database with some features 170 | * @param features query features 171 | * @param ret (out) query results 172 | * @param max_results number of results to return. <= 0 means all 173 | * @param max_id only entries with id <= max_id are returned in ret. 174 | * < 0 means all 175 | */ 176 | void query(const std::vector &features, QueryResults &ret, 177 | int max_results = 1, int max_id = -1) const; 178 | 179 | /** 180 | * Queries the database with a vector 181 | * @param vec bow vector already normalized 182 | * @param ret results 183 | * @param max_results number of results to return. <= 0 means all 184 | * @param max_id only entries with id <= max_id are returned in ret. 185 | * < 0 means all 186 | */ 187 | void query(const BowVector &vec, QueryResults &ret, 188 | int max_results = 1, int max_id = -1) const; 189 | 190 | /** 191 | * Returns the a feature vector associated with a database entry 192 | * @param id entry id (must be < size()) 193 | * @return const reference to map of nodes and their associated features in 194 | * the given entry 195 | */ 196 | const FeatureVector& retrieveFeatures(EntryId id) const; 197 | 198 | /** 199 | * Stores the database in a file 200 | * @param filename 201 | */ 202 | void save(const std::string &filename) const; 203 | 204 | /** 205 | * Loads the database from a file 206 | * @param filename 207 | */ 208 | void load(const std::string &filename); 209 | 210 | /** 211 | * Stores the database in the given file storage structure 212 | * @param fs 213 | * @param name node name 214 | */ 215 | virtual void save(cv::FileStorage &fs, 216 | const std::string &name = "database") const; 217 | 218 | /** 219 | * Loads the database from the given file storage structure 220 | * @param fs 221 | * @param name node name 222 | */ 223 | virtual void load(const cv::FileStorage &fs, 224 | const std::string &name = "database"); 225 | 226 | protected: 227 | 228 | /// Query with L1 scoring 229 | void queryL1(const BowVector &vec, QueryResults &ret, 230 | int max_results, int max_id) const; 231 | 232 | /// Query with L2 scoring 233 | void queryL2(const BowVector &vec, QueryResults &ret, 234 | int max_results, int max_id) const; 235 | 236 | /// Query with Chi square scoring 237 | void queryChiSquare(const BowVector &vec, QueryResults &ret, 238 | int max_results, int max_id) const; 239 | 240 | /// Query with Bhattacharyya scoring 241 | void queryBhattacharyya(const BowVector &vec, QueryResults &ret, 242 | int max_results, int max_id) const; 243 | 244 | /// Query with KL divergence scoring 245 | void queryKL(const BowVector &vec, QueryResults &ret, 246 | int max_results, int max_id) const; 247 | 248 | /// Query with dot product scoring 249 | void queryDotProduct(const BowVector &vec, QueryResults &ret, 250 | int max_results, int max_id) const; 251 | 252 | protected: 253 | 254 | /* Inverted file declaration */ 255 | 256 | /// Item of IFRow 257 | struct IFPair 258 | { 259 | /// Entry id 260 | EntryId entry_id; 261 | 262 | /// Word weight in this entry 263 | WordValue word_weight; 264 | 265 | /** 266 | * Creates an empty pair 267 | */ 268 | IFPair(){} 269 | 270 | /** 271 | * Creates an inverted file pair 272 | * @param eid entry id 273 | * @param wv word weight 274 | */ 275 | IFPair(EntryId eid, WordValue wv): entry_id(eid), word_weight(wv) {} 276 | 277 | /** 278 | * Compares the entry ids 279 | * @param eid 280 | * @return true iff this entry id is the same as eid 281 | */ 282 | inline bool operator==(EntryId eid) const { return entry_id == eid; } 283 | }; 284 | 285 | /// Row of InvertedFile 286 | typedef std::list IFRow; 287 | // IFRows are sorted in ascending entry_id order 288 | 289 | /// Inverted index 290 | typedef std::vector InvertedFile; 291 | // InvertedFile[word_id] --> inverted file of that word 292 | 293 | /* Direct file declaration */ 294 | 295 | /// Direct index 296 | typedef std::vector DirectFile; 297 | // DirectFile[entry_id] --> [ directentry, ... ] 298 | 299 | protected: 300 | 301 | /// Associated vocabulary 302 | TemplatedVocabulary *m_voc; 303 | 304 | /// Flag to use direct index 305 | bool m_use_di; 306 | 307 | /// Levels to go up the vocabulary tree to select nodes to store 308 | /// in the direct index 309 | int m_dilevels; 310 | 311 | /// Inverted file (must have size() == |words|) 312 | InvertedFile m_ifile; 313 | 314 | /// Direct file (resized for allocation) 315 | DirectFile m_dfile; 316 | 317 | /// Number of valid entries in m_dfile 318 | int m_nentries; 319 | 320 | }; 321 | 322 | // -------------------------------------------------------------------------- 323 | 324 | template 325 | TemplatedDatabase::TemplatedDatabase 326 | (bool use_di, int di_levels) 327 | : m_voc(NULL), m_use_di(use_di), m_dilevels(di_levels), m_nentries(0) 328 | { 329 | } 330 | 331 | // -------------------------------------------------------------------------- 332 | 333 | template 334 | template 335 | TemplatedDatabase::TemplatedDatabase 336 | (const T &voc, bool use_di, int di_levels) 337 | : m_voc(NULL), m_use_di(use_di), m_dilevels(di_levels) 338 | { 339 | setVocabulary(voc); 340 | clear(); 341 | } 342 | 343 | // -------------------------------------------------------------------------- 344 | 345 | template 346 | TemplatedDatabase::TemplatedDatabase 347 | (const TemplatedDatabase &db) 348 | : m_voc(NULL) 349 | { 350 | *this = db; 351 | } 352 | 353 | // -------------------------------------------------------------------------- 354 | 355 | template 356 | TemplatedDatabase::TemplatedDatabase 357 | (const std::string &filename) 358 | : m_voc(NULL) 359 | { 360 | load(filename); 361 | } 362 | 363 | // -------------------------------------------------------------------------- 364 | 365 | template 366 | TemplatedDatabase::TemplatedDatabase 367 | (const char *filename) 368 | : m_voc(NULL) 369 | { 370 | load(filename); 371 | } 372 | 373 | // -------------------------------------------------------------------------- 374 | 375 | template 376 | TemplatedDatabase::~TemplatedDatabase(void) 377 | { 378 | delete m_voc; 379 | } 380 | 381 | // -------------------------------------------------------------------------- 382 | 383 | template 384 | TemplatedDatabase& TemplatedDatabase::operator= 385 | (const TemplatedDatabase &db) 386 | { 387 | if(this != &db) 388 | { 389 | m_dfile = db.m_dfile; 390 | m_dilevels = db.m_dilevels; 391 | m_ifile = db.m_ifile; 392 | m_nentries = db.m_nentries; 393 | m_use_di = db.m_use_di; 394 | setVocabulary(*db.m_voc); 395 | } 396 | return *this; 397 | } 398 | 399 | // -------------------------------------------------------------------------- 400 | 401 | template 402 | EntryId TemplatedDatabase::add( 403 | const std::vector &features, 404 | BowVector *bowvec, FeatureVector *fvec) 405 | { 406 | BowVector aux; 407 | BowVector& v = (bowvec ? *bowvec : aux); 408 | 409 | if(m_use_di && fvec != NULL) 410 | { 411 | m_voc->transform(features, v, *fvec, m_dilevels); // with features 412 | return add(v, *fvec); 413 | } 414 | else if(m_use_di) 415 | { 416 | FeatureVector fv; 417 | m_voc->transform(features, v, fv, m_dilevels); // with features 418 | return add(v, fv); 419 | } 420 | else if(fvec != NULL) 421 | { 422 | m_voc->transform(features, v, *fvec, m_dilevels); // with features 423 | return add(v); 424 | } 425 | else 426 | { 427 | m_voc->transform(features, v); // with features 428 | return add(v); 429 | } 430 | } 431 | 432 | // --------------------------------------------------------------------------- 433 | 434 | template 435 | EntryId TemplatedDatabase::add(const BowVector &v, 436 | const FeatureVector &fv) 437 | { 438 | EntryId entry_id = m_nentries++; 439 | 440 | BowVector::const_iterator vit; 441 | std::vector::const_iterator iit; 442 | 443 | if(m_use_di) 444 | { 445 | // update direct file 446 | if(entry_id == m_dfile.size()) 447 | { 448 | m_dfile.push_back(fv); 449 | } 450 | else 451 | { 452 | m_dfile[entry_id] = fv; 453 | } 454 | } 455 | 456 | // update inverted file 457 | for(vit = v.begin(); vit != v.end(); ++vit) 458 | { 459 | const WordId& word_id = vit->first; 460 | const WordValue& word_weight = vit->second; 461 | 462 | IFRow& ifrow = m_ifile[word_id]; 463 | ifrow.push_back(IFPair(entry_id, word_weight)); 464 | } 465 | 466 | return entry_id; 467 | } 468 | 469 | // -------------------------------------------------------------------------- 470 | 471 | template 472 | template 473 | inline void TemplatedDatabase::setVocabulary 474 | (const T& voc) 475 | { 476 | delete m_voc; 477 | m_voc = new T(voc); 478 | clear(); 479 | } 480 | 481 | // -------------------------------------------------------------------------- 482 | 483 | template 484 | template 485 | inline void TemplatedDatabase::setVocabulary 486 | (const T& voc, bool use_di, int di_levels) 487 | { 488 | m_use_di = use_di; 489 | m_dilevels = di_levels; 490 | delete m_voc; 491 | m_voc = new T(voc); 492 | clear(); 493 | } 494 | 495 | // -------------------------------------------------------------------------- 496 | 497 | template 498 | inline const TemplatedVocabulary* 499 | TemplatedDatabase::getVocabulary() const 500 | { 501 | return m_voc; 502 | } 503 | 504 | // -------------------------------------------------------------------------- 505 | 506 | template 507 | inline void TemplatedDatabase::clear() 508 | { 509 | // resize vectors 510 | m_ifile.resize(0); 511 | m_ifile.resize(m_voc->size()); 512 | m_dfile.resize(0); 513 | m_nentries = 0; 514 | } 515 | 516 | // -------------------------------------------------------------------------- 517 | 518 | template 519 | void TemplatedDatabase::allocate(int nd, int ni) 520 | { 521 | // m_ifile already contains |words| items 522 | if(ni > 0) 523 | { 524 | typename std::vector::iterator rit; 525 | for(rit = m_ifile.begin(); rit != m_ifile.end(); ++rit) 526 | { 527 | int n = (int)rit->size(); 528 | if(ni > n) 529 | { 530 | rit->resize(ni); 531 | rit->resize(n); 532 | } 533 | } 534 | } 535 | 536 | if(m_use_di && (int)m_dfile.size() < nd) 537 | { 538 | m_dfile.resize(nd); 539 | } 540 | } 541 | 542 | // -------------------------------------------------------------------------- 543 | 544 | template 545 | inline unsigned int TemplatedDatabase::size() const 546 | { 547 | return m_nentries; 548 | } 549 | 550 | // -------------------------------------------------------------------------- 551 | 552 | template 553 | inline bool TemplatedDatabase::usingDirectIndex() const 554 | { 555 | return m_use_di; 556 | } 557 | 558 | // -------------------------------------------------------------------------- 559 | 560 | template 561 | inline int TemplatedDatabase::getDirectIndexLevels() const 562 | { 563 | return m_dilevels; 564 | } 565 | 566 | // -------------------------------------------------------------------------- 567 | 568 | template 569 | void TemplatedDatabase::query( 570 | const std::vector &features, 571 | QueryResults &ret, int max_results, int max_id) const 572 | { 573 | BowVector vec; 574 | m_voc->transform(features, vec); 575 | query(vec, ret, max_results, max_id); 576 | } 577 | 578 | // -------------------------------------------------------------------------- 579 | 580 | template 581 | void TemplatedDatabase::query( 582 | const BowVector &vec, 583 | QueryResults &ret, int max_results, int max_id) const 584 | { 585 | ret.resize(0); 586 | 587 | switch(m_voc->getScoringType()) 588 | { 589 | case L1_NORM: 590 | queryL1(vec, ret, max_results, max_id); 591 | break; 592 | 593 | case L2_NORM: 594 | queryL2(vec, ret, max_results, max_id); 595 | break; 596 | 597 | case CHI_SQUARE: 598 | queryChiSquare(vec, ret, max_results, max_id); 599 | break; 600 | 601 | case KL: 602 | queryKL(vec, ret, max_results, max_id); 603 | break; 604 | 605 | case BHATTACHARYYA: 606 | queryBhattacharyya(vec, ret, max_results, max_id); 607 | break; 608 | 609 | case DOT_PRODUCT: 610 | queryDotProduct(vec, ret, max_results, max_id); 611 | break; 612 | } 613 | } 614 | 615 | // -------------------------------------------------------------------------- 616 | 617 | template 618 | void TemplatedDatabase::queryL1(const BowVector &vec, 619 | QueryResults &ret, int max_results, int max_id) const 620 | { 621 | BowVector::const_iterator vit; 622 | typename IFRow::const_iterator rit; 623 | 624 | std::map pairs; 625 | std::map::iterator pit; 626 | 627 | for(vit = vec.begin(); vit != vec.end(); ++vit) 628 | { 629 | const WordId word_id = vit->first; 630 | const WordValue& qvalue = vit->second; 631 | 632 | const IFRow& row = m_ifile[word_id]; 633 | 634 | // IFRows are sorted in ascending entry_id order 635 | 636 | for(rit = row.begin(); rit != row.end(); ++rit) 637 | { 638 | const EntryId entry_id = rit->entry_id; 639 | const WordValue& dvalue = rit->word_weight; 640 | 641 | if((int)entry_id < max_id || max_id == -1) 642 | { 643 | double value = fabs(qvalue - dvalue) - fabs(qvalue) - fabs(dvalue); 644 | 645 | pit = pairs.lower_bound(entry_id); 646 | if(pit != pairs.end() && !(pairs.key_comp()(entry_id, pit->first))) 647 | { 648 | pit->second += value; 649 | } 650 | else 651 | { 652 | pairs.insert(pit, 653 | std::map::value_type(entry_id, value)); 654 | } 655 | } 656 | 657 | } // for each inverted row 658 | } // for each query word 659 | 660 | // move to vector 661 | ret.reserve(pairs.size()); 662 | for(pit = pairs.begin(); pit != pairs.end(); ++pit) 663 | { 664 | ret.push_back(Result(pit->first, pit->second)); 665 | } 666 | 667 | // resulting "scores" are now in [-2 best .. 0 worst] 668 | 669 | // sort vector in ascending order of score 670 | std::sort(ret.begin(), ret.end()); 671 | // (ret is inverted now --the lower the better--) 672 | 673 | // cut vector 674 | if(max_results > 0 && (int)ret.size() > max_results) 675 | ret.resize(max_results); 676 | 677 | // complete and scale score to [0 worst .. 1 best] 678 | // ||v - w||_{L1} = 2 + Sum(|v_i - w_i| - |v_i| - |w_i|) 679 | // for all i | v_i != 0 and w_i != 0 680 | // (Nister, 2006) 681 | // scaled_||v - w||_{L1} = 1 - 0.5 * ||v - w||_{L1} 682 | QueryResults::iterator qit; 683 | for(qit = ret.begin(); qit != ret.end(); qit++) 684 | qit->Score = -qit->Score/2.0; 685 | } 686 | 687 | // -------------------------------------------------------------------------- 688 | 689 | template 690 | void TemplatedDatabase::queryL2(const BowVector &vec, 691 | QueryResults &ret, int max_results, int max_id) const 692 | { 693 | BowVector::const_iterator vit; 694 | typename IFRow::const_iterator rit; 695 | 696 | std::map pairs; 697 | std::map::iterator pit; 698 | 699 | //map counters; 700 | //map::iterator cit; 701 | 702 | for(vit = vec.begin(); vit != vec.end(); ++vit) 703 | { 704 | const WordId word_id = vit->first; 705 | const WordValue& qvalue = vit->second; 706 | 707 | const IFRow& row = m_ifile[word_id]; 708 | 709 | // IFRows are sorted in ascending entry_id order 710 | 711 | for(rit = row.begin(); rit != row.end(); ++rit) 712 | { 713 | const EntryId entry_id = rit->entry_id; 714 | const WordValue& dvalue = rit->word_weight; 715 | 716 | if((int)entry_id < max_id || max_id == -1) 717 | { 718 | double value = - qvalue * dvalue; // minus sign for sorting trick 719 | 720 | pit = pairs.lower_bound(entry_id); 721 | //cit = counters.lower_bound(entry_id); 722 | if(pit != pairs.end() && !(pairs.key_comp()(entry_id, pit->first))) 723 | { 724 | pit->second += value; 725 | //cit->second += 1; 726 | } 727 | else 728 | { 729 | pairs.insert(pit, 730 | std::map::value_type(entry_id, value)); 731 | 732 | //counters.insert(cit, 733 | // map::value_type(entry_id, 1)); 734 | } 735 | } 736 | 737 | } // for each inverted row 738 | } // for each query word 739 | 740 | // move to vector 741 | ret.reserve(pairs.size()); 742 | //cit = counters.begin(); 743 | for(pit = pairs.begin(); pit != pairs.end(); ++pit)//, ++cit) 744 | { 745 | ret.push_back(Result(pit->first, pit->second));// / cit->second)); 746 | } 747 | 748 | // resulting "scores" are now in [-1 best .. 0 worst] 749 | 750 | // sort vector in ascending order of score 751 | std::sort(ret.begin(), ret.end()); 752 | // (ret is inverted now --the lower the better--) 753 | 754 | // cut vector 755 | if(max_results > 0 && (int)ret.size() > max_results) 756 | ret.resize(max_results); 757 | 758 | // complete and scale score to [0 worst .. 1 best] 759 | // ||v - w||_{L2} = sqrt( 2 - 2 * Sum(v_i * w_i) 760 | // for all i | v_i != 0 and w_i != 0 ) 761 | // (Nister, 2006) 762 | QueryResults::iterator qit; 763 | for(qit = ret.begin(); qit != ret.end(); qit++) 764 | { 765 | if(qit->Score <= -1.0) // rounding error 766 | qit->Score = 1.0; 767 | else 768 | qit->Score = 1.0 - sqrt(1.0 + qit->Score); // [0..1] 769 | // the + sign is ok, it is due to - sign in 770 | // value = - qvalue * dvalue 771 | } 772 | 773 | } 774 | 775 | // -------------------------------------------------------------------------- 776 | 777 | template 778 | void TemplatedDatabase::queryChiSquare(const BowVector &vec, 779 | QueryResults &ret, int max_results, int max_id) const 780 | { 781 | BowVector::const_iterator vit; 782 | typename IFRow::const_iterator rit; 783 | 784 | std::map > pairs; 785 | std::map >::iterator pit; 786 | 787 | std::map > sums; // < sum vi, sum wi > 788 | std::map >::iterator sit; 789 | 790 | // In the current implementation, we suppose vec is not normalized 791 | 792 | //map expected; 793 | //map::iterator eit; 794 | 795 | for(vit = vec.begin(); vit != vec.end(); ++vit) 796 | { 797 | const WordId word_id = vit->first; 798 | const WordValue& qvalue = vit->second; 799 | 800 | const IFRow& row = m_ifile[word_id]; 801 | 802 | // IFRows are sorted in ascending entry_id order 803 | 804 | for(rit = row.begin(); rit != row.end(); ++rit) 805 | { 806 | const EntryId entry_id = rit->entry_id; 807 | const WordValue& dvalue = rit->word_weight; 808 | 809 | if((int)entry_id < max_id || max_id == -1) 810 | { 811 | // (v-w)^2/(v+w) - v - w = -4 vw/(v+w) 812 | // we move the 4 out 813 | double value = 0; 814 | if(qvalue + dvalue != 0.0) // words may have weight zero 815 | value = - qvalue * dvalue / (qvalue + dvalue); 816 | 817 | pit = pairs.lower_bound(entry_id); 818 | sit = sums.lower_bound(entry_id); 819 | //eit = expected.lower_bound(entry_id); 820 | if(pit != pairs.end() && !(pairs.key_comp()(entry_id, pit->first))) 821 | { 822 | pit->second.first += value; 823 | pit->second.second += 1; 824 | //eit->second += dvalue; 825 | sit->second.first += qvalue; 826 | sit->second.second += dvalue; 827 | } 828 | else 829 | { 830 | pairs.insert(pit, 831 | std::map >::value_type(entry_id, 832 | std::make_pair(value, 1) )); 833 | //expected.insert(eit, 834 | // map::value_type(entry_id, dvalue)); 835 | 836 | sums.insert(sit, 837 | std::map >::value_type(entry_id, 838 | std::make_pair(qvalue, dvalue) )); 839 | } 840 | } 841 | 842 | } // for each inverted row 843 | } // for each query word 844 | 845 | // move to vector 846 | ret.reserve(pairs.size()); 847 | sit = sums.begin(); 848 | for(pit = pairs.begin(); pit != pairs.end(); ++pit, ++sit) 849 | { 850 | if(pit->second.second >= MIN_COMMON_WORDS) 851 | { 852 | ret.push_back(Result(pit->first, pit->second.first)); 853 | ret.back().nWords = pit->second.second; 854 | ret.back().sumCommonVi = sit->second.first; 855 | ret.back().sumCommonWi = sit->second.second; 856 | ret.back().expectedChiScore = 857 | 2 * sit->second.second / (1 + sit->second.second); 858 | } 859 | 860 | //ret.push_back(Result(pit->first, pit->second)); 861 | } 862 | 863 | // resulting "scores" are now in [-2 best .. 0 worst] 864 | // we have to add +2 to the scores to obtain the chi square score 865 | 866 | // sort vector in ascending order of score 867 | std::sort(ret.begin(), ret.end()); 868 | // (ret is inverted now --the lower the better--) 869 | 870 | // cut vector 871 | if(max_results > 0 && (int)ret.size() > max_results) 872 | ret.resize(max_results); 873 | 874 | // complete and scale score to [0 worst .. 1 best] 875 | QueryResults::iterator qit; 876 | for(qit = ret.begin(); qit != ret.end(); qit++) 877 | { 878 | // this takes the 4 into account 879 | qit->Score = - 2. * qit->Score; // [0..1] 880 | 881 | qit->chiScore = qit->Score; 882 | } 883 | 884 | } 885 | 886 | // -------------------------------------------------------------------------- 887 | 888 | template 889 | void TemplatedDatabase::queryKL(const BowVector &vec, 890 | QueryResults &ret, int max_results, int max_id) const 891 | { 892 | BowVector::const_iterator vit; 893 | typename IFRow::const_iterator rit; 894 | 895 | std::map pairs; 896 | std::map::iterator pit; 897 | 898 | for(vit = vec.begin(); vit != vec.end(); ++vit) 899 | { 900 | const WordId word_id = vit->first; 901 | const WordValue& vi = vit->second; 902 | 903 | const IFRow& row = m_ifile[word_id]; 904 | 905 | // IFRows are sorted in ascending entry_id order 906 | 907 | for(rit = row.begin(); rit != row.end(); ++rit) 908 | { 909 | const EntryId entry_id = rit->entry_id; 910 | const WordValue& wi = rit->word_weight; 911 | 912 | if((int)entry_id < max_id || max_id == -1) 913 | { 914 | double value = 0; 915 | if(vi != 0 && wi != 0) value = vi * log(vi/wi); 916 | 917 | pit = pairs.lower_bound(entry_id); 918 | if(pit != pairs.end() && !(pairs.key_comp()(entry_id, pit->first))) 919 | { 920 | pit->second += value; 921 | } 922 | else 923 | { 924 | pairs.insert(pit, 925 | std::map::value_type(entry_id, value)); 926 | } 927 | } 928 | 929 | } // for each inverted row 930 | } // for each query word 931 | 932 | // resulting "scores" are now in [-X worst .. 0 best .. X worst] 933 | // but we cannot make sure which ones are better without calculating 934 | // the complete score 935 | 936 | // complete scores and move to vector 937 | ret.reserve(pairs.size()); 938 | for(pit = pairs.begin(); pit != pairs.end(); ++pit) 939 | { 940 | EntryId eid = pit->first; 941 | double value = 0.0; 942 | 943 | for(vit = vec.begin(); vit != vec.end(); ++vit) 944 | { 945 | const WordValue &vi = vit->second; 946 | const IFRow& row = m_ifile[vit->first]; 947 | 948 | if(vi != 0) 949 | { 950 | if(row.end() == find(row.begin(), row.end(), eid )) 951 | { 952 | value += vi * (log(vi) - GeneralScoring::LOG_EPS); 953 | } 954 | } 955 | } 956 | 957 | pit->second += value; 958 | 959 | // to vector 960 | ret.push_back(Result(pit->first, pit->second)); 961 | } 962 | 963 | // real scores are now in [0 best .. X worst] 964 | 965 | // sort vector in ascending order 966 | // (scores are inverted now --the lower the better--) 967 | std::sort(ret.begin(), ret.end()); 968 | 969 | // cut vector 970 | if(max_results > 0 && (int)ret.size() > max_results) 971 | ret.resize(max_results); 972 | 973 | // cannot scale scores 974 | 975 | } 976 | 977 | // -------------------------------------------------------------------------- 978 | 979 | template 980 | void TemplatedDatabase::queryBhattacharyya( 981 | const BowVector &vec, QueryResults &ret, int max_results, int max_id) const 982 | { 983 | BowVector::const_iterator vit; 984 | typename IFRow::const_iterator rit; 985 | 986 | //map pairs; 987 | //map::iterator pit; 988 | 989 | std::map > pairs; // > 990 | std::map >::iterator pit; 991 | 992 | for(vit = vec.begin(); vit != vec.end(); ++vit) 993 | { 994 | const WordId word_id = vit->first; 995 | const WordValue& qvalue = vit->second; 996 | 997 | const IFRow& row = m_ifile[word_id]; 998 | 999 | // IFRows are sorted in ascending entry_id order 1000 | 1001 | for(rit = row.begin(); rit != row.end(); ++rit) 1002 | { 1003 | const EntryId entry_id = rit->entry_id; 1004 | const WordValue& dvalue = rit->word_weight; 1005 | 1006 | if((int)entry_id < max_id || max_id == -1) 1007 | { 1008 | double value = sqrt(qvalue * dvalue); 1009 | 1010 | pit = pairs.lower_bound(entry_id); 1011 | if(pit != pairs.end() && !(pairs.key_comp()(entry_id, pit->first))) 1012 | { 1013 | pit->second.first += value; 1014 | pit->second.second += 1; 1015 | } 1016 | else 1017 | { 1018 | pairs.insert(pit, 1019 | std::map >::value_type(entry_id, 1020 | std::make_pair(value, 1))); 1021 | } 1022 | } 1023 | 1024 | } // for each inverted row 1025 | } // for each query word 1026 | 1027 | // move to vector 1028 | ret.reserve(pairs.size()); 1029 | for(pit = pairs.begin(); pit != pairs.end(); ++pit) 1030 | { 1031 | if(pit->second.second >= MIN_COMMON_WORDS) 1032 | { 1033 | ret.push_back(Result(pit->first, pit->second.first)); 1034 | ret.back().nWords = pit->second.second; 1035 | ret.back().bhatScore = pit->second.first; 1036 | } 1037 | } 1038 | 1039 | // scores are already in [0..1] 1040 | 1041 | // sort vector in descending order 1042 | std::sort(ret.begin(), ret.end(), Result::gt); 1043 | 1044 | // cut vector 1045 | if(max_results > 0 && (int)ret.size() > max_results) 1046 | ret.resize(max_results); 1047 | 1048 | } 1049 | 1050 | // --------------------------------------------------------------------------- 1051 | 1052 | template 1053 | void TemplatedDatabase::queryDotProduct( 1054 | const BowVector &vec, QueryResults &ret, int max_results, int max_id) const 1055 | { 1056 | BowVector::const_iterator vit; 1057 | typename IFRow::const_iterator rit; 1058 | 1059 | std::map pairs; 1060 | std::map::iterator pit; 1061 | 1062 | for(vit = vec.begin(); vit != vec.end(); ++vit) 1063 | { 1064 | const WordId word_id = vit->first; 1065 | const WordValue& qvalue = vit->second; 1066 | 1067 | const IFRow& row = m_ifile[word_id]; 1068 | 1069 | // IFRows are sorted in ascending entry_id order 1070 | 1071 | for(rit = row.begin(); rit != row.end(); ++rit) 1072 | { 1073 | const EntryId entry_id = rit->entry_id; 1074 | const WordValue& dvalue = rit->word_weight; 1075 | 1076 | if((int)entry_id < max_id || max_id == -1) 1077 | { 1078 | double value; 1079 | if(this->m_voc->getWeightingType() == BINARY) 1080 | value = 1; 1081 | else 1082 | value = qvalue * dvalue; 1083 | 1084 | pit = pairs.lower_bound(entry_id); 1085 | if(pit != pairs.end() && !(pairs.key_comp()(entry_id, pit->first))) 1086 | { 1087 | pit->second += value; 1088 | } 1089 | else 1090 | { 1091 | pairs.insert(pit, 1092 | std::map::value_type(entry_id, value)); 1093 | } 1094 | } 1095 | 1096 | } // for each inverted row 1097 | } // for each query word 1098 | 1099 | // move to vector 1100 | ret.reserve(pairs.size()); 1101 | for(pit = pairs.begin(); pit != pairs.end(); ++pit) 1102 | { 1103 | ret.push_back(Result(pit->first, pit->second)); 1104 | } 1105 | 1106 | // scores are the greater the better 1107 | 1108 | // sort vector in descending order 1109 | std::sort(ret.begin(), ret.end(), Result::gt); 1110 | 1111 | // cut vector 1112 | if(max_results > 0 && (int)ret.size() > max_results) 1113 | ret.resize(max_results); 1114 | 1115 | // these scores cannot be scaled 1116 | } 1117 | 1118 | // --------------------------------------------------------------------------- 1119 | 1120 | template 1121 | const FeatureVector& TemplatedDatabase::retrieveFeatures 1122 | (EntryId id) const 1123 | { 1124 | assert(id < size()); 1125 | return m_dfile[id]; 1126 | } 1127 | 1128 | // -------------------------------------------------------------------------- 1129 | 1130 | template 1131 | void TemplatedDatabase::save(const std::string &filename) const 1132 | { 1133 | cv::FileStorage fs(filename.c_str(), cv::FileStorage::WRITE); 1134 | if(!fs.isOpened()) throw std::string("Could not open file ") + filename; 1135 | 1136 | save(fs); 1137 | } 1138 | 1139 | // -------------------------------------------------------------------------- 1140 | 1141 | template 1142 | void TemplatedDatabase::save(cv::FileStorage &fs, 1143 | const std::string &name) const 1144 | { 1145 | // Format YAML: 1146 | // vocabulary { ... see TemplatedVocabulary::save } 1147 | // database 1148 | // { 1149 | // nEntries: 1150 | // usingDI: 1151 | // diLevels: 1152 | // invertedIndex 1153 | // [ 1154 | // [ 1155 | // { 1156 | // imageId: 1157 | // weight: 1158 | // } 1159 | // ] 1160 | // ] 1161 | // directIndex 1162 | // [ 1163 | // [ 1164 | // { 1165 | // nodeId: 1166 | // features: [ ] 1167 | // } 1168 | // ] 1169 | // ] 1170 | 1171 | // invertedIndex[i] is for the i-th word 1172 | // directIndex[i] is for the i-th entry 1173 | // directIndex may be empty if not using direct index 1174 | // 1175 | // imageId's and nodeId's must be stored in ascending order 1176 | // (according to the construction of the indexes) 1177 | 1178 | m_voc->save(fs); 1179 | 1180 | fs << name << "{"; 1181 | 1182 | fs << "nEntries" << m_nentries; 1183 | fs << "usingDI" << (m_use_di ? 1 : 0); 1184 | fs << "diLevels" << m_dilevels; 1185 | 1186 | fs << "invertedIndex" << "["; 1187 | 1188 | typename InvertedFile::const_iterator iit; 1189 | typename IFRow::const_iterator irit; 1190 | for(iit = m_ifile.begin(); iit != m_ifile.end(); ++iit) 1191 | { 1192 | fs << "["; // word of IF 1193 | for(irit = iit->begin(); irit != iit->end(); ++irit) 1194 | { 1195 | fs << "{:" 1196 | << "imageId" << (int)irit->entry_id 1197 | << "weight" << irit->word_weight 1198 | << "}"; 1199 | } 1200 | fs << "]"; // word of IF 1201 | } 1202 | 1203 | fs << "]"; // invertedIndex 1204 | 1205 | fs << "directIndex" << "["; 1206 | 1207 | typename DirectFile::const_iterator dit; 1208 | typename FeatureVector::const_iterator drit; 1209 | for(dit = m_dfile.begin(); dit != m_dfile.end(); ++dit) 1210 | { 1211 | fs << "["; // entry of DF 1212 | 1213 | for(drit = dit->begin(); drit != dit->end(); ++drit) 1214 | { 1215 | NodeId nid = drit->first; 1216 | const std::vector& features = drit->second; 1217 | 1218 | // save info of last_nid 1219 | fs << "{"; 1220 | fs << "nodeId" << (int)nid; 1221 | // msvc++ 2010 with opencv 2.3.1 does not allow FileStorage::operator<< 1222 | // with vectors of unsigned int 1223 | fs << "features" << "[" 1224 | << *(const std::vector*)(&features) << "]"; 1225 | fs << "}"; 1226 | } 1227 | 1228 | fs << "]"; // entry of DF 1229 | } 1230 | 1231 | fs << "]"; // directIndex 1232 | 1233 | fs << "}"; // database 1234 | } 1235 | 1236 | // -------------------------------------------------------------------------- 1237 | 1238 | template 1239 | void TemplatedDatabase::load(const std::string &filename) 1240 | { 1241 | cv::FileStorage fs(filename.c_str(), cv::FileStorage::READ); 1242 | if(!fs.isOpened()) throw std::string("Could not open file ") + filename; 1243 | 1244 | load(fs); 1245 | } 1246 | 1247 | // -------------------------------------------------------------------------- 1248 | 1249 | template 1250 | void TemplatedDatabase::load(const cv::FileStorage &fs, 1251 | const std::string &name) 1252 | { 1253 | // load voc first 1254 | // subclasses must instantiate m_voc before calling this ::load 1255 | if(!m_voc) m_voc = new TemplatedVocabulary; 1256 | 1257 | m_voc->load(fs); 1258 | 1259 | // load database now 1260 | clear(); // resizes inverted file 1261 | 1262 | cv::FileNode fdb = fs[name]; 1263 | 1264 | m_nentries = (int)fdb["nEntries"]; 1265 | m_use_di = (int)fdb["usingDI"] != 0; 1266 | m_dilevels = (int)fdb["diLevels"]; 1267 | 1268 | cv::FileNode fn = fdb["invertedIndex"]; 1269 | for(WordId wid = 0; wid < fn.size(); ++wid) 1270 | { 1271 | cv::FileNode fw = fn[wid]; 1272 | 1273 | for(unsigned int i = 0; i < fw.size(); ++i) 1274 | { 1275 | EntryId eid = (int)fw[i]["imageId"]; 1276 | WordValue v = fw[i]["weight"]; 1277 | 1278 | m_ifile[wid].push_back(IFPair(eid, v)); 1279 | } 1280 | } 1281 | 1282 | if(m_use_di) 1283 | { 1284 | fn = fdb["directIndex"]; 1285 | 1286 | m_dfile.resize(fn.size()); 1287 | assert(m_nentries == (int)fn.size()); 1288 | 1289 | FeatureVector::iterator dit; 1290 | for(EntryId eid = 0; eid < fn.size(); ++eid) 1291 | { 1292 | cv::FileNode fe = fn[eid]; 1293 | 1294 | m_dfile[eid].clear(); 1295 | for(unsigned int i = 0; i < fe.size(); ++i) 1296 | { 1297 | NodeId nid = (int)fe[i]["nodeId"]; 1298 | 1299 | dit = m_dfile[eid].insert(m_dfile[eid].end(), 1300 | make_pair(nid, std::vector() )); 1301 | 1302 | // this failed to compile with some opencv versions (2.3.1) 1303 | //fe[i]["features"] >> dit->second; 1304 | 1305 | // this was ok until OpenCV 2.4.1 1306 | //std::vector aux; 1307 | //fe[i]["features"] >> aux; // OpenCV < 2.4.1 1308 | //dit->second.resize(aux.size()); 1309 | //std::copy(aux.begin(), aux.end(), dit->second.begin()); 1310 | 1311 | cv::FileNode ff = fe[i]["features"][0]; 1312 | dit->second.reserve(ff.size()); 1313 | 1314 | cv::FileNodeIterator ffit; 1315 | for(ffit = ff.begin(); ffit != ff.end(); ++ffit) 1316 | { 1317 | dit->second.push_back((int)*ffit); 1318 | } 1319 | } 1320 | } // for each entry 1321 | } // if use_id 1322 | 1323 | } 1324 | 1325 | // -------------------------------------------------------------------------- 1326 | 1327 | /** 1328 | * Writes printable information of the database 1329 | * @param os stream to write to 1330 | * @param db 1331 | */ 1332 | template 1333 | std::ostream& operator<<(std::ostream &os, 1334 | const TemplatedDatabase &db) 1335 | { 1336 | os << "Database: Entries = " << db.size() << ", " 1337 | "Using direct index = " << (db.usingDirectIndex() ? "yes" : "no"); 1338 | 1339 | if(db.usingDirectIndex()) 1340 | os << ", Direct index levels = " << db.getDirectIndexLevels(); 1341 | 1342 | os << ". " << *db.getVocabulary(); 1343 | return os; 1344 | } 1345 | 1346 | // -------------------------------------------------------------------------- 1347 | 1348 | } // namespace DBoW2 1349 | 1350 | #endif 1351 | -------------------------------------------------------------------------------- /include/DBoW2/TemplatedVocabulary.h: -------------------------------------------------------------------------------- 1 | /** 2 | * File: TemplatedVocabulary.h 3 | * Date: February 2011 4 | * Author: Dorian Galvez-Lopez 5 | * Description: templated vocabulary 6 | * License: see the LICENSE.txt file 7 | * 8 | */ 9 | 10 | #ifndef __D_T_TEMPLATED_VOCABULARY__ 11 | #define __D_T_TEMPLATED_VOCABULARY__ 12 | 13 | #include 14 | 15 | #include 16 | #include 17 | #include 18 | #include 19 | #include 20 | #include 21 | 22 | #include "FeatureVector.h" 23 | #include "BowVector.h" 24 | #include "ScoringObject.h" 25 | 26 | #include 27 | 28 | using namespace std; 29 | 30 | namespace DBoW2 { 31 | 32 | /// @param TDescriptor class of descriptor 33 | /// @param F class of descriptor functions 34 | template 35 | /// Generic Vocabulary 36 | class TemplatedVocabulary 37 | { 38 | public: 39 | 40 | /** 41 | * Initiates an empty vocabulary 42 | * @param k branching factor 43 | * @param L depth levels 44 | * @param weighting weighting type 45 | * @param scoring scoring type 46 | */ 47 | TemplatedVocabulary(int k = 10, int L = 5, 48 | WeightingType weighting = TF_IDF, ScoringType scoring = L1_NORM); 49 | 50 | /** 51 | * Creates the vocabulary by loading a file 52 | * @param filename 53 | */ 54 | TemplatedVocabulary(const std::string &filename); 55 | 56 | /** 57 | * Creates the vocabulary by loading a file 58 | * @param filename 59 | */ 60 | TemplatedVocabulary(const char *filename); 61 | 62 | /** 63 | * Copy constructor 64 | * @param voc 65 | */ 66 | TemplatedVocabulary(const TemplatedVocabulary &voc); 67 | 68 | /** 69 | * Destructor 70 | */ 71 | virtual ~TemplatedVocabulary(); 72 | 73 | /** 74 | * Assigns the given vocabulary to this by copying its data and removing 75 | * all the data contained by this vocabulary before 76 | * @param voc 77 | * @return reference to this vocabulary 78 | */ 79 | TemplatedVocabulary& operator=( 80 | const TemplatedVocabulary &voc); 81 | 82 | /** 83 | * Creates a vocabulary from the training features with the already 84 | * defined parameters 85 | * @param training_features 86 | */ 87 | virtual void create 88 | (const std::vector > &training_features); 89 | 90 | /** 91 | * Creates a vocabulary from the training features, setting the branching 92 | * factor and the depth levels of the tree 93 | * @param training_features 94 | * @param k branching factor 95 | * @param L depth levels 96 | */ 97 | virtual void create 98 | (const std::vector > &training_features, 99 | int k, int L); 100 | 101 | /** 102 | * Creates a vocabulary from the training features, setting the branching 103 | * factor nad the depth levels of the tree, and the weighting and scoring 104 | * schemes 105 | */ 106 | virtual void create 107 | (const std::vector > &training_features, 108 | int k, int L, WeightingType weighting, ScoringType scoring); 109 | 110 | /** 111 | * Returns the number of words in the vocabulary 112 | * @return number of words 113 | */ 114 | virtual inline unsigned int size() const; 115 | 116 | /** 117 | * Returns whether the vocabulary is empty (i.e. it has not been trained) 118 | * @return true iff the vocabulary is empty 119 | */ 120 | virtual inline bool empty() const; 121 | 122 | /** 123 | * Transforms a set of descriptores into a bow vector 124 | * @param features 125 | * @param v (out) bow vector of weighted words 126 | */ 127 | virtual void transform(const std::vector& features, BowVector &v) 128 | const; 129 | 130 | /** 131 | * Transform a set of descriptors into a bow vector and a feature vector 132 | * @param features 133 | * @param v (out) bow vector 134 | * @param fv (out) feature vector of nodes and feature indexes 135 | * @param levelsup levels to go up the vocabulary tree to get the node index 136 | */ 137 | virtual void transform(const std::vector& features, 138 | BowVector &v, FeatureVector &fv, int levelsup) const; 139 | 140 | /** 141 | * Transforms a single feature into a word (without weight) 142 | * @param feature 143 | * @return word id 144 | */ 145 | virtual WordId transform(const TDescriptor& feature) const; 146 | 147 | /** 148 | * Returns the score of two vectors 149 | * @param a vector 150 | * @param b vector 151 | * @return score between vectors 152 | * @note the vectors must be already sorted and normalized if necessary 153 | */ 154 | inline double score(const BowVector &a, const BowVector &b) const; 155 | 156 | /** 157 | * Returns the id of the node that is "levelsup" levels from the word given 158 | * @param wid word id 159 | * @param levelsup 0..L 160 | * @return node id. if levelsup is 0, returns the node id associated to the 161 | * word id 162 | */ 163 | virtual NodeId getParentNode(WordId wid, int levelsup) const; 164 | 165 | /** 166 | * Returns the ids of all the words that are under the given node id, 167 | * by traversing any of the branches that goes down from the node 168 | * @param nid starting node id 169 | * @param words ids of words 170 | */ 171 | void getWordsFromNode(NodeId nid, std::vector &words) const; 172 | 173 | /** 174 | * Returns the branching factor of the tree (k) 175 | * @return k 176 | */ 177 | inline int getBranchingFactor() const { return m_k; } 178 | 179 | /** 180 | * Returns the depth levels of the tree (L) 181 | * @return L 182 | */ 183 | inline int getDepthLevels() const { return m_L; } 184 | 185 | /** 186 | * Returns the real depth levels of the tree on average 187 | * @return average of depth levels of leaves 188 | */ 189 | float getEffectiveLevels() const; 190 | 191 | /** 192 | * Returns the descriptor of a word 193 | * @param wid word id 194 | * @return descriptor 195 | */ 196 | virtual inline TDescriptor getWord(WordId wid) const; 197 | 198 | /** 199 | * Returns the weight of a word 200 | * @param wid word id 201 | * @return weight 202 | */ 203 | virtual inline WordValue getWordWeight(WordId wid) const; 204 | 205 | /** 206 | * Returns the weighting method 207 | * @return weighting method 208 | */ 209 | inline WeightingType getWeightingType() const { return m_weighting; } 210 | 211 | /** 212 | * Returns the scoring method 213 | * @return scoring method 214 | */ 215 | inline ScoringType getScoringType() const { return m_scoring; } 216 | 217 | /** 218 | * Changes the weighting method 219 | * @param type new weighting type 220 | */ 221 | inline void setWeightingType(WeightingType type); 222 | 223 | /** 224 | * Changes the scoring method 225 | * @param type new scoring type 226 | */ 227 | void setScoringType(ScoringType type); 228 | 229 | /** 230 | * Saves the vocabulary into a file 231 | * @param filename 232 | */ 233 | void save(const std::string &filename) const; 234 | 235 | void saveToTextFile(const std::string &filename) const; 236 | 237 | /** 238 | * Loads the vocabulary from a file 239 | * @param filename 240 | */ 241 | void load(const std::string &filename); 242 | 243 | /** 244 | * Saves the vocabulary to a file storage structure 245 | * @param fn node in file storage 246 | */ 247 | virtual void save(cv::FileStorage &fs, 248 | const std::string &name = "vocabulary") const; 249 | 250 | /** 251 | * Loads the vocabulary from a file storage node 252 | * @param fn first node 253 | * @param subname name of the child node of fn where the tree is stored. 254 | * If not given, the fn node is used instead 255 | */ 256 | virtual void load(const cv::FileStorage &fs, 257 | const std::string &name = "vocabulary"); 258 | 259 | /** 260 | * Stops those words whose weight is below minWeight. 261 | * Words are stopped by setting their weight to 0. There are not returned 262 | * later when transforming image features into vectors. 263 | * Note that when using IDF or TF_IDF, the weight is the idf part, which 264 | * is equivalent to -log(f), where f is the frequency of the word 265 | * (f = Ni/N, Ni: number of training images where the word is present, 266 | * N: number of training images). 267 | * Note that the old weight is forgotten, and subsequent calls to this 268 | * function with a lower minWeight have no effect. 269 | * @return number of words stopped now 270 | */ 271 | virtual int stopWords(double minWeight); 272 | 273 | protected: 274 | 275 | /// Pointer to descriptor 276 | typedef const TDescriptor *pDescriptor; 277 | 278 | /// Tree node 279 | struct Node 280 | { 281 | /// Node id 282 | NodeId id; 283 | /// Weight if the node is a word 284 | WordValue weight; 285 | /// Children 286 | std::vector children; 287 | /// Parent node (undefined in case of root) 288 | NodeId parent; 289 | /// Node descriptor 290 | TDescriptor descriptor; 291 | 292 | /// Word id if the node is a word 293 | WordId word_id; 294 | 295 | /** 296 | * Empty constructor 297 | */ 298 | Node(): id(0), weight(0), parent(0), word_id(0){} 299 | 300 | /** 301 | * Constructor 302 | * @param _id node id 303 | */ 304 | Node(NodeId _id): id(_id), weight(0), parent(0), word_id(0){} 305 | 306 | /** 307 | * Returns whether the node is a leaf node 308 | * @return true iff the node is a leaf 309 | */ 310 | inline bool isLeaf() const { return children.empty(); } 311 | }; 312 | 313 | protected: 314 | 315 | /** 316 | * Creates an instance of the scoring object accoring to m_scoring 317 | */ 318 | void createScoringObject(); 319 | 320 | /** 321 | * Returns a set of pointers to descriptores 322 | * @param training_features all the features 323 | * @param features (out) pointers to the training features 324 | */ 325 | void getFeatures( 326 | const std::vector > &training_features, 327 | std::vector &features) const; 328 | 329 | /** 330 | * Returns the word id associated to a feature 331 | * @param feature 332 | * @param id (out) word id 333 | * @param weight (out) word weight 334 | * @param nid (out) if given, id of the node "levelsup" levels up 335 | * @param levelsup 336 | */ 337 | virtual void transform(const TDescriptor &feature, 338 | WordId &id, WordValue &weight, NodeId* nid = NULL, int levelsup = 0) const; 339 | 340 | /** 341 | * Returns the word id associated to a feature 342 | * @param feature 343 | * @param id (out) word id 344 | */ 345 | virtual void transform(const TDescriptor &feature, WordId &id) const; 346 | 347 | /** 348 | * Creates a level in the tree, under the parent, by running kmeans with 349 | * a descriptor set, and recursively creates the subsequent levels too 350 | * @param parent_id id of parent node 351 | * @param descriptors descriptors to run the kmeans on 352 | * @param current_level current level in the tree 353 | */ 354 | void HKmeansStep(NodeId parent_id, const std::vector &descriptors, 355 | int current_level); 356 | 357 | /** 358 | * Creates k clusters from the given descriptors with some seeding algorithm. 359 | * @note In this class, kmeans++ is used, but this function should be 360 | * overriden by inherited classes. 361 | */ 362 | virtual void initiateClusters(const std::vector &descriptors, 363 | std::vector &clusters) const; 364 | 365 | /** 366 | * Creates k clusters from the given descriptor sets by running the 367 | * initial step of kmeans++ 368 | * @param descriptors 369 | * @param clusters resulting clusters 370 | */ 371 | void initiateClustersKMpp(const std::vector &descriptors, 372 | std::vector &clusters) const; 373 | 374 | /** 375 | * Create the words of the vocabulary once the tree has been built 376 | */ 377 | void createWords(); 378 | 379 | /** 380 | * Sets the weights of the nodes of tree according to the given features. 381 | * Before calling this function, the nodes and the words must be already 382 | * created (by calling HKmeansStep and createWords) 383 | * @param features 384 | */ 385 | void setNodeWeights(const std::vector > &features); 386 | 387 | protected: 388 | 389 | /// Branching factor 390 | int m_k; 391 | 392 | /// Depth levels 393 | int m_L; 394 | 395 | /// Weighting method 396 | WeightingType m_weighting; 397 | 398 | /// Scoring method 399 | ScoringType m_scoring; 400 | 401 | /// Object for computing scores 402 | GeneralScoring* m_scoring_object; 403 | 404 | /// Tree nodes 405 | std::vector m_nodes; 406 | 407 | /// Words of the vocabulary (tree leaves) 408 | /// this condition holds: m_words[wid]->word_id == wid 409 | std::vector m_words; 410 | 411 | }; 412 | 413 | // -------------------------------------------------------------------------- 414 | 415 | template 416 | TemplatedVocabulary::TemplatedVocabulary 417 | (int k, int L, WeightingType weighting, ScoringType scoring) 418 | : m_k(k), m_L(L), m_weighting(weighting), m_scoring(scoring), 419 | m_scoring_object(NULL) 420 | { 421 | createScoringObject(); 422 | } 423 | 424 | // -------------------------------------------------------------------------- 425 | 426 | template 427 | TemplatedVocabulary::TemplatedVocabulary 428 | (const std::string &filename): m_scoring_object(NULL) 429 | { 430 | load(filename); 431 | } 432 | 433 | // -------------------------------------------------------------------------- 434 | 435 | template 436 | TemplatedVocabulary::TemplatedVocabulary 437 | (const char *filename): m_scoring_object(NULL) 438 | { 439 | load(filename); 440 | } 441 | 442 | // -------------------------------------------------------------------------- 443 | 444 | template 445 | void TemplatedVocabulary::createScoringObject() 446 | { 447 | delete m_scoring_object; 448 | m_scoring_object = NULL; 449 | 450 | switch(m_scoring) 451 | { 452 | case L1_NORM: 453 | m_scoring_object = new L1Scoring; 454 | break; 455 | 456 | case L2_NORM: 457 | m_scoring_object = new L2Scoring; 458 | break; 459 | 460 | case CHI_SQUARE: 461 | m_scoring_object = new ChiSquareScoring; 462 | break; 463 | 464 | case KL: 465 | m_scoring_object = new KLScoring; 466 | break; 467 | 468 | case BHATTACHARYYA: 469 | m_scoring_object = new BhattacharyyaScoring; 470 | break; 471 | 472 | case DOT_PRODUCT: 473 | m_scoring_object = new DotProductScoring; 474 | break; 475 | 476 | } 477 | } 478 | 479 | // -------------------------------------------------------------------------- 480 | 481 | template 482 | void TemplatedVocabulary::setScoringType(ScoringType type) 483 | { 484 | m_scoring = type; 485 | createScoringObject(); 486 | } 487 | 488 | // -------------------------------------------------------------------------- 489 | 490 | template 491 | void TemplatedVocabulary::setWeightingType(WeightingType type) 492 | { 493 | this->m_weighting = type; 494 | } 495 | 496 | // -------------------------------------------------------------------------- 497 | 498 | template 499 | TemplatedVocabulary::TemplatedVocabulary( 500 | const TemplatedVocabulary &voc) 501 | : m_scoring_object(NULL) 502 | { 503 | *this = voc; 504 | } 505 | 506 | // -------------------------------------------------------------------------- 507 | 508 | template 509 | TemplatedVocabulary::~TemplatedVocabulary() 510 | { 511 | delete m_scoring_object; 512 | } 513 | 514 | // -------------------------------------------------------------------------- 515 | 516 | template 517 | TemplatedVocabulary& 518 | TemplatedVocabulary::operator= 519 | (const TemplatedVocabulary &voc) 520 | { 521 | this->m_k = voc.m_k; 522 | this->m_L = voc.m_L; 523 | this->m_scoring = voc.m_scoring; 524 | this->m_weighting = voc.m_weighting; 525 | 526 | this->createScoringObject(); 527 | 528 | this->m_nodes.clear(); 529 | this->m_words.clear(); 530 | 531 | this->m_nodes = voc.m_nodes; 532 | this->createWords(); 533 | 534 | return *this; 535 | } 536 | 537 | // -------------------------------------------------------------------------- 538 | 539 | template 540 | void TemplatedVocabulary::create( 541 | const std::vector > &training_features) 542 | { 543 | m_nodes.clear(); 544 | m_words.clear(); 545 | 546 | // expected_nodes = Sum_{i=0..L} ( k^i ) 547 | int expected_nodes = 548 | (int)((pow((double)m_k, (double)m_L + 1) - 1)/(m_k - 1)); 549 | 550 | m_nodes.reserve(expected_nodes); // avoid allocations when creating the tree 551 | 552 | 553 | std::vector features; 554 | getFeatures(training_features, features); 555 | 556 | 557 | // create root 558 | m_nodes.push_back(Node(0)); // root 559 | 560 | // create the tree 561 | HKmeansStep(0, features, 1); 562 | 563 | // create the words 564 | createWords(); 565 | 566 | // and set the weight of each node of the tree 567 | setNodeWeights(training_features); 568 | 569 | } 570 | 571 | // -------------------------------------------------------------------------- 572 | 573 | template 574 | void TemplatedVocabulary::create( 575 | const std::vector > &training_features, 576 | int k, int L) 577 | { 578 | m_k = k; 579 | m_L = L; 580 | 581 | create(training_features); 582 | } 583 | 584 | // -------------------------------------------------------------------------- 585 | 586 | template 587 | void TemplatedVocabulary::create( 588 | const std::vector > &training_features, 589 | int k, int L, WeightingType weighting, ScoringType scoring) 590 | { 591 | m_k = k; 592 | m_L = L; 593 | m_weighting = weighting; 594 | m_scoring = scoring; 595 | createScoringObject(); 596 | 597 | create(training_features); 598 | } 599 | 600 | // -------------------------------------------------------------------------- 601 | 602 | template 603 | void TemplatedVocabulary::getFeatures( 604 | const std::vector > &training_features, 605 | std::vector &features) const 606 | { 607 | features.resize(0); 608 | 609 | typename std::vector >::const_iterator vvit; 610 | typename std::vector::const_iterator vit; 611 | for(vvit = training_features.begin(); vvit != training_features.end(); ++vvit) 612 | { 613 | features.reserve(features.size() + vvit->size()); 614 | for(vit = vvit->begin(); vit != vvit->end(); ++vit) 615 | { 616 | features.push_back(&(*vit)); 617 | } 618 | } 619 | } 620 | 621 | // -------------------------------------------------------------------------- 622 | 623 | template 624 | void TemplatedVocabulary::HKmeansStep(NodeId parent_id, 625 | const std::vector &descriptors, int current_level) 626 | { 627 | if(descriptors.empty()) return; 628 | 629 | // features associated to each cluster 630 | std::vector clusters; 631 | std::vector > groups; // groups[i] = [j1, j2, ...] 632 | // j1, j2, ... indices of descriptors associated to cluster i 633 | 634 | clusters.reserve(m_k); 635 | groups.reserve(m_k); 636 | 637 | //const int msizes[] = { m_k, descriptors.size() }; 638 | //cv::SparseMat assoc(2, msizes, CV_8U); 639 | //cv::SparseMat last_assoc(2, msizes, CV_8U); 640 | //// assoc.row(cluster_idx).col(descriptor_idx) = 1 iif associated 641 | 642 | if((int)descriptors.size() <= m_k) 643 | { 644 | // trivial case: one cluster per feature 645 | groups.resize(descriptors.size()); 646 | 647 | for(unsigned int i = 0; i < descriptors.size(); i++) 648 | { 649 | groups[i].push_back(i); 650 | clusters.push_back(*descriptors[i]); 651 | } 652 | } 653 | else 654 | { 655 | // select clusters and groups with kmeans 656 | 657 | bool first_time = true; 658 | bool goon = true; 659 | 660 | // to check if clusters move after iterations 661 | std::vector last_association, current_association; 662 | 663 | while(goon) 664 | { 665 | // 1. Calculate clusters 666 | 667 | if(first_time) 668 | { 669 | // random sample 670 | initiateClusters(descriptors, clusters); 671 | } 672 | else 673 | { 674 | // calculate cluster centres 675 | 676 | for(unsigned int c = 0; c < clusters.size(); ++c) 677 | { 678 | std::vector cluster_descriptors; 679 | cluster_descriptors.reserve(groups[c].size()); 680 | 681 | /* 682 | for(unsigned int d = 0; d < descriptors.size(); ++d) 683 | { 684 | if( assoc.find(c, d) ) 685 | { 686 | cluster_descriptors.push_back(descriptors[d]); 687 | } 688 | } 689 | */ 690 | 691 | std::vector::const_iterator vit; 692 | for(vit = groups[c].begin(); vit != groups[c].end(); ++vit) 693 | { 694 | cluster_descriptors.push_back(descriptors[*vit]); 695 | } 696 | 697 | 698 | F::meanValue(cluster_descriptors, clusters[c]); 699 | } 700 | 701 | } // if(!first_time) 702 | 703 | // 2. Associate features with clusters 704 | 705 | // calculate distances to cluster centers 706 | groups.clear(); 707 | groups.resize(clusters.size(), std::vector()); 708 | current_association.resize(descriptors.size()); 709 | 710 | //assoc.clear(); 711 | 712 | typename std::vector::const_iterator fit; 713 | //unsigned int d = 0; 714 | for(fit = descriptors.begin(); fit != descriptors.end(); ++fit)//, ++d) 715 | { 716 | double best_dist = F::distance(*(*fit), clusters[0]); 717 | unsigned int icluster = 0; 718 | 719 | for(unsigned int c = 1; c < clusters.size(); ++c) 720 | { 721 | double dist = F::distance(*(*fit), clusters[c]); 722 | if(dist < best_dist) 723 | { 724 | best_dist = dist; 725 | icluster = c; 726 | } 727 | } 728 | 729 | //assoc.ref(icluster, d) = 1; 730 | 731 | groups[icluster].push_back(fit - descriptors.begin()); 732 | current_association[ fit - descriptors.begin() ] = icluster; 733 | } 734 | 735 | // kmeans++ ensures all the clusters has any feature associated with them 736 | 737 | // 3. check convergence 738 | if(first_time) 739 | { 740 | first_time = false; 741 | } 742 | else 743 | { 744 | //goon = !eqUChar(last_assoc, assoc); 745 | 746 | goon = false; 747 | for(unsigned int i = 0; i < current_association.size(); i++) 748 | { 749 | if(current_association[i] != last_association[i]){ 750 | goon = true; 751 | break; 752 | } 753 | } 754 | } 755 | 756 | if(goon) 757 | { 758 | // copy last feature-cluster association 759 | last_association = current_association; 760 | //last_assoc = assoc.clone(); 761 | } 762 | 763 | } // while(goon) 764 | 765 | } // if must run kmeans 766 | 767 | // create nodes 768 | for(unsigned int i = 0; i < clusters.size(); ++i) 769 | { 770 | NodeId id = m_nodes.size(); 771 | m_nodes.push_back(Node(id)); 772 | m_nodes.back().descriptor = clusters[i]; 773 | m_nodes.back().parent = parent_id; 774 | m_nodes[parent_id].children.push_back(id); 775 | } 776 | 777 | // go on with the next level 778 | if(current_level < m_L) 779 | { 780 | // iterate again with the resulting clusters 781 | const std::vector &children_ids = m_nodes[parent_id].children; 782 | for(unsigned int i = 0; i < clusters.size(); ++i) 783 | { 784 | NodeId id = children_ids[i]; 785 | 786 | std::vector child_features; 787 | child_features.reserve(groups[i].size()); 788 | 789 | std::vector::const_iterator vit; 790 | for(vit = groups[i].begin(); vit != groups[i].end(); ++vit) 791 | { 792 | child_features.push_back(descriptors[*vit]); 793 | } 794 | 795 | if(child_features.size() > 1) 796 | { 797 | HKmeansStep(id, child_features, current_level + 1); 798 | } 799 | } 800 | } 801 | } 802 | 803 | // -------------------------------------------------------------------------- 804 | 805 | template 806 | void TemplatedVocabulary::initiateClusters 807 | (const std::vector &descriptors, 808 | std::vector &clusters) const 809 | { 810 | initiateClustersKMpp(descriptors, clusters); 811 | } 812 | 813 | // -------------------------------------------------------------------------- 814 | 815 | template 816 | void TemplatedVocabulary::initiateClustersKMpp( 817 | const std::vector &pfeatures, 818 | std::vector &clusters) const 819 | { 820 | // Implements kmeans++ seeding algorithm 821 | // Algorithm: 822 | // 1. Choose one center uniformly at random from among the data points. 823 | // 2. For each data point x, compute D(x), the distance between x and the nearest 824 | // center that has already been chosen. 825 | // 3. Add one new data point as a center. Each point x is chosen with probability 826 | // proportional to D(x)^2. 827 | // 4. Repeat Steps 2 and 3 until k centers have been chosen. 828 | // 5. Now that the initial centers have been chosen, proceed using standard k-means 829 | // clustering. 830 | 831 | DUtils::Random::SeedRandOnce(); 832 | 833 | clusters.resize(0); 834 | clusters.reserve(m_k); 835 | std::vector min_dists(pfeatures.size(), std::numeric_limits::max()); 836 | 837 | // 1. 838 | 839 | int ifeature = DUtils::Random::RandomInt(0, pfeatures.size()-1); 840 | 841 | // create first cluster 842 | clusters.push_back(*pfeatures[ifeature]); 843 | 844 | // compute the initial distances 845 | typename std::vector::const_iterator fit; 846 | std::vector::iterator dit; 847 | dit = min_dists.begin(); 848 | for(fit = pfeatures.begin(); fit != pfeatures.end(); ++fit, ++dit) 849 | { 850 | *dit = F::distance(*(*fit), clusters.back()); 851 | } 852 | 853 | while((int)clusters.size() < m_k) 854 | { 855 | // 2. 856 | dit = min_dists.begin(); 857 | for(fit = pfeatures.begin(); fit != pfeatures.end(); ++fit, ++dit) 858 | { 859 | if(*dit > 0) 860 | { 861 | double dist = F::distance(*(*fit), clusters.back()); 862 | if(dist < *dit) *dit = dist; 863 | } 864 | } 865 | 866 | // 3. 867 | double dist_sum = std::accumulate(min_dists.begin(), min_dists.end(), 0.0); 868 | 869 | if(dist_sum > 0) 870 | { 871 | double cut_d; 872 | do 873 | { 874 | cut_d = DUtils::Random::RandomValue(0, dist_sum); 875 | } while(cut_d == 0.0); 876 | 877 | double d_up_now = 0; 878 | for(dit = min_dists.begin(); dit != min_dists.end(); ++dit) 879 | { 880 | d_up_now += *dit; 881 | if(d_up_now >= cut_d) break; 882 | } 883 | 884 | if(dit == min_dists.end()) 885 | ifeature = pfeatures.size()-1; 886 | else 887 | ifeature = dit - min_dists.begin(); 888 | 889 | clusters.push_back(*pfeatures[ifeature]); 890 | 891 | } // if dist_sum > 0 892 | else 893 | break; 894 | 895 | } // while(used_clusters < m_k) 896 | 897 | } 898 | 899 | // -------------------------------------------------------------------------- 900 | 901 | template 902 | void TemplatedVocabulary::createWords() 903 | { 904 | m_words.resize(0); 905 | 906 | if(!m_nodes.empty()) 907 | { 908 | m_words.reserve( (int)pow((double)m_k, (double)m_L) ); 909 | 910 | typename std::vector::iterator nit; 911 | 912 | nit = m_nodes.begin(); // ignore root 913 | for(++nit; nit != m_nodes.end(); ++nit) 914 | { 915 | if(nit->isLeaf()) 916 | { 917 | nit->word_id = m_words.size(); 918 | m_words.push_back( &(*nit) ); 919 | } 920 | } 921 | } 922 | } 923 | 924 | // -------------------------------------------------------------------------- 925 | 926 | template 927 | void TemplatedVocabulary::setNodeWeights 928 | (const std::vector > &training_features) 929 | { 930 | const unsigned int NWords = m_words.size(); 931 | const unsigned int NDocs = training_features.size(); 932 | 933 | if(m_weighting == TF || m_weighting == BINARY) 934 | { 935 | // idf part must be 1 always 936 | for(unsigned int i = 0; i < NWords; i++) 937 | m_words[i]->weight = 1; 938 | } 939 | else if(m_weighting == IDF || m_weighting == TF_IDF) 940 | { 941 | // IDF and TF-IDF: we calculte the idf path now 942 | 943 | // Note: this actually calculates the idf part of the tf-idf score. 944 | // The complete tf-idf score is calculated in ::transform 945 | 946 | std::vector Ni(NWords, 0); 947 | std::vector counted(NWords, false); 948 | 949 | typename std::vector >::const_iterator mit; 950 | typename std::vector::const_iterator fit; 951 | 952 | for(mit = training_features.begin(); mit != training_features.end(); ++mit) 953 | { 954 | fill(counted.begin(), counted.end(), false); 955 | 956 | for(fit = mit->begin(); fit < mit->end(); ++fit) 957 | { 958 | WordId word_id; 959 | transform(*fit, word_id); 960 | 961 | if(!counted[word_id]) 962 | { 963 | Ni[word_id]++; 964 | counted[word_id] = true; 965 | } 966 | } 967 | } 968 | 969 | // set ln(N/Ni) 970 | for(unsigned int i = 0; i < NWords; i++) 971 | { 972 | if(Ni[i] > 0) 973 | { 974 | m_words[i]->weight = log((double)NDocs / (double)Ni[i]); 975 | }// else // This cannot occur if using kmeans++ 976 | } 977 | 978 | } 979 | 980 | } 981 | 982 | // -------------------------------------------------------------------------- 983 | 984 | template 985 | inline unsigned int TemplatedVocabulary::size() const 986 | { 987 | return m_words.size(); 988 | } 989 | 990 | // -------------------------------------------------------------------------- 991 | 992 | template 993 | inline bool TemplatedVocabulary::empty() const 994 | { 995 | return m_words.empty(); 996 | } 997 | 998 | // -------------------------------------------------------------------------- 999 | 1000 | template 1001 | float TemplatedVocabulary::getEffectiveLevels() const 1002 | { 1003 | long sum = 0; 1004 | typename std::vector::const_iterator wit; 1005 | for(wit = m_words.begin(); wit != m_words.end(); ++wit) 1006 | { 1007 | const Node *p = *wit; 1008 | 1009 | for(; p->id != 0; sum++) p = &m_nodes[p->parent]; 1010 | } 1011 | 1012 | return (float)((double)sum / (double)m_words.size()); 1013 | } 1014 | 1015 | // -------------------------------------------------------------------------- 1016 | 1017 | template 1018 | TDescriptor TemplatedVocabulary::getWord(WordId wid) const 1019 | { 1020 | return m_words[wid]->descriptor; 1021 | } 1022 | 1023 | // -------------------------------------------------------------------------- 1024 | 1025 | template 1026 | WordValue TemplatedVocabulary::getWordWeight(WordId wid) const 1027 | { 1028 | return m_words[wid]->weight; 1029 | } 1030 | 1031 | // -------------------------------------------------------------------------- 1032 | 1033 | template 1034 | WordId TemplatedVocabulary::transform 1035 | (const TDescriptor& feature) const 1036 | { 1037 | if(empty()) 1038 | { 1039 | return 0; 1040 | } 1041 | 1042 | WordId wid; 1043 | transform(feature, wid); 1044 | return wid; 1045 | } 1046 | 1047 | // -------------------------------------------------------------------------- 1048 | 1049 | template 1050 | void TemplatedVocabulary::transform( 1051 | const std::vector& features, BowVector &v) const 1052 | { 1053 | v.clear(); 1054 | 1055 | if(empty()) 1056 | { 1057 | return; 1058 | } 1059 | 1060 | // normalize 1061 | LNorm norm; 1062 | bool must = m_scoring_object->mustNormalize(norm); 1063 | 1064 | typename std::vector::const_iterator fit; 1065 | 1066 | if(m_weighting == TF || m_weighting == TF_IDF) 1067 | { 1068 | for(fit = features.begin(); fit < features.end(); ++fit) 1069 | { 1070 | WordId id; 1071 | WordValue w; 1072 | // w is the idf value if TF_IDF, 1 if TF 1073 | 1074 | transform(*fit, id, w); 1075 | 1076 | // not stopped 1077 | if(w > 0) v.addWeight(id, w); 1078 | } 1079 | 1080 | if(!v.empty() && !must) 1081 | { 1082 | // unnecessary when normalizing 1083 | const double nd = v.size(); 1084 | for(BowVector::iterator vit = v.begin(); vit != v.end(); vit++) 1085 | vit->second /= nd; 1086 | } 1087 | 1088 | } 1089 | else // IDF || BINARY 1090 | { 1091 | for(fit = features.begin(); fit < features.end(); ++fit) 1092 | { 1093 | WordId id; 1094 | WordValue w; 1095 | // w is idf if IDF, or 1 if BINARY 1096 | 1097 | transform(*fit, id, w); 1098 | 1099 | // not stopped 1100 | if(w > 0) v.addIfNotExist(id, w); 1101 | 1102 | } // if add_features 1103 | } // if m_weighting == ... 1104 | 1105 | if(must) v.normalize(norm); 1106 | } 1107 | 1108 | // -------------------------------------------------------------------------- 1109 | 1110 | template 1111 | void TemplatedVocabulary::transform( 1112 | const std::vector& features, 1113 | BowVector &v, FeatureVector &fv, int levelsup) const 1114 | { 1115 | v.clear(); 1116 | fv.clear(); 1117 | 1118 | if(empty()) // safe for subclasses 1119 | { 1120 | return; 1121 | } 1122 | 1123 | // normalize 1124 | LNorm norm; 1125 | bool must = m_scoring_object->mustNormalize(norm); 1126 | 1127 | typename std::vector::const_iterator fit; 1128 | 1129 | if(m_weighting == TF || m_weighting == TF_IDF) 1130 | { 1131 | unsigned int i_feature = 0; 1132 | for(fit = features.begin(); fit < features.end(); ++fit, ++i_feature) 1133 | { 1134 | WordId id; 1135 | NodeId nid; 1136 | WordValue w; 1137 | // w is the idf value if TF_IDF, 1 if TF 1138 | 1139 | transform(*fit, id, w, &nid, levelsup); 1140 | 1141 | if(w > 0) // not stopped 1142 | { 1143 | v.addWeight(id, w); 1144 | fv.addFeature(nid, i_feature); 1145 | } 1146 | } 1147 | 1148 | if(!v.empty() && !must) 1149 | { 1150 | // unnecessary when normalizing 1151 | const double nd = v.size(); 1152 | for(BowVector::iterator vit = v.begin(); vit != v.end(); vit++) 1153 | vit->second /= nd; 1154 | } 1155 | 1156 | } 1157 | else // IDF || BINARY 1158 | { 1159 | unsigned int i_feature = 0; 1160 | for(fit = features.begin(); fit < features.end(); ++fit, ++i_feature) 1161 | { 1162 | WordId id; 1163 | NodeId nid; 1164 | WordValue w; 1165 | // w is idf if IDF, or 1 if BINARY 1166 | 1167 | transform(*fit, id, w, &nid, levelsup); 1168 | 1169 | if(w > 0) // not stopped 1170 | { 1171 | v.addIfNotExist(id, w); 1172 | fv.addFeature(nid, i_feature); 1173 | } 1174 | } 1175 | } // if m_weighting == ... 1176 | 1177 | if(must) v.normalize(norm); 1178 | } 1179 | 1180 | // -------------------------------------------------------------------------- 1181 | 1182 | template 1183 | inline double TemplatedVocabulary::score 1184 | (const BowVector &v1, const BowVector &v2) const 1185 | { 1186 | return m_scoring_object->score(v1, v2); 1187 | } 1188 | 1189 | // -------------------------------------------------------------------------- 1190 | 1191 | template 1192 | void TemplatedVocabulary::transform 1193 | (const TDescriptor &feature, WordId &id) const 1194 | { 1195 | WordValue weight; 1196 | transform(feature, id, weight); 1197 | } 1198 | 1199 | // -------------------------------------------------------------------------- 1200 | 1201 | template 1202 | void TemplatedVocabulary::transform(const TDescriptor &feature, 1203 | WordId &word_id, WordValue &weight, NodeId *nid, int levelsup) const 1204 | { 1205 | // propagate the feature down the tree 1206 | std::vector nodes; 1207 | typename std::vector::const_iterator nit; 1208 | 1209 | // level at which the node must be stored in nid, if given 1210 | const int nid_level = m_L - levelsup; 1211 | if(nid_level <= 0 && nid != NULL) *nid = 0; // root 1212 | 1213 | NodeId final_id = 0; // root 1214 | int current_level = 0; 1215 | 1216 | do 1217 | { 1218 | ++current_level; 1219 | nodes = m_nodes[final_id].children; 1220 | final_id = nodes[0]; 1221 | 1222 | double best_d = F::distance(feature, m_nodes[final_id].descriptor); 1223 | 1224 | for(nit = nodes.begin() + 1; nit != nodes.end(); ++nit) 1225 | { 1226 | NodeId id = *nit; 1227 | double d = F::distance(feature, m_nodes[id].descriptor); 1228 | if(d < best_d) 1229 | { 1230 | best_d = d; 1231 | final_id = id; 1232 | } 1233 | } 1234 | 1235 | if(nid != NULL && current_level == nid_level) 1236 | *nid = final_id; 1237 | 1238 | } while( !m_nodes[final_id].isLeaf() ); 1239 | 1240 | // turn node id into word id 1241 | word_id = m_nodes[final_id].word_id; 1242 | weight = m_nodes[final_id].weight; 1243 | } 1244 | 1245 | // -------------------------------------------------------------------------- 1246 | 1247 | template 1248 | NodeId TemplatedVocabulary::getParentNode 1249 | (WordId wid, int levelsup) const 1250 | { 1251 | NodeId ret = m_words[wid]->id; // node id 1252 | while(levelsup > 0 && ret != 0) // ret == 0 --> root 1253 | { 1254 | --levelsup; 1255 | ret = m_nodes[ret].parent; 1256 | } 1257 | return ret; 1258 | } 1259 | 1260 | // -------------------------------------------------------------------------- 1261 | 1262 | template 1263 | void TemplatedVocabulary::getWordsFromNode 1264 | (NodeId nid, std::vector &words) const 1265 | { 1266 | words.clear(); 1267 | 1268 | if(m_nodes[nid].isLeaf()) 1269 | { 1270 | words.push_back(m_nodes[nid].word_id); 1271 | } 1272 | else 1273 | { 1274 | words.reserve(m_k); // ^1, ^2, ... 1275 | 1276 | std::vector parents; 1277 | parents.push_back(nid); 1278 | 1279 | while(!parents.empty()) 1280 | { 1281 | NodeId parentid = parents.back(); 1282 | parents.pop_back(); 1283 | 1284 | const std::vector &child_ids = m_nodes[parentid].children; 1285 | std::vector::const_iterator cit; 1286 | 1287 | for(cit = child_ids.begin(); cit != child_ids.end(); ++cit) 1288 | { 1289 | const Node &child_node = m_nodes[*cit]; 1290 | 1291 | if(child_node.isLeaf()) 1292 | words.push_back(child_node.word_id); 1293 | else 1294 | parents.push_back(*cit); 1295 | 1296 | } // for each child 1297 | } // while !parents.empty 1298 | } 1299 | } 1300 | 1301 | // -------------------------------------------------------------------------- 1302 | 1303 | template 1304 | int TemplatedVocabulary::stopWords(double minWeight) 1305 | { 1306 | int c = 0; 1307 | typename std::vector::iterator wit; 1308 | for(wit = m_words.begin(); wit != m_words.end(); ++wit) 1309 | { 1310 | if((*wit)->weight < minWeight) 1311 | { 1312 | ++c; 1313 | (*wit)->weight = 0; 1314 | } 1315 | } 1316 | return c; 1317 | } 1318 | 1319 | // -------------------------------------------------------------------------- 1320 | 1321 | template 1322 | void TemplatedVocabulary::save(const std::string &filename) const 1323 | { 1324 | cv::FileStorage fs(filename.c_str(), cv::FileStorage::WRITE); 1325 | if(!fs.isOpened()) throw std::string("Could not open file ") + filename; 1326 | 1327 | save(fs); 1328 | } 1329 | 1330 | // -------------------------------------------------------------------------- 1331 | 1332 | template 1333 | void TemplatedVocabulary::saveToTextFile(const std::string &filename) const 1334 | { 1335 | fstream f; 1336 | f.open(filename.c_str(),ios_base::out); 1337 | f << m_k << " " << m_L << " " << " " << m_scoring << " " << m_weighting << endl; 1338 | 1339 | for(size_t i=1; i 1359 | void TemplatedVocabulary::load(const std::string &filename) 1360 | { 1361 | cv::FileStorage fs(filename.c_str(), cv::FileStorage::READ); 1362 | if(!fs.isOpened()) throw std::string("Could not open file ") + filename; 1363 | 1364 | this->load(fs); 1365 | } 1366 | 1367 | // -------------------------------------------------------------------------- 1368 | 1369 | template 1370 | void TemplatedVocabulary::save(cv::FileStorage &f, 1371 | const std::string &name) const 1372 | { 1373 | // Format YAML: 1374 | // vocabulary 1375 | // { 1376 | // k: 1377 | // L: 1378 | // scoringType: 1379 | // weightingType: 1380 | // nodes 1381 | // [ 1382 | // { 1383 | // nodeId: 1384 | // parentId: 1385 | // weight: 1386 | // descriptor: 1387 | // } 1388 | // ] 1389 | // words 1390 | // [ 1391 | // { 1392 | // wordId: 1393 | // nodeId: 1394 | // } 1395 | // ] 1396 | // } 1397 | // 1398 | // The root node (index 0) is not included in the node vector 1399 | // 1400 | 1401 | f << name << "{"; 1402 | 1403 | f << "k" << m_k; 1404 | f << "L" << m_L; 1405 | f << "scoringType" << m_scoring; 1406 | f << "weightingType" << m_weighting; 1407 | 1408 | // tree 1409 | f << "nodes" << "["; 1410 | std::vector parents, children; 1411 | std::vector::const_iterator pit; 1412 | 1413 | parents.push_back(0); // root 1414 | 1415 | while(!parents.empty()) 1416 | { 1417 | NodeId pid = parents.back(); 1418 | parents.pop_back(); 1419 | 1420 | const Node& parent = m_nodes[pid]; 1421 | children = parent.children; 1422 | 1423 | for(pit = children.begin(); pit != children.end(); pit++) 1424 | { 1425 | const Node& child = m_nodes[*pit]; 1426 | 1427 | // save node data 1428 | f << "{:"; 1429 | f << "nodeId" << (int)child.id; 1430 | f << "parentId" << (int)pid; 1431 | f << "weight" << (double)child.weight; 1432 | f << "descriptor" << F::toString(child.descriptor); 1433 | f << "}"; 1434 | 1435 | // add to parent list 1436 | if(!child.isLeaf()) 1437 | { 1438 | parents.push_back(*pit); 1439 | } 1440 | } 1441 | } 1442 | 1443 | f << "]"; // nodes 1444 | 1445 | // words 1446 | f << "words" << "["; 1447 | 1448 | typename std::vector::const_iterator wit; 1449 | for(wit = m_words.begin(); wit != m_words.end(); wit++) 1450 | { 1451 | WordId id = wit - m_words.begin(); 1452 | f << "{:"; 1453 | f << "wordId" << (int)id; 1454 | f << "nodeId" << (int)(*wit)->id; 1455 | f << "}"; 1456 | } 1457 | 1458 | f << "]"; // words 1459 | 1460 | f << "}"; 1461 | 1462 | } 1463 | 1464 | // -------------------------------------------------------------------------- 1465 | 1466 | template 1467 | void TemplatedVocabulary::load(const cv::FileStorage &fs, 1468 | const std::string &name) 1469 | { 1470 | m_words.clear(); 1471 | m_nodes.clear(); 1472 | 1473 | cv::FileNode fvoc = fs[name]; 1474 | 1475 | m_k = (int)fvoc["k"]; 1476 | m_L = (int)fvoc["L"]; 1477 | m_scoring = (ScoringType)((int)fvoc["scoringType"]); 1478 | m_weighting = (WeightingType)((int)fvoc["weightingType"]); 1479 | 1480 | createScoringObject(); 1481 | 1482 | // nodes 1483 | cv::FileNode fn = fvoc["nodes"]; 1484 | 1485 | m_nodes.resize(fn.size() + 1); // +1 to include root 1486 | m_nodes[0].id = 0; 1487 | 1488 | for(unsigned int i = 0; i < fn.size(); ++i) 1489 | { 1490 | NodeId nid = (int)fn[i]["nodeId"]; 1491 | NodeId pid = (int)fn[i]["parentId"]; 1492 | WordValue weight = (WordValue)fn[i]["weight"]; 1493 | std::string d = (std::string)fn[i]["descriptor"]; 1494 | 1495 | m_nodes[nid].id = nid; 1496 | m_nodes[nid].parent = pid; 1497 | m_nodes[nid].weight = weight; 1498 | m_nodes[pid].children.push_back(nid); 1499 | 1500 | F::fromString(m_nodes[nid].descriptor, d); 1501 | } 1502 | 1503 | // words 1504 | fn = fvoc["words"]; 1505 | 1506 | m_words.resize(fn.size()); 1507 | 1508 | for(unsigned int i = 0; i < fn.size(); ++i) 1509 | { 1510 | NodeId wid = (int)fn[i]["wordId"]; 1511 | NodeId nid = (int)fn[i]["nodeId"]; 1512 | 1513 | m_nodes[nid].word_id = wid; 1514 | m_words[wid] = &m_nodes[nid]; 1515 | } 1516 | } 1517 | 1518 | // -------------------------------------------------------------------------- 1519 | 1520 | /** 1521 | * Writes printable information of the vocabulary 1522 | * @param os stream to write to 1523 | * @param voc 1524 | */ 1525 | template 1526 | std::ostream& operator<<(std::ostream &os, 1527 | const TemplatedVocabulary &voc) 1528 | { 1529 | os << "Vocabulary: k = " << voc.getBranchingFactor() 1530 | << ", L = " << voc.getDepthLevels() 1531 | << ", Weighting = "; 1532 | 1533 | switch(voc.getWeightingType()) 1534 | { 1535 | case TF_IDF: os << "tf-idf"; break; 1536 | case TF: os << "tf"; break; 1537 | case IDF: os << "idf"; break; 1538 | case BINARY: os << "binary"; break; 1539 | } 1540 | 1541 | os << ", Scoring = "; 1542 | switch(voc.getScoringType()) 1543 | { 1544 | case L1_NORM: os << "L1-norm"; break; 1545 | case L2_NORM: os << "L2-norm"; break; 1546 | case CHI_SQUARE: os << "Chi square distance"; break; 1547 | case KL: os << "KL-divergence"; break; 1548 | case BHATTACHARYYA: os << "Bhattacharyya coefficient"; break; 1549 | case DOT_PRODUCT: os << "Dot product"; break; 1550 | } 1551 | 1552 | os << ", Number of words = " << voc.size(); 1553 | 1554 | return os; 1555 | } 1556 | 1557 | } // namespace DBoW2 1558 | 1559 | #endif 1560 | --------------------------------------------------------------------------------