├── .gitignore ├── DBoW2 ├── .travis.yml ├── CMakeLists.txt ├── LICENSE.txt ├── README.md ├── demo │ ├── demo.cpp │ └── images │ │ ├── image0.png │ │ ├── image1.png │ │ ├── image2.png │ │ └── image3.png ├── include │ └── DBoW2 │ │ ├── BowVector.h │ │ ├── DBoW2.h │ │ ├── FBrief.h │ │ ├── FClass.h │ │ ├── FORB.h │ │ ├── FSurf64.h │ │ ├── FeatureVector.h │ │ ├── QueryResults.h │ │ ├── ScoringObject.h │ │ ├── TemplatedDatabase.h │ │ └── TemplatedVocabulary.h ├── package.xml └── src │ ├── BowVector.cpp │ ├── DBoW2.cmake.in │ ├── FBrief.cpp │ ├── FORB.cpp │ ├── FSurf64.cpp │ ├── FeatureVector.cpp │ ├── QueryResults.cpp │ └── ScoringObject.cpp ├── ORB_SLAM_txt ├── CMakeLists.txt ├── Example_Vocab │ ├── Castle_Ruins_voc.zip │ └── ORBvoc.txt.tar.gz ├── README.md ├── Thirdparty │ └── DBoW2 │ │ ├── CMakeLists.txt │ │ ├── DBoW2 │ │ ├── BowVector.cpp │ │ ├── BowVector.h │ │ ├── FClass.h │ │ ├── FORB.cpp │ │ ├── FORB.h │ │ ├── FeatureVector.cpp │ │ ├── FeatureVector.h │ │ ├── ScoringObject.cpp │ │ ├── ScoringObject.h │ │ └── TemplatedVocabulary.h │ │ ├── DUtils │ │ ├── Random.cpp │ │ ├── Random.h │ │ ├── Timestamp.cpp │ │ └── Timestamp.h │ │ ├── LICENSE.txt │ │ └── README.txt ├── Vocab │ └── convert_to_txt.cpp ├── cmake_modules │ └── FindEigen3.cmake ├── include │ └── ORBVocabulary.h └── src │ └── Orb_vocab.cc ├── README.md └── bag_to_img.launch /.gitignore: -------------------------------------------------------------------------------- 1 | ORB_SLAM_txt/Thirdparty/DBoW2/build 2 | DBoW2/build 3 | build/ -------------------------------------------------------------------------------- /DBoW2/.travis.yml: -------------------------------------------------------------------------------- 1 | language: cpp 2 | os: 3 | - linux 4 | - osx 5 | - windows 6 | dist: 7 | - bionic 8 | osx_image: 9 | - xcode11.3 10 | env: 11 | - OPENCV_BRANCH=master 12 | - OPENCV_BRANCH=3.4 13 | cache: 14 | directories: 15 | - ${TRAVIS_BUILD_DIR}/opencv 16 | before_script: 17 | - rmdir opencv || true 18 | - if [ ! -d opencv ]; then git clone --single-branch --branch ${OPENCV_BRANCH} https://github.com/opencv/opencv.git; fi 19 | - pushd opencv 20 | - mkdir -p build 21 | - cd build 22 | - cmake .. -DBUILD_LIST=core,imgproc,imgcodecs,calib3d,highgui -DBUILD_EXAMPLES=OFF -DCMAKE_INSTALL_PREFIX=../install 23 | - cmake --build . --parallel 8 --target install --config Release 24 | - popd 25 | script: 26 | - mkdir -p build 27 | - cd build 28 | - export OPENCV_CONFIG=$(dirname $(find ${TRAVIS_BUILD_DIR}/opencv/install -name OpenCVConfig.cmake | head -n1)) 29 | - cmake .. -DOpenCV_DIR=${OPENCV_CONFIG} 30 | - cmake --build . --config Release 31 | - export DEMO=$(find . -type f \( -name demo.exe -o -name demo \) | head -n1) 32 | - export PATH="$PATH:${TRAVIS_BUILD_DIR}/opencv/install/x86/vc15/bin" 33 | - echo | $DEMO 34 | -------------------------------------------------------------------------------- /DBoW2/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 3.0) 2 | project(DBoW2) 3 | include(ExternalProject) 4 | 5 | option(BUILD_DBoW2 "Build DBoW2" ON) 6 | option(BUILD_Demo "Build demo 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 | add_compile_options(/W4) 16 | else() 17 | add_compile_options(-Wall -Wextra -Wpedantic) 18 | endif() 19 | 20 | set(HDRS 21 | include/DBoW2/BowVector.h include/DBoW2/FBrief.h 22 | include/DBoW2/QueryResults.h include/DBoW2/TemplatedDatabase.h include/DBoW2/FORB.h 23 | include/DBoW2/DBoW2.h include/DBoW2/FClass.h include/DBoW2/FeatureVector.h 24 | include/DBoW2/ScoringObject.h include/DBoW2/TemplatedVocabulary.h) 25 | set(SRCS 26 | src/BowVector.cpp src/FBrief.cpp src/FORB.cpp 27 | src/FeatureVector.cpp src/QueryResults.cpp src/ScoringObject.cpp) 28 | 29 | set(DEPENDENCY_DIR ${CMAKE_CURRENT_BINARY_DIR}/dependencies) 30 | set(DEPENDENCY_INSTALL_DIR ${DEPENDENCY_DIR}/install) 31 | 32 | find_package(OpenCV REQUIRED) 33 | include_directories(${OpenCV_INCLUDE_DIRS}) 34 | 35 | if(BUILD_DBoW2) 36 | set(LIB_SHARED "SHARED") 37 | if(WIN32) 38 | set(LIB_SHARED "STATIC") 39 | endif(WIN32) 40 | add_library(${PROJECT_NAME} ${LIB_SHARED} ${SRCS}) 41 | target_include_directories(${PROJECT_NAME} PUBLIC include/DBoW2/ include/) 42 | target_link_libraries(${PROJECT_NAME} ${OpenCV_LIBS}) 43 | set_target_properties(${PROJECT_NAME} PROPERTIES CXX_STANDARD 11) 44 | endif(BUILD_DBoW2) 45 | 46 | if(BUILD_Demo) 47 | add_executable(demo demo/demo.cpp) 48 | target_link_libraries(demo ${PROJECT_NAME} ${OpenCV_LIBS}) 49 | set_target_properties(demo PROPERTIES CXX_STANDARD 11) 50 | file(COPY demo/images DESTINATION ${CMAKE_BINARY_DIR}/) 51 | endif(BUILD_Demo) 52 | 53 | configure_file(src/DBoW2.cmake.in 54 | "${PROJECT_BINARY_DIR}/DBoW2Config.cmake" @ONLY) 55 | 56 | install(TARGETS ${PROJECT_NAME} DESTINATION ${CMAKE_INSTALL_PREFIX}/lib) 57 | if(BUILD_DBoW2) 58 | install(DIRECTORY include/DBoW2 DESTINATION ${CMAKE_INSTALL_PREFIX}/include) 59 | endif() 60 | install(FILES "${CMAKE_CURRENT_BINARY_DIR}/DBoW2Config.cmake" 61 | DESTINATION ${CMAKE_INSTALL_PREFIX}/include/${PROJECT_NAME}) 62 | install(FILES "${PROJECT_BINARY_DIR}/DBoW2Config.cmake" 63 | DESTINATION ${CMAKE_INSTALL_PREFIX}/lib/cmake/DBoW2/) 64 | install(DIRECTORY ${DEPENDENCY_INSTALL_DIR}/ DESTINATION ${CMAKE_INSTALL_PREFIX} OPTIONAL) 65 | 66 | -------------------------------------------------------------------------------- /DBoW2/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 | -------------------------------------------------------------------------------- /DBoW2/README.md: -------------------------------------------------------------------------------- 1 | DBoW2 2 | ===== 3 | 4 | DBoW2 is an improved version of the DBow library, an open source C++ library for indexing and converting images into a bag-of-word representation. It implements a hierarchical tree for approximating nearest neighbours in the image feature space and creating a visual vocabulary. DBoW2 also implements an image database with inverted and direct files to index images and enabling quick queries and feature comparisons. The main differences with the previous DBow library are: 5 | 6 | * DBoW2 classes are templated, so it can work with any type of descriptor. 7 | * DBoW2 is shipped with classes to directly work with ORB or BRIEF descriptors. 8 | * DBoW2 adds a direct file to the image database to do fast feature comparison. This is used by DLoopDetector. 9 | * DBoW2 does not use a binary format any longer. On the other hand, it uses the OpenCV storage system to save vocabularies and databases. This means that these files can be stored as plain text in YAML format, making compatibility easier, or compressed in gunzip format (.gz) to reduce disk usage. 10 | * Some pieces of code have been rewritten to optimize speed. The interface of DBoW2 has been simplified. 11 | * For performance reasons, DBoW2 does not support stop words. 12 | 13 | DBoW2 requires OpenCV and the `Boost::dynamic_bitset` class in order to use the BRIEF version. 14 | 15 | DBoW2, along with DLoopDetector, has been tested on several real datasets, yielding an execution time of 3 ms to convert the BRIEF features of an image into a bag-of-words vector and 5 ms to look for image matches in a database with more than 19000 images. 16 | 17 | ## Citing 18 | 19 | If you use this software in an academic work, please cite: 20 | 21 | @ARTICLE{GalvezTRO12, 22 | author={G\'alvez-L\'opez, Dorian and Tard\'os, J. D.}, 23 | journal={IEEE Transactions on Robotics}, 24 | title={Bags of Binary Words for Fast Place Recognition in Image Sequences}, 25 | year={2012}, 26 | month={October}, 27 | volume={28}, 28 | number={5}, 29 | pages={1188--1197}, 30 | doi={10.1109/TRO.2012.2197158}, 31 | ISSN={1552-3098} 32 | } 33 | } 34 | 35 | ## Usage notes 36 | 37 | ### Weighting and Scoring 38 | 39 | DBoW2 implements the same weighting and scoring mechanisms as DBow. Check them here. The only difference is that DBoW2 scales all the scores to [0..1], so that the scaling flag is not used any longer. 40 | 41 | ### Save & Load 42 | 43 | All vocabularies and databases can be saved to and load from disk with the save and load member functions. When a database is saved, the vocabulary it is associated with is also embedded in the file, so that vocabulary and database files are completely independent. 44 | 45 | You can also add the vocabulary or database data to any file opened with a `cv::FileStorage` structure. 46 | 47 | You can save the vocabulary or the database with any file extension. If you use .gz, the file is automatically compressed (OpenCV behaviour). 48 | 49 | ## Implementation notes 50 | 51 | ### Template parameters 52 | 53 | DBoW2 has two main classes: `TemplatedVocabulary` and `TemplatedDatabase`. These implement the visual vocabulary to convert images into bag-of-words vectors and the database to index images. These classes are templated: 54 | 55 | template 56 | class TemplatedVocabulary 57 | { 58 | ... 59 | }; 60 | 61 | template 62 | class TemplatedDatabase 63 | { 64 | ... 65 | }; 66 | 67 | Two classes must be provided: `TDescriptor` is the data type of a single descriptor vector, and `F`, a class with the functions to manipulate descriptors, derived from `FClass`. 68 | 69 | For example, to work with ORB descriptors, `TDescriptor` is defined as `cv::Mat` (of type `CV_8UC1`), which is a single row that contains 32 8-bit values. When features are extracted from an image, a `std::vector` must be obtained. In the case of BRIEF, `TDescriptor` is defined as `boost::dynamic_bitset<>`. 70 | 71 | The `F` parameter is the name of a class that implements the functions defined in `FClass`. These functions get `TDescriptor` data and compute some result. Classes to deal with ORB and BRIEF descriptors are already included in DBoW2. (`FORB`, `FBrief`). 72 | 73 | ### Predefined Vocabularies and Databases 74 | 75 | To make it easier to use, DBoW2 defines two kinds of vocabularies and databases: `OrbVocabulary`, `OrbDatabase`, `BriefVocabulary`, `BriefDatabase`. Please, check the demo application to see how they are created and used. 76 | -------------------------------------------------------------------------------- /DBoW2/demo/demo.cpp: -------------------------------------------------------------------------------- 1 | /** 2 | * File: Demo.cpp 3 | * Date: November 2011 4 | * Author: Dorian Galvez-Lopez 5 | * Description: demo application of DBoW2 6 | * License: see the LICENSE.txt file 7 | */ 8 | 9 | #include 10 | #include 11 | 12 | // DBoW2 13 | #include "DBoW2.h" // defines OrbVocabulary and OrbDatabase 14 | 15 | // OpenCV 16 | #include 17 | #include 18 | #include 19 | 20 | 21 | using namespace DBoW2; 22 | using namespace std; 23 | 24 | // - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - 25 | 26 | void loadFeatures(vector > &features); 27 | void changeStructure(const cv::Mat &plain, vector &out); 28 | void testVocCreation(const vector > &features); 29 | void testDatabase(const vector > &features); 30 | 31 | 32 | // - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - 33 | 34 | // number of training images 35 | const int NIMAGES = 4; 36 | 37 | // - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - 38 | 39 | void wait() 40 | { 41 | cout << endl << "Press enter to continue" << endl; 42 | getchar(); 43 | } 44 | 45 | // ---------------------------------------------------------------------------- 46 | 47 | int main() 48 | { 49 | vector > features; 50 | loadFeatures(features); 51 | 52 | testVocCreation(features); 53 | 54 | wait(); 55 | 56 | testDatabase(features); 57 | 58 | return 0; 59 | } 60 | 61 | // ---------------------------------------------------------------------------- 62 | 63 | void loadFeatures(vector > &features) 64 | { 65 | features.clear(); 66 | features.reserve(NIMAGES); 67 | 68 | cv::Ptr orb = cv::ORB::create(); 69 | 70 | cout << "Extracting ORB features..." << endl; 71 | for(int i = 0; i < NIMAGES; ++i) 72 | { 73 | stringstream ss; 74 | ss << "images/image" << i << ".png"; 75 | 76 | cv::Mat image = cv::imread(ss.str(), 0); 77 | cv::Mat mask; 78 | vector keypoints; 79 | cv::Mat descriptors; 80 | 81 | orb->detectAndCompute(image, mask, keypoints, descriptors); 82 | 83 | features.push_back(vector()); 84 | changeStructure(descriptors, features.back()); 85 | } 86 | } 87 | 88 | // ---------------------------------------------------------------------------- 89 | 90 | void changeStructure(const cv::Mat &plain, vector &out) 91 | { 92 | out.resize(plain.rows); 93 | 94 | for(int i = 0; i < plain.rows; ++i) 95 | { 96 | out[i] = plain.row(i); 97 | } 98 | } 99 | 100 | // ---------------------------------------------------------------------------- 101 | 102 | void testVocCreation(const vector > &features) 103 | { 104 | // branching factor and depth levels 105 | const int k = 10; 106 | const int L = 6; 107 | const WeightingType weight = TF_IDF; 108 | const ScoringType scoring = L1_NORM; 109 | 110 | OrbVocabulary voc(k, L, weight, scoring); 111 | 112 | cout << "Creating a small " << k << "^" << L << " vocabulary..." << endl; 113 | voc.create(features); 114 | cout << "... done!" << endl; 115 | 116 | cout << "Vocabulary information: " << endl 117 | << voc << endl << endl; 118 | 119 | // lets do something with this vocabulary 120 | cout << "Matching images against themselves (0 low, 1 high): " << endl; 121 | BowVector v1, v2; 122 | for(int i = 0; i < NIMAGES; i++) 123 | { 124 | voc.transform(features[i], v1); 125 | for(int j = 0; j < NIMAGES; j++) 126 | { 127 | voc.transform(features[j], v2); 128 | 129 | double score = voc.score(v1, v2); 130 | cout << "Image " << i << " vs Image " << j << ": " << score << endl; 131 | } 132 | } 133 | 134 | // save the vocabulary to disk 135 | cout << endl << "Saving vocabulary..." << endl; 136 | voc.save("castle_ruins.yml.gz"); 137 | cout << "Done" << endl; 138 | } 139 | 140 | // ---------------------------------------------------------------------------- 141 | 142 | void testDatabase(const vector > &features) 143 | { 144 | cout << "Creating a small database..." << endl; 145 | 146 | // load the vocabulary from disk 147 | OrbVocabulary voc("castle_ruins.yml.gz"); 148 | 149 | OrbDatabase db(voc, false, 0); // false = do not use direct index 150 | // (so ignore the last param) 151 | // The direct index is useful if we want to retrieve the features that 152 | // belong to some vocabulary node. 153 | // db creates a copy of the vocabulary, we may get rid of "voc" now 154 | 155 | // add images to the database 156 | for(int i = 0; i < NIMAGES; i++) 157 | { 158 | db.add(features[i]); 159 | } 160 | 161 | cout << "... done!" << endl; 162 | 163 | cout << "Database information: " << endl << db << endl; 164 | 165 | // and query the database 166 | cout << "Querying the database: " << endl; 167 | 168 | QueryResults ret; 169 | for(int i = 0; i < NIMAGES; i++) 170 | { 171 | db.query(features[i], ret, 4); 172 | 173 | // ret[0] is always the same image in this case, because we added it to the 174 | // database. ret[1] is the second best match. 175 | 176 | cout << "Searching for Image " << i << ". " << ret << endl; 177 | } 178 | 179 | cout << endl; 180 | 181 | // we can save the database. The created file includes the vocabulary 182 | // and the entries added 183 | cout << "Saving database..." << endl; 184 | db.save("small_db.yml.gz"); 185 | cout << "... done!" << endl; 186 | 187 | // once saved, we can load it again 188 | cout << "Retrieving database once again..." << endl; 189 | OrbDatabase db2("small_db.yml.gz"); 190 | cout << "... done! This is: " << endl << db2 << endl; 191 | } 192 | 193 | // ---------------------------------------------------------------------------- 194 | 195 | 196 | -------------------------------------------------------------------------------- /DBoW2/demo/images/image0.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manthan99/ORB_SLAM_vocab-build/7f99fefa293fdf9b670e15985944fbb494c0d618/DBoW2/demo/images/image0.png -------------------------------------------------------------------------------- /DBoW2/demo/images/image1.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manthan99/ORB_SLAM_vocab-build/7f99fefa293fdf9b670e15985944fbb494c0d618/DBoW2/demo/images/image1.png -------------------------------------------------------------------------------- /DBoW2/demo/images/image2.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manthan99/ORB_SLAM_vocab-build/7f99fefa293fdf9b670e15985944fbb494c0d618/DBoW2/demo/images/image2.png -------------------------------------------------------------------------------- /DBoW2/demo/images/image3.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manthan99/ORB_SLAM_vocab-build/7f99fefa293fdf9b670e15985944fbb494c0d618/DBoW2/demo/images/image3.png -------------------------------------------------------------------------------- /DBoW2/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 | -------------------------------------------------------------------------------- /DBoW2/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 | -------------------------------------------------------------------------------- /DBoW2/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 | #include 17 | 18 | #include "FClass.h" 19 | 20 | namespace DBoW2 { 21 | 22 | /// Functions to manipulate BRIEF descriptors 23 | class FBrief: protected FClass 24 | { 25 | public: 26 | 27 | static const int L = 256; // Descriptor length (in bits) 28 | typedef std::bitset TDescriptor; 29 | typedef const TDescriptor *pDescriptor; 30 | 31 | /** 32 | * Calculates the mean value of a set of descriptors 33 | * @param descriptors 34 | * @param mean mean descriptor 35 | */ 36 | static void meanValue(const std::vector &descriptors, 37 | TDescriptor &mean); 38 | 39 | /** 40 | * Calculates the distance between two descriptors 41 | * @param a 42 | * @param b 43 | * @return distance 44 | */ 45 | static double distance(const TDescriptor &a, const TDescriptor &b); 46 | 47 | /** 48 | * Returns a string version of the descriptor 49 | * @param a descriptor 50 | * @return string version 51 | */ 52 | static std::string toString(const TDescriptor &a); 53 | 54 | /** 55 | * Returns a descriptor from a string 56 | * @param a descriptor 57 | * @param s string version 58 | */ 59 | static void fromString(TDescriptor &a, const std::string &s); 60 | 61 | /** 62 | * Returns a mat with the descriptors in float format 63 | * @param descriptors 64 | * @param mat (out) NxL 32F matrix 65 | */ 66 | static void toMat32F(const std::vector &descriptors, 67 | cv::Mat &mat); 68 | 69 | }; 70 | 71 | } // namespace DBoW2 72 | 73 | #endif 74 | 75 | -------------------------------------------------------------------------------- /DBoW2/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 | -------------------------------------------------------------------------------- /DBoW2/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 | -------------------------------------------------------------------------------- /DBoW2/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 | -------------------------------------------------------------------------------- /DBoW2/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 | -------------------------------------------------------------------------------- /DBoW2/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 | -------------------------------------------------------------------------------- /DBoW2/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 | -------------------------------------------------------------------------------- /DBoW2/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 | namespace DBoW2 { 27 | 28 | // For query functions 29 | static int MIN_COMMON_WORDS = 5; 30 | 31 | /// @param TDescriptor class of descriptor 32 | /// @param F class of descriptor functions 33 | template 34 | /// Generic Database 35 | class TemplatedDatabase 36 | { 37 | public: 38 | 39 | /** 40 | * Creates an empty database without vocabulary 41 | * @param use_di a direct index is used to store feature indexes 42 | * @param di_levels levels to go up the vocabulary tree to select the 43 | * node id to store in the direct index when adding images 44 | */ 45 | explicit TemplatedDatabase(bool use_di = true, int di_levels = 0); 46 | 47 | /** 48 | * Creates a database with the given vocabulary 49 | * @param T class inherited from TemplatedVocabulary 50 | * @param voc vocabulary 51 | * @param use_di a direct index is used to store feature indexes 52 | * @param di_levels levels to go up the vocabulary tree to select the 53 | * node id to store in the direct index when adding images 54 | */ 55 | template 56 | explicit TemplatedDatabase(const T &voc, bool use_di = true, 57 | int di_levels = 0); 58 | 59 | /** 60 | * Copy constructor. Copies the vocabulary too 61 | * @param db object to copy 62 | */ 63 | TemplatedDatabase(const TemplatedDatabase &db); 64 | 65 | /** 66 | * Creates the database from a file 67 | * @param filename 68 | */ 69 | TemplatedDatabase(const std::string &filename); 70 | 71 | /** 72 | * Creates the database from a file 73 | * @param filename 74 | */ 75 | TemplatedDatabase(const char *filename); 76 | 77 | /** 78 | * Destructor 79 | */ 80 | virtual ~TemplatedDatabase(void); 81 | 82 | /** 83 | * Copies the given database and its vocabulary 84 | * @param db database to copy 85 | */ 86 | TemplatedDatabase& operator=( 87 | const TemplatedDatabase &db); 88 | 89 | /** 90 | * Sets the vocabulary to use and clears the content of the database. 91 | * @param T class inherited from TemplatedVocabulary 92 | * @param voc vocabulary to copy 93 | */ 94 | template 95 | inline void setVocabulary(const T &voc); 96 | 97 | /** 98 | * Sets the vocabulary to use and the direct index parameters, and clears 99 | * the content of the database 100 | * @param T class inherited from TemplatedVocabulary 101 | * @param voc vocabulary to copy 102 | * @param use_di a direct index is used to store feature indexes 103 | * @param di_levels levels to go up the vocabulary tree to select the 104 | * node id to store in the direct index when adding images 105 | */ 106 | template 107 | void setVocabulary(const T& voc, bool use_di, int di_levels = 0); 108 | 109 | /** 110 | * Returns a pointer to the vocabulary used 111 | * @return vocabulary 112 | */ 113 | inline const TemplatedVocabulary* getVocabulary() const; 114 | 115 | /** 116 | * Allocates some memory for the direct and inverted indexes 117 | * @param nd number of expected image entries in the database 118 | * @param ni number of expected words per image 119 | * @note Use 0 to ignore a parameter 120 | */ 121 | void allocate(int nd = 0, int ni = 0); 122 | 123 | /** 124 | * Adds an entry to the database and returns its index 125 | * @param features features of the new entry 126 | * @param bowvec if given, the bow vector of these features is returned 127 | * @param fvec if given, the vector of nodes and feature indexes is returned 128 | * @return id of new entry 129 | */ 130 | EntryId add(const std::vector &features, 131 | BowVector *bowvec = NULL, FeatureVector *fvec = NULL); 132 | 133 | /** 134 | * Adss an entry to the database and returns its index 135 | * @param vec bow vector 136 | * @param fec feature vector to add the entry. Only necessary if using the 137 | * direct index 138 | * @return id of new entry 139 | */ 140 | EntryId add(const BowVector &vec, 141 | const FeatureVector &fec = FeatureVector() ); 142 | 143 | /** 144 | * Empties the database 145 | */ 146 | inline void clear(); 147 | 148 | /** 149 | * Returns the number of entries in the database 150 | * @return number of entries in the database 151 | */ 152 | inline unsigned int size() const; 153 | 154 | /** 155 | * Checks if the direct index is being used 156 | * @return true iff using direct index 157 | */ 158 | inline bool usingDirectIndex() const; 159 | 160 | /** 161 | * Returns the di levels when using direct index 162 | * @return di levels 163 | */ 164 | inline int getDirectIndexLevels() const; 165 | 166 | /** 167 | * Queries the database with some features 168 | * @param features query features 169 | * @param ret (out) query results 170 | * @param max_results number of results to return. <= 0 means all 171 | * @param max_id only entries with id <= max_id are returned in ret. 172 | * < 0 means all 173 | */ 174 | void query(const std::vector &features, QueryResults &ret, 175 | int max_results = 1, int max_id = -1) const; 176 | 177 | /** 178 | * Queries the database with a vector 179 | * @param vec bow vector already normalized 180 | * @param ret results 181 | * @param max_results number of results to return. <= 0 means all 182 | * @param max_id only entries with id <= max_id are returned in ret. 183 | * < 0 means all 184 | */ 185 | void query(const BowVector &vec, QueryResults &ret, 186 | int max_results = 1, int max_id = -1) const; 187 | 188 | /** 189 | * Returns the a feature vector associated with a database entry 190 | * @param id entry id (must be < size()) 191 | * @return const reference to map of nodes and their associated features in 192 | * the given entry 193 | */ 194 | const FeatureVector& retrieveFeatures(EntryId id) const; 195 | 196 | /** 197 | * Stores the database in a file 198 | * @param filename 199 | */ 200 | void save(const std::string &filename) const; 201 | 202 | /** 203 | * Loads the database from a file 204 | * @param filename 205 | */ 206 | void load(const std::string &filename); 207 | 208 | /** 209 | * Stores the database in the given file storage structure 210 | * @param fs 211 | * @param name node name 212 | */ 213 | virtual void save(cv::FileStorage &fs, 214 | const std::string &name = "database") const; 215 | 216 | /** 217 | * Loads the database from the given file storage structure 218 | * @param fs 219 | * @param name node name 220 | */ 221 | virtual void load(const cv::FileStorage &fs, 222 | const std::string &name = "database"); 223 | 224 | protected: 225 | 226 | /// Query with L1 scoring 227 | void queryL1(const BowVector &vec, QueryResults &ret, 228 | int max_results, int max_id) const; 229 | 230 | /// Query with L2 scoring 231 | void queryL2(const BowVector &vec, QueryResults &ret, 232 | int max_results, int max_id) const; 233 | 234 | /// Query with Chi square scoring 235 | void queryChiSquare(const BowVector &vec, QueryResults &ret, 236 | int max_results, int max_id) const; 237 | 238 | /// Query with Bhattacharyya scoring 239 | void queryBhattacharyya(const BowVector &vec, QueryResults &ret, 240 | int max_results, int max_id) const; 241 | 242 | /// Query with KL divergence scoring 243 | void queryKL(const BowVector &vec, QueryResults &ret, 244 | int max_results, int max_id) const; 245 | 246 | /// Query with dot product scoring 247 | void queryDotProduct(const BowVector &vec, QueryResults &ret, 248 | int max_results, int max_id) const; 249 | 250 | protected: 251 | 252 | /* Inverted file declaration */ 253 | 254 | /// Item of IFRow 255 | struct IFPair 256 | { 257 | /// Entry id 258 | EntryId entry_id; 259 | 260 | /// Word weight in this entry 261 | WordValue word_weight; 262 | 263 | /** 264 | * Creates an empty pair 265 | */ 266 | IFPair(){} 267 | 268 | /** 269 | * Creates an inverted file pair 270 | * @param eid entry id 271 | * @param wv word weight 272 | */ 273 | IFPair(EntryId eid, WordValue wv): entry_id(eid), word_weight(wv) {} 274 | 275 | /** 276 | * Compares the entry ids 277 | * @param eid 278 | * @return true iff this entry id is the same as eid 279 | */ 280 | inline bool operator==(EntryId eid) const { return entry_id == eid; } 281 | }; 282 | 283 | /// Row of InvertedFile 284 | typedef std::list IFRow; 285 | // IFRows are sorted in ascending entry_id order 286 | 287 | /// Inverted index 288 | typedef std::vector InvertedFile; 289 | // InvertedFile[word_id] --> inverted file of that word 290 | 291 | /* Direct file declaration */ 292 | 293 | /// Direct index 294 | typedef std::vector DirectFile; 295 | // DirectFile[entry_id] --> [ directentry, ... ] 296 | 297 | protected: 298 | 299 | /// Associated vocabulary 300 | TemplatedVocabulary *m_voc; 301 | 302 | /// Flag to use direct index 303 | bool m_use_di; 304 | 305 | /// Levels to go up the vocabulary tree to select nodes to store 306 | /// in the direct index 307 | int m_dilevels; 308 | 309 | /// Inverted file (must have size() == |words|) 310 | InvertedFile m_ifile; 311 | 312 | /// Direct file (resized for allocation) 313 | DirectFile m_dfile; 314 | 315 | /// Number of valid entries in m_dfile 316 | int m_nentries; 317 | 318 | }; 319 | 320 | // -------------------------------------------------------------------------- 321 | 322 | template 323 | TemplatedDatabase::TemplatedDatabase 324 | (bool use_di, int di_levels) 325 | : m_voc(NULL), m_use_di(use_di), m_dilevels(di_levels), m_nentries(0) 326 | { 327 | } 328 | 329 | // -------------------------------------------------------------------------- 330 | 331 | template 332 | template 333 | TemplatedDatabase::TemplatedDatabase 334 | (const T &voc, bool use_di, int di_levels) 335 | : m_voc(NULL), m_use_di(use_di), m_dilevels(di_levels) 336 | { 337 | setVocabulary(voc); 338 | clear(); 339 | } 340 | 341 | // -------------------------------------------------------------------------- 342 | 343 | template 344 | TemplatedDatabase::TemplatedDatabase 345 | (const TemplatedDatabase &db) 346 | : m_voc(NULL) 347 | { 348 | *this = db; 349 | } 350 | 351 | // -------------------------------------------------------------------------- 352 | 353 | template 354 | TemplatedDatabase::TemplatedDatabase 355 | (const std::string &filename) 356 | : m_voc(NULL) 357 | { 358 | load(filename); 359 | } 360 | 361 | // -------------------------------------------------------------------------- 362 | 363 | template 364 | TemplatedDatabase::TemplatedDatabase 365 | (const char *filename) 366 | : m_voc(NULL) 367 | { 368 | load(filename); 369 | } 370 | 371 | // -------------------------------------------------------------------------- 372 | 373 | template 374 | TemplatedDatabase::~TemplatedDatabase(void) 375 | { 376 | delete m_voc; 377 | } 378 | 379 | // -------------------------------------------------------------------------- 380 | 381 | template 382 | TemplatedDatabase& TemplatedDatabase::operator= 383 | (const TemplatedDatabase &db) 384 | { 385 | if(this != &db) 386 | { 387 | m_dfile = db.m_dfile; 388 | m_dilevels = db.m_dilevels; 389 | m_ifile = db.m_ifile; 390 | m_nentries = db.m_nentries; 391 | m_use_di = db.m_use_di; 392 | setVocabulary(*db.m_voc); 393 | } 394 | return *this; 395 | } 396 | 397 | // -------------------------------------------------------------------------- 398 | 399 | template 400 | EntryId TemplatedDatabase::add( 401 | const std::vector &features, 402 | BowVector *bowvec, FeatureVector *fvec) 403 | { 404 | BowVector aux; 405 | BowVector& v = (bowvec ? *bowvec : aux); 406 | 407 | if(m_use_di && fvec != NULL) 408 | { 409 | m_voc->transform(features, v, *fvec, m_dilevels); // with features 410 | return add(v, *fvec); 411 | } 412 | else if(m_use_di) 413 | { 414 | FeatureVector fv; 415 | m_voc->transform(features, v, fv, m_dilevels); // with features 416 | return add(v, fv); 417 | } 418 | else if(fvec != NULL) 419 | { 420 | m_voc->transform(features, v, *fvec, m_dilevels); // with features 421 | return add(v); 422 | } 423 | else 424 | { 425 | m_voc->transform(features, v); // with features 426 | return add(v); 427 | } 428 | } 429 | 430 | // --------------------------------------------------------------------------- 431 | 432 | template 433 | EntryId TemplatedDatabase::add(const BowVector &v, 434 | const FeatureVector &fv) 435 | { 436 | EntryId entry_id = m_nentries++; 437 | 438 | BowVector::const_iterator vit; 439 | 440 | if(m_use_di) 441 | { 442 | // update direct file 443 | if(entry_id == m_dfile.size()) 444 | { 445 | m_dfile.push_back(fv); 446 | } 447 | else 448 | { 449 | m_dfile[entry_id] = fv; 450 | } 451 | } 452 | 453 | // update inverted file 454 | for(vit = v.begin(); vit != v.end(); ++vit) 455 | { 456 | const WordId& word_id = vit->first; 457 | const WordValue& word_weight = vit->second; 458 | 459 | IFRow& ifrow = m_ifile[word_id]; 460 | ifrow.push_back(IFPair(entry_id, word_weight)); 461 | } 462 | 463 | return entry_id; 464 | } 465 | 466 | // -------------------------------------------------------------------------- 467 | 468 | template 469 | template 470 | inline void TemplatedDatabase::setVocabulary 471 | (const T& voc) 472 | { 473 | delete m_voc; 474 | m_voc = new T(voc); 475 | clear(); 476 | } 477 | 478 | // -------------------------------------------------------------------------- 479 | 480 | template 481 | template 482 | inline void TemplatedDatabase::setVocabulary 483 | (const T& voc, bool use_di, int di_levels) 484 | { 485 | m_use_di = use_di; 486 | m_dilevels = di_levels; 487 | delete m_voc; 488 | m_voc = new T(voc); 489 | clear(); 490 | } 491 | 492 | // -------------------------------------------------------------------------- 493 | 494 | template 495 | inline const TemplatedVocabulary* 496 | TemplatedDatabase::getVocabulary() const 497 | { 498 | return m_voc; 499 | } 500 | 501 | // -------------------------------------------------------------------------- 502 | 503 | template 504 | inline void TemplatedDatabase::clear() 505 | { 506 | // resize vectors 507 | m_ifile.resize(0); 508 | m_ifile.resize(m_voc->size()); 509 | m_dfile.resize(0); 510 | m_nentries = 0; 511 | } 512 | 513 | // -------------------------------------------------------------------------- 514 | 515 | template 516 | void TemplatedDatabase::allocate(int nd, int ni) 517 | { 518 | // m_ifile already contains |words| items 519 | if(ni > 0) 520 | { 521 | typename std::vector::iterator rit; 522 | for(rit = m_ifile.begin(); rit != m_ifile.end(); ++rit) 523 | { 524 | int n = (int)rit->size(); 525 | if(ni > n) 526 | { 527 | rit->resize(ni); 528 | rit->resize(n); 529 | } 530 | } 531 | } 532 | 533 | if(m_use_di && (int)m_dfile.size() < nd) 534 | { 535 | m_dfile.resize(nd); 536 | } 537 | } 538 | 539 | // -------------------------------------------------------------------------- 540 | 541 | template 542 | inline unsigned int TemplatedDatabase::size() const 543 | { 544 | return m_nentries; 545 | } 546 | 547 | // -------------------------------------------------------------------------- 548 | 549 | template 550 | inline bool TemplatedDatabase::usingDirectIndex() const 551 | { 552 | return m_use_di; 553 | } 554 | 555 | // -------------------------------------------------------------------------- 556 | 557 | template 558 | inline int TemplatedDatabase::getDirectIndexLevels() const 559 | { 560 | return m_dilevels; 561 | } 562 | 563 | // -------------------------------------------------------------------------- 564 | 565 | template 566 | void TemplatedDatabase::query( 567 | const std::vector &features, 568 | QueryResults &ret, int max_results, int max_id) const 569 | { 570 | BowVector vec; 571 | m_voc->transform(features, vec); 572 | query(vec, ret, max_results, max_id); 573 | } 574 | 575 | // -------------------------------------------------------------------------- 576 | 577 | template 578 | void TemplatedDatabase::query( 579 | const BowVector &vec, 580 | QueryResults &ret, int max_results, int max_id) const 581 | { 582 | ret.resize(0); 583 | 584 | switch(m_voc->getScoringType()) 585 | { 586 | case L1_NORM: 587 | queryL1(vec, ret, max_results, max_id); 588 | break; 589 | 590 | case L2_NORM: 591 | queryL2(vec, ret, max_results, max_id); 592 | break; 593 | 594 | case CHI_SQUARE: 595 | queryChiSquare(vec, ret, max_results, max_id); 596 | break; 597 | 598 | case KL: 599 | queryKL(vec, ret, max_results, max_id); 600 | break; 601 | 602 | case BHATTACHARYYA: 603 | queryBhattacharyya(vec, ret, max_results, max_id); 604 | break; 605 | 606 | case DOT_PRODUCT: 607 | queryDotProduct(vec, ret, max_results, max_id); 608 | break; 609 | } 610 | } 611 | 612 | // -------------------------------------------------------------------------- 613 | 614 | template 615 | void TemplatedDatabase::queryL1(const BowVector &vec, 616 | QueryResults &ret, int max_results, int max_id) const 617 | { 618 | BowVector::const_iterator vit; 619 | typename IFRow::const_iterator rit; 620 | 621 | std::map pairs; 622 | std::map::iterator pit; 623 | 624 | for(vit = vec.begin(); vit != vec.end(); ++vit) 625 | { 626 | const WordId word_id = vit->first; 627 | const WordValue& qvalue = vit->second; 628 | 629 | const IFRow& row = m_ifile[word_id]; 630 | 631 | // IFRows are sorted in ascending entry_id order 632 | 633 | for(rit = row.begin(); rit != row.end(); ++rit) 634 | { 635 | const EntryId entry_id = rit->entry_id; 636 | const WordValue& dvalue = rit->word_weight; 637 | 638 | if((int)entry_id < max_id || max_id == -1) 639 | { 640 | double value = fabs(qvalue - dvalue) - fabs(qvalue) - fabs(dvalue); 641 | 642 | pit = pairs.lower_bound(entry_id); 643 | if(pit != pairs.end() && !(pairs.key_comp()(entry_id, pit->first))) 644 | { 645 | pit->second += value; 646 | } 647 | else 648 | { 649 | pairs.insert(pit, 650 | std::map::value_type(entry_id, value)); 651 | } 652 | } 653 | 654 | } // for each inverted row 655 | } // for each query word 656 | 657 | // move to vector 658 | ret.reserve(pairs.size()); 659 | for(pit = pairs.begin(); pit != pairs.end(); ++pit) 660 | { 661 | ret.push_back(Result(pit->first, pit->second)); 662 | } 663 | 664 | // resulting "scores" are now in [-2 best .. 0 worst] 665 | 666 | // sort vector in ascending order of score 667 | std::sort(ret.begin(), ret.end()); 668 | // (ret is inverted now --the lower the better--) 669 | 670 | // cut vector 671 | if(max_results > 0 && (int)ret.size() > max_results) 672 | ret.resize(max_results); 673 | 674 | // complete and scale score to [0 worst .. 1 best] 675 | // ||v - w||_{L1} = 2 + Sum(|v_i - w_i| - |v_i| - |w_i|) 676 | // for all i | v_i != 0 and w_i != 0 677 | // (Nister, 2006) 678 | // scaled_||v - w||_{L1} = 1 - 0.5 * ||v - w||_{L1} 679 | QueryResults::iterator qit; 680 | for(qit = ret.begin(); qit != ret.end(); qit++) 681 | qit->Score = -qit->Score/2.0; 682 | } 683 | 684 | // -------------------------------------------------------------------------- 685 | 686 | template 687 | void TemplatedDatabase::queryL2(const BowVector &vec, 688 | QueryResults &ret, int max_results, int max_id) const 689 | { 690 | BowVector::const_iterator vit; 691 | typename IFRow::const_iterator rit; 692 | 693 | std::map pairs; 694 | std::map::iterator pit; 695 | 696 | //map counters; 697 | //map::iterator cit; 698 | 699 | for(vit = vec.begin(); vit != vec.end(); ++vit) 700 | { 701 | const WordId word_id = vit->first; 702 | const WordValue& qvalue = vit->second; 703 | 704 | const IFRow& row = m_ifile[word_id]; 705 | 706 | // IFRows are sorted in ascending entry_id order 707 | 708 | for(rit = row.begin(); rit != row.end(); ++rit) 709 | { 710 | const EntryId entry_id = rit->entry_id; 711 | const WordValue& dvalue = rit->word_weight; 712 | 713 | if((int)entry_id < max_id || max_id == -1) 714 | { 715 | double value = - qvalue * dvalue; // minus sign for sorting trick 716 | 717 | pit = pairs.lower_bound(entry_id); 718 | //cit = counters.lower_bound(entry_id); 719 | if(pit != pairs.end() && !(pairs.key_comp()(entry_id, pit->first))) 720 | { 721 | pit->second += value; 722 | //cit->second += 1; 723 | } 724 | else 725 | { 726 | pairs.insert(pit, 727 | std::map::value_type(entry_id, value)); 728 | 729 | //counters.insert(cit, 730 | // map::value_type(entry_id, 1)); 731 | } 732 | } 733 | 734 | } // for each inverted row 735 | } // for each query word 736 | 737 | // move to vector 738 | ret.reserve(pairs.size()); 739 | //cit = counters.begin(); 740 | for(pit = pairs.begin(); pit != pairs.end(); ++pit)//, ++cit) 741 | { 742 | ret.push_back(Result(pit->first, pit->second));// / cit->second)); 743 | } 744 | 745 | // resulting "scores" are now in [-1 best .. 0 worst] 746 | 747 | // sort vector in ascending order of score 748 | std::sort(ret.begin(), ret.end()); 749 | // (ret is inverted now --the lower the better--) 750 | 751 | // cut vector 752 | if(max_results > 0 && (int)ret.size() > max_results) 753 | ret.resize(max_results); 754 | 755 | // complete and scale score to [0 worst .. 1 best] 756 | // ||v - w||_{L2} = sqrt( 2 - 2 * Sum(v_i * w_i) 757 | // for all i | v_i != 0 and w_i != 0 ) 758 | // (Nister, 2006) 759 | QueryResults::iterator qit; 760 | for(qit = ret.begin(); qit != ret.end(); qit++) 761 | { 762 | if(qit->Score <= -1.0) // rounding error 763 | qit->Score = 1.0; 764 | else 765 | qit->Score = 1.0 - sqrt(1.0 + qit->Score); // [0..1] 766 | // the + sign is ok, it is due to - sign in 767 | // value = - qvalue * dvalue 768 | } 769 | 770 | } 771 | 772 | // -------------------------------------------------------------------------- 773 | 774 | template 775 | void TemplatedDatabase::queryChiSquare(const BowVector &vec, 776 | QueryResults &ret, int max_results, int max_id) const 777 | { 778 | BowVector::const_iterator vit; 779 | typename IFRow::const_iterator rit; 780 | 781 | std::map > pairs; 782 | std::map >::iterator pit; 783 | 784 | std::map > sums; // < sum vi, sum wi > 785 | std::map >::iterator sit; 786 | 787 | // In the current implementation, we suppose vec is not normalized 788 | 789 | //map expected; 790 | //map::iterator eit; 791 | 792 | for(vit = vec.begin(); vit != vec.end(); ++vit) 793 | { 794 | const WordId word_id = vit->first; 795 | const WordValue& qvalue = vit->second; 796 | 797 | const IFRow& row = m_ifile[word_id]; 798 | 799 | // IFRows are sorted in ascending entry_id order 800 | 801 | for(rit = row.begin(); rit != row.end(); ++rit) 802 | { 803 | const EntryId entry_id = rit->entry_id; 804 | const WordValue& dvalue = rit->word_weight; 805 | 806 | if((int)entry_id < max_id || max_id == -1) 807 | { 808 | // (v-w)^2/(v+w) - v - w = -4 vw/(v+w) 809 | // we move the 4 out 810 | double value = 0; 811 | if(qvalue + dvalue != 0.0) // words may have weight zero 812 | value = - qvalue * dvalue / (qvalue + dvalue); 813 | 814 | pit = pairs.lower_bound(entry_id); 815 | sit = sums.lower_bound(entry_id); 816 | //eit = expected.lower_bound(entry_id); 817 | if(pit != pairs.end() && !(pairs.key_comp()(entry_id, pit->first))) 818 | { 819 | pit->second.first += value; 820 | pit->second.second += 1; 821 | //eit->second += dvalue; 822 | sit->second.first += qvalue; 823 | sit->second.second += dvalue; 824 | } 825 | else 826 | { 827 | pairs.insert(pit, 828 | std::map >::value_type(entry_id, 829 | std::make_pair(value, 1) )); 830 | //expected.insert(eit, 831 | // map::value_type(entry_id, dvalue)); 832 | 833 | sums.insert(sit, 834 | std::map >::value_type(entry_id, 835 | std::make_pair(qvalue, dvalue) )); 836 | } 837 | } 838 | 839 | } // for each inverted row 840 | } // for each query word 841 | 842 | // move to vector 843 | ret.reserve(pairs.size()); 844 | sit = sums.begin(); 845 | for(pit = pairs.begin(); pit != pairs.end(); ++pit, ++sit) 846 | { 847 | if(pit->second.second >= MIN_COMMON_WORDS) 848 | { 849 | ret.push_back(Result(pit->first, pit->second.first)); 850 | ret.back().nWords = pit->second.second; 851 | ret.back().sumCommonVi = sit->second.first; 852 | ret.back().sumCommonWi = sit->second.second; 853 | ret.back().expectedChiScore = 854 | 2 * sit->second.second / (1 + sit->second.second); 855 | } 856 | 857 | //ret.push_back(Result(pit->first, pit->second)); 858 | } 859 | 860 | // resulting "scores" are now in [-2 best .. 0 worst] 861 | // we have to add +2 to the scores to obtain the chi square score 862 | 863 | // sort vector in ascending order of score 864 | std::sort(ret.begin(), ret.end()); 865 | // (ret is inverted now --the lower the better--) 866 | 867 | // cut vector 868 | if(max_results > 0 && (int)ret.size() > max_results) 869 | ret.resize(max_results); 870 | 871 | // complete and scale score to [0 worst .. 1 best] 872 | QueryResults::iterator qit; 873 | for(qit = ret.begin(); qit != ret.end(); qit++) 874 | { 875 | // this takes the 4 into account 876 | qit->Score = - 2. * qit->Score; // [0..1] 877 | 878 | qit->chiScore = qit->Score; 879 | } 880 | 881 | } 882 | 883 | // -------------------------------------------------------------------------- 884 | 885 | template 886 | void TemplatedDatabase::queryKL(const BowVector &vec, 887 | QueryResults &ret, int max_results, int max_id) const 888 | { 889 | BowVector::const_iterator vit; 890 | typename IFRow::const_iterator rit; 891 | 892 | std::map pairs; 893 | std::map::iterator pit; 894 | 895 | for(vit = vec.begin(); vit != vec.end(); ++vit) 896 | { 897 | const WordId word_id = vit->first; 898 | const WordValue& vi = vit->second; 899 | 900 | const IFRow& row = m_ifile[word_id]; 901 | 902 | // IFRows are sorted in ascending entry_id order 903 | 904 | for(rit = row.begin(); rit != row.end(); ++rit) 905 | { 906 | const EntryId entry_id = rit->entry_id; 907 | const WordValue& wi = rit->word_weight; 908 | 909 | if((int)entry_id < max_id || max_id == -1) 910 | { 911 | double value = 0; 912 | if(vi != 0 && wi != 0) value = vi * log(vi/wi); 913 | 914 | pit = pairs.lower_bound(entry_id); 915 | if(pit != pairs.end() && !(pairs.key_comp()(entry_id, pit->first))) 916 | { 917 | pit->second += value; 918 | } 919 | else 920 | { 921 | pairs.insert(pit, 922 | std::map::value_type(entry_id, value)); 923 | } 924 | } 925 | 926 | } // for each inverted row 927 | } // for each query word 928 | 929 | // resulting "scores" are now in [-X worst .. 0 best .. X worst] 930 | // but we cannot make sure which ones are better without calculating 931 | // the complete score 932 | 933 | // complete scores and move to vector 934 | ret.reserve(pairs.size()); 935 | for(pit = pairs.begin(); pit != pairs.end(); ++pit) 936 | { 937 | EntryId eid = pit->first; 938 | double value = 0.0; 939 | 940 | for(vit = vec.begin(); vit != vec.end(); ++vit) 941 | { 942 | const WordValue &vi = vit->second; 943 | const IFRow& row = m_ifile[vit->first]; 944 | 945 | if(vi != 0) 946 | { 947 | if(row.end() == find(row.begin(), row.end(), eid )) 948 | { 949 | value += vi * (log(vi) - GeneralScoring::LOG_EPS); 950 | } 951 | } 952 | } 953 | 954 | pit->second += value; 955 | 956 | // to vector 957 | ret.push_back(Result(pit->first, pit->second)); 958 | } 959 | 960 | // real scores are now in [0 best .. X worst] 961 | 962 | // sort vector in ascending order 963 | // (scores are inverted now --the lower the better--) 964 | std::sort(ret.begin(), ret.end()); 965 | 966 | // cut vector 967 | if(max_results > 0 && (int)ret.size() > max_results) 968 | ret.resize(max_results); 969 | 970 | // cannot scale scores 971 | 972 | } 973 | 974 | // -------------------------------------------------------------------------- 975 | 976 | template 977 | void TemplatedDatabase::queryBhattacharyya( 978 | const BowVector &vec, QueryResults &ret, int max_results, int max_id) const 979 | { 980 | BowVector::const_iterator vit; 981 | typename IFRow::const_iterator rit; 982 | 983 | //map pairs; 984 | //map::iterator pit; 985 | 986 | std::map > pairs; // > 987 | std::map >::iterator pit; 988 | 989 | for(vit = vec.begin(); vit != vec.end(); ++vit) 990 | { 991 | const WordId word_id = vit->first; 992 | const WordValue& qvalue = vit->second; 993 | 994 | const IFRow& row = m_ifile[word_id]; 995 | 996 | // IFRows are sorted in ascending entry_id order 997 | 998 | for(rit = row.begin(); rit != row.end(); ++rit) 999 | { 1000 | const EntryId entry_id = rit->entry_id; 1001 | const WordValue& dvalue = rit->word_weight; 1002 | 1003 | if((int)entry_id < max_id || max_id == -1) 1004 | { 1005 | double value = sqrt(qvalue * dvalue); 1006 | 1007 | pit = pairs.lower_bound(entry_id); 1008 | if(pit != pairs.end() && !(pairs.key_comp()(entry_id, pit->first))) 1009 | { 1010 | pit->second.first += value; 1011 | pit->second.second += 1; 1012 | } 1013 | else 1014 | { 1015 | pairs.insert(pit, 1016 | std::map >::value_type(entry_id, 1017 | std::make_pair(value, 1))); 1018 | } 1019 | } 1020 | 1021 | } // for each inverted row 1022 | } // for each query word 1023 | 1024 | // move to vector 1025 | ret.reserve(pairs.size()); 1026 | for(pit = pairs.begin(); pit != pairs.end(); ++pit) 1027 | { 1028 | if(pit->second.second >= MIN_COMMON_WORDS) 1029 | { 1030 | ret.push_back(Result(pit->first, pit->second.first)); 1031 | ret.back().nWords = pit->second.second; 1032 | ret.back().bhatScore = pit->second.first; 1033 | } 1034 | } 1035 | 1036 | // scores are already in [0..1] 1037 | 1038 | // sort vector in descending order 1039 | std::sort(ret.begin(), ret.end(), Result::gt); 1040 | 1041 | // cut vector 1042 | if(max_results > 0 && (int)ret.size() > max_results) 1043 | ret.resize(max_results); 1044 | 1045 | } 1046 | 1047 | // --------------------------------------------------------------------------- 1048 | 1049 | template 1050 | void TemplatedDatabase::queryDotProduct( 1051 | const BowVector &vec, QueryResults &ret, int max_results, int max_id) const 1052 | { 1053 | BowVector::const_iterator vit; 1054 | typename IFRow::const_iterator rit; 1055 | 1056 | std::map pairs; 1057 | std::map::iterator pit; 1058 | 1059 | for(vit = vec.begin(); vit != vec.end(); ++vit) 1060 | { 1061 | const WordId word_id = vit->first; 1062 | const WordValue& qvalue = vit->second; 1063 | 1064 | const IFRow& row = m_ifile[word_id]; 1065 | 1066 | // IFRows are sorted in ascending entry_id order 1067 | 1068 | for(rit = row.begin(); rit != row.end(); ++rit) 1069 | { 1070 | const EntryId entry_id = rit->entry_id; 1071 | const WordValue& dvalue = rit->word_weight; 1072 | 1073 | if((int)entry_id < max_id || max_id == -1) 1074 | { 1075 | double value; 1076 | if(this->m_voc->getWeightingType() == BINARY) 1077 | value = 1; 1078 | else 1079 | value = qvalue * dvalue; 1080 | 1081 | pit = pairs.lower_bound(entry_id); 1082 | if(pit != pairs.end() && !(pairs.key_comp()(entry_id, pit->first))) 1083 | { 1084 | pit->second += value; 1085 | } 1086 | else 1087 | { 1088 | pairs.insert(pit, 1089 | std::map::value_type(entry_id, value)); 1090 | } 1091 | } 1092 | 1093 | } // for each inverted row 1094 | } // for each query word 1095 | 1096 | // move to vector 1097 | ret.reserve(pairs.size()); 1098 | for(pit = pairs.begin(); pit != pairs.end(); ++pit) 1099 | { 1100 | ret.push_back(Result(pit->first, pit->second)); 1101 | } 1102 | 1103 | // scores are the greater the better 1104 | 1105 | // sort vector in descending order 1106 | std::sort(ret.begin(), ret.end(), Result::gt); 1107 | 1108 | // cut vector 1109 | if(max_results > 0 && (int)ret.size() > max_results) 1110 | ret.resize(max_results); 1111 | 1112 | // these scores cannot be scaled 1113 | } 1114 | 1115 | // --------------------------------------------------------------------------- 1116 | 1117 | template 1118 | const FeatureVector& TemplatedDatabase::retrieveFeatures 1119 | (EntryId id) const 1120 | { 1121 | assert(id < size()); 1122 | return m_dfile[id]; 1123 | } 1124 | 1125 | // -------------------------------------------------------------------------- 1126 | 1127 | template 1128 | void TemplatedDatabase::save(const std::string &filename) const 1129 | { 1130 | cv::FileStorage fs(filename.c_str(), cv::FileStorage::WRITE); 1131 | if(!fs.isOpened()) throw std::string("Could not open file ") + filename; 1132 | 1133 | save(fs); 1134 | } 1135 | 1136 | // -------------------------------------------------------------------------- 1137 | 1138 | template 1139 | void TemplatedDatabase::save(cv::FileStorage &fs, 1140 | const std::string &name) const 1141 | { 1142 | // Format YAML: 1143 | // vocabulary { ... see TemplatedVocabulary::save } 1144 | // database 1145 | // { 1146 | // nEntries: 1147 | // usingDI: 1148 | // diLevels: 1149 | // invertedIndex 1150 | // [ 1151 | // [ 1152 | // { 1153 | // imageId: 1154 | // weight: 1155 | // } 1156 | // ] 1157 | // ] 1158 | // directIndex 1159 | // [ 1160 | // [ 1161 | // { 1162 | // nodeId: 1163 | // features: [ ] 1164 | // } 1165 | // ] 1166 | // ] 1167 | 1168 | // invertedIndex[i] is for the i-th word 1169 | // directIndex[i] is for the i-th entry 1170 | // directIndex may be empty if not using direct index 1171 | // 1172 | // imageId's and nodeId's must be stored in ascending order 1173 | // (according to the construction of the indexes) 1174 | 1175 | m_voc->save(fs); 1176 | 1177 | fs << name << "{"; 1178 | 1179 | fs << "nEntries" << m_nentries; 1180 | fs << "usingDI" << (m_use_di ? 1 : 0); 1181 | fs << "diLevels" << m_dilevels; 1182 | 1183 | fs << "invertedIndex" << "["; 1184 | 1185 | typename InvertedFile::const_iterator iit; 1186 | typename IFRow::const_iterator irit; 1187 | for(iit = m_ifile.begin(); iit != m_ifile.end(); ++iit) 1188 | { 1189 | fs << "["; // word of IF 1190 | for(irit = iit->begin(); irit != iit->end(); ++irit) 1191 | { 1192 | fs << "{:" 1193 | << "imageId" << (int)irit->entry_id 1194 | << "weight" << irit->word_weight 1195 | << "}"; 1196 | } 1197 | fs << "]"; // word of IF 1198 | } 1199 | 1200 | fs << "]"; // invertedIndex 1201 | 1202 | fs << "directIndex" << "["; 1203 | 1204 | typename DirectFile::const_iterator dit; 1205 | typename FeatureVector::const_iterator drit; 1206 | for(dit = m_dfile.begin(); dit != m_dfile.end(); ++dit) 1207 | { 1208 | fs << "["; // entry of DF 1209 | 1210 | for(drit = dit->begin(); drit != dit->end(); ++drit) 1211 | { 1212 | NodeId nid = drit->first; 1213 | const std::vector& features = drit->second; 1214 | 1215 | // save info of last_nid 1216 | fs << "{"; 1217 | fs << "nodeId" << (int)nid; 1218 | // msvc++ 2010 with opencv 2.3.1 does not allow FileStorage::operator<< 1219 | // with vectors of unsigned int 1220 | fs << "features" << "[" 1221 | << *(const std::vector*)(&features) << "]"; 1222 | fs << "}"; 1223 | } 1224 | 1225 | fs << "]"; // entry of DF 1226 | } 1227 | 1228 | fs << "]"; // directIndex 1229 | 1230 | fs << "}"; // database 1231 | } 1232 | 1233 | // -------------------------------------------------------------------------- 1234 | 1235 | template 1236 | void TemplatedDatabase::load(const std::string &filename) 1237 | { 1238 | cv::FileStorage fs(filename.c_str(), cv::FileStorage::READ); 1239 | if(!fs.isOpened()) throw std::string("Could not open file ") + filename; 1240 | 1241 | load(fs); 1242 | } 1243 | 1244 | // -------------------------------------------------------------------------- 1245 | 1246 | template 1247 | void TemplatedDatabase::load(const cv::FileStorage &fs, 1248 | const std::string &name) 1249 | { 1250 | // load voc first 1251 | // subclasses must instantiate m_voc before calling this ::load 1252 | if(!m_voc) m_voc = new TemplatedVocabulary; 1253 | 1254 | m_voc->load(fs); 1255 | 1256 | // load database now 1257 | clear(); // resizes inverted file 1258 | 1259 | cv::FileNode fdb = fs[name]; 1260 | 1261 | m_nentries = (int)fdb["nEntries"]; 1262 | m_use_di = (int)fdb["usingDI"] != 0; 1263 | m_dilevels = (int)fdb["diLevels"]; 1264 | 1265 | cv::FileNode fn = fdb["invertedIndex"]; 1266 | for(WordId wid = 0; wid < fn.size(); ++wid) 1267 | { 1268 | cv::FileNode fw = fn[wid]; 1269 | 1270 | for(unsigned int i = 0; i < fw.size(); ++i) 1271 | { 1272 | EntryId eid = (int)fw[i]["imageId"]; 1273 | WordValue v = fw[i]["weight"]; 1274 | 1275 | m_ifile[wid].push_back(IFPair(eid, v)); 1276 | } 1277 | } 1278 | 1279 | if(m_use_di) 1280 | { 1281 | fn = fdb["directIndex"]; 1282 | 1283 | m_dfile.resize(fn.size()); 1284 | assert(m_nentries == (int)fn.size()); 1285 | 1286 | FeatureVector::iterator dit; 1287 | for(EntryId eid = 0; eid < fn.size(); ++eid) 1288 | { 1289 | cv::FileNode fe = fn[eid]; 1290 | 1291 | m_dfile[eid].clear(); 1292 | for(unsigned int i = 0; i < fe.size(); ++i) 1293 | { 1294 | NodeId nid = (int)fe[i]["nodeId"]; 1295 | 1296 | dit = m_dfile[eid].insert(m_dfile[eid].end(), 1297 | make_pair(nid, std::vector() )); 1298 | 1299 | // this failed to compile with some opencv versions (2.3.1) 1300 | //fe[i]["features"] >> dit->second; 1301 | 1302 | // this was ok until OpenCV 2.4.1 1303 | //std::vector aux; 1304 | //fe[i]["features"] >> aux; // OpenCV < 2.4.1 1305 | //dit->second.resize(aux.size()); 1306 | //std::copy(aux.begin(), aux.end(), dit->second.begin()); 1307 | 1308 | cv::FileNode ff = fe[i]["features"][0]; 1309 | dit->second.reserve(ff.size()); 1310 | 1311 | cv::FileNodeIterator ffit; 1312 | for(ffit = ff.begin(); ffit != ff.end(); ++ffit) 1313 | { 1314 | dit->second.push_back((int)*ffit); 1315 | } 1316 | } 1317 | } // for each entry 1318 | } // if use_id 1319 | 1320 | } 1321 | 1322 | // -------------------------------------------------------------------------- 1323 | 1324 | /** 1325 | * Writes printable information of the database 1326 | * @param os stream to write to 1327 | * @param db 1328 | */ 1329 | template 1330 | std::ostream& operator<<(std::ostream &os, 1331 | const TemplatedDatabase &db) 1332 | { 1333 | os << "Database: Entries = " << db.size() << ", " 1334 | "Using direct index = " << (db.usingDirectIndex() ? "yes" : "no"); 1335 | 1336 | if(db.usingDirectIndex()) 1337 | os << ", Direct index levels = " << db.getDirectIndexLevels(); 1338 | 1339 | os << ". " << *db.getVocabulary(); 1340 | return os; 1341 | } 1342 | 1343 | // -------------------------------------------------------------------------- 1344 | 1345 | } // namespace DBoW2 1346 | 1347 | #endif 1348 | -------------------------------------------------------------------------------- /DBoW2/package.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | dbow2 5 | 1.1.0 6 | 7 | Enhanced hierarchical bag-of-word library for C++ 8 | 9 | Dorian Gálvez-López 10 | BSD + notification 11 | 12 | cmake 13 | 14 | libopencv-dev 15 | 16 | 17 | cmake 18 | 19 | 20 | -------------------------------------------------------------------------------- /DBoW2/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 | unsigned int i = 0; 92 | const unsigned int N = v.size(); 93 | for(vit = v.begin(); vit != v.end(); ++vit, ++i) 94 | { 95 | out << "<" << vit->first << ", " << vit->second << ">"; 96 | 97 | if(i < N-1) out << ", "; 98 | } 99 | return out; 100 | } 101 | 102 | // -------------------------------------------------------------------------- 103 | 104 | void BowVector::saveM(const std::string &filename, size_t W) const 105 | { 106 | std::fstream f(filename.c_str(), std::ios::out); 107 | 108 | WordId last = 0; 109 | BowVector::const_iterator bit; 110 | for(bit = this->begin(); bit != this->end(); ++bit) 111 | { 112 | for(; last < bit->first; ++last) 113 | { 114 | f << "0 "; 115 | } 116 | f << bit->second << " "; 117 | 118 | last = bit->first + 1; 119 | } 120 | for(; last < (WordId)W; ++last) 121 | f << "0 "; 122 | 123 | f.close(); 124 | } 125 | 126 | // -------------------------------------------------------------------------- 127 | 128 | } // namespace DBoW2 129 | 130 | -------------------------------------------------------------------------------- /DBoW2/src/DBoW2.cmake.in: -------------------------------------------------------------------------------- 1 | FIND_LIBRARY(DBoW2_LIBRARY DBoW2 2 | PATHS "@CMAKE_INSTALL_PREFIX@/lib" 3 | ) 4 | FIND_PATH(DBoW2_INCLUDE_DIR DBoW2.h 5 | PATHS "@CMAKE_INSTALL_PREFIX@/include/@PROJECT_NAME@" 6 | ) 7 | LIST(APPEND DBoW2_INCLUDE_DIR ${DBoW2_INCLUDE_DIR}/../) 8 | SET(DBoW2_LIBRARIES ${DBoW2_LIBRARY}) 9 | SET(DBoW2_LIBS ${DBoW2_LIBRARY}) 10 | SET(DBoW2_INCLUDE_DIRS ${DBoW2_INCLUDE_DIR}) 11 | -------------------------------------------------------------------------------- /DBoW2/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 "FBrief.h" 15 | 16 | using namespace std; 17 | 18 | namespace DBoW2 { 19 | 20 | // -------------------------------------------------------------------------- 21 | 22 | void FBrief::meanValue(const std::vector &descriptors, 23 | FBrief::TDescriptor &mean) 24 | { 25 | mean.reset(); 26 | 27 | if(descriptors.empty()) return; 28 | 29 | const int N2 = descriptors.size() / 2; 30 | 31 | vector counters(FBrief::L, 0); 32 | 33 | vector::const_iterator it; 34 | for(it = descriptors.begin(); it != descriptors.end(); ++it) 35 | { 36 | const FBrief::TDescriptor &desc = **it; 37 | for(int i = 0; i < FBrief::L; ++i) 38 | { 39 | if(desc[i]) counters[i]++; 40 | } 41 | } 42 | 43 | for(int i = 0; i < FBrief::L; ++i) 44 | { 45 | if(counters[i] > N2) mean.set(i); 46 | } 47 | 48 | } 49 | 50 | // -------------------------------------------------------------------------- 51 | 52 | double FBrief::distance(const FBrief::TDescriptor &a, 53 | const FBrief::TDescriptor &b) 54 | { 55 | return (double)(a^b).count(); 56 | } 57 | 58 | // -------------------------------------------------------------------------- 59 | 60 | std::string FBrief::toString(const FBrief::TDescriptor &a) 61 | { 62 | return a.to_string(); // reversed 63 | } 64 | 65 | // -------------------------------------------------------------------------- 66 | 67 | void FBrief::fromString(FBrief::TDescriptor &a, const std::string &s) 68 | { 69 | stringstream ss(s); 70 | ss >> a; 71 | } 72 | 73 | // -------------------------------------------------------------------------- 74 | 75 | void FBrief::toMat32F(const std::vector &descriptors, 76 | cv::Mat &mat) 77 | { 78 | if(descriptors.empty()) 79 | { 80 | mat.release(); 81 | return; 82 | } 83 | 84 | const int N = descriptors.size(); 85 | 86 | mat.create(N, FBrief::L, CV_32F); 87 | 88 | for(int i = 0; i < N; ++i) 89 | { 90 | const TDescriptor& desc = descriptors[i]; 91 | float *p = mat.ptr(i); 92 | for(int j = 0; j < FBrief::L; ++j, ++p) 93 | { 94 | *p = (desc[j] ? 1.f : 0.f); 95 | } 96 | } 97 | } 98 | 99 | // -------------------------------------------------------------------------- 100 | 101 | } // namespace DBoW2 102 | 103 | -------------------------------------------------------------------------------- /DBoW2/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 "FORB.h" 17 | 18 | using namespace std; 19 | 20 | namespace DBoW2 { 21 | 22 | // -------------------------------------------------------------------------- 23 | 24 | void FORB::meanValue(const std::vector &descriptors, 25 | FORB::TDescriptor &mean) 26 | { 27 | if(descriptors.empty()) 28 | { 29 | mean.release(); 30 | return; 31 | } 32 | else if(descriptors.size() == 1) 33 | { 34 | mean = descriptors[0]->clone(); 35 | } 36 | else 37 | { 38 | vector sum(FORB::L * 8, 0); 39 | 40 | for(size_t i = 0; i < descriptors.size(); ++i) 41 | { 42 | const cv::Mat &d = *descriptors[i]; 43 | const unsigned char *p = d.ptr(); 44 | 45 | for(int j = 0; j < d.cols; ++j, ++p) 46 | { 47 | if(*p & (1 << 7)) ++sum[ j*8 ]; 48 | if(*p & (1 << 6)) ++sum[ j*8 + 1 ]; 49 | if(*p & (1 << 5)) ++sum[ j*8 + 2 ]; 50 | if(*p & (1 << 4)) ++sum[ j*8 + 3 ]; 51 | if(*p & (1 << 3)) ++sum[ j*8 + 4 ]; 52 | if(*p & (1 << 2)) ++sum[ j*8 + 5 ]; 53 | if(*p & (1 << 1)) ++sum[ j*8 + 6 ]; 54 | if(*p & (1)) ++sum[ j*8 + 7 ]; 55 | } 56 | } 57 | 58 | mean = cv::Mat::zeros(1, FORB::L, CV_8U); 59 | unsigned char *p = mean.ptr(); 60 | 61 | const int N2 = (int)descriptors.size() / 2 + descriptors.size() % 2; 62 | for(size_t i = 0; i < sum.size(); ++i) 63 | { 64 | if(sum[i] >= N2) 65 | { 66 | // set bit 67 | *p |= 1 << (7 - (i % 8)); 68 | } 69 | 70 | if(i % 8 == 7) ++p; 71 | } 72 | } 73 | } 74 | 75 | // -------------------------------------------------------------------------- 76 | 77 | double FORB::distance(const FORB::TDescriptor &a, 78 | const FORB::TDescriptor &b) 79 | { 80 | // Bit count function got from: 81 | // http://graphics.stanford.edu/~seander/bithacks.html#CountBitsSetKernighan 82 | // This implementation assumes that a.cols (CV_8U) % sizeof(uint64_t) == 0 83 | 84 | const uint64_t *pa, *pb; 85 | pa = a.ptr(); // a & b are actually CV_8U 86 | pb = b.ptr(); 87 | 88 | uint64_t v, ret = 0; 89 | for(size_t i = 0; i < a.cols / sizeof(uint64_t); ++i, ++pa, ++pb) 90 | { 91 | v = *pa ^ *pb; 92 | v = v - ((v >> 1) & (uint64_t)~(uint64_t)0/3); 93 | v = (v & (uint64_t)~(uint64_t)0/15*3) + ((v >> 2) & 94 | (uint64_t)~(uint64_t)0/15*3); 95 | v = (v + (v >> 4)) & (uint64_t)~(uint64_t)0/255*15; 96 | ret += (uint64_t)(v * ((uint64_t)~(uint64_t)0/255)) >> 97 | (sizeof(uint64_t) - 1) * CHAR_BIT; 98 | } 99 | 100 | return static_cast(ret); 101 | 102 | // // If uint64_t is not defined in your system, you can try this 103 | // // portable approach (requires DUtils from DLib) 104 | // const unsigned char *pa, *pb; 105 | // pa = a.ptr(); 106 | // pb = b.ptr(); 107 | // 108 | // int ret = 0; 109 | // for(int i = 0; i < a.cols; ++i, ++pa, ++pb) 110 | // { 111 | // ret += DUtils::LUT::ones8bits[ *pa ^ *pb ]; 112 | // } 113 | // 114 | // return ret; 115 | } 116 | 117 | // -------------------------------------------------------------------------- 118 | 119 | std::string FORB::toString(const FORB::TDescriptor &a) 120 | { 121 | stringstream ss; 122 | const unsigned char *p = a.ptr(); 123 | 124 | for(int i = 0; i < a.cols; ++i, ++p) 125 | { 126 | ss << (int)*p << " "; 127 | } 128 | 129 | return ss.str(); 130 | } 131 | 132 | // -------------------------------------------------------------------------- 133 | 134 | void FORB::fromString(FORB::TDescriptor &a, const std::string &s) 135 | { 136 | a.create(1, FORB::L, CV_8U); 137 | unsigned char *p = a.ptr(); 138 | 139 | stringstream ss(s); 140 | for(int i = 0; i < FORB::L; ++i, ++p) 141 | { 142 | int n; 143 | ss >> n; 144 | 145 | if(!ss.fail()) 146 | *p = (unsigned char)n; 147 | } 148 | 149 | } 150 | 151 | // -------------------------------------------------------------------------- 152 | 153 | void FORB::toMat32F(const std::vector &descriptors, 154 | cv::Mat &mat) 155 | { 156 | if(descriptors.empty()) 157 | { 158 | mat.release(); 159 | return; 160 | } 161 | 162 | const size_t N = descriptors.size(); 163 | 164 | mat.create(N, FORB::L*8, CV_32F); 165 | float *p = mat.ptr(); 166 | 167 | for(size_t i = 0; i < N; ++i) 168 | { 169 | const int C = descriptors[i].cols; 170 | const unsigned char *desc = descriptors[i].ptr(); 171 | 172 | for(int j = 0; j < C; ++j, p += 8) 173 | { 174 | p[0] = (desc[j] & (1 << 7) ? 1.f : 0.f); 175 | p[1] = (desc[j] & (1 << 6) ? 1.f : 0.f); 176 | p[2] = (desc[j] & (1 << 5) ? 1.f : 0.f); 177 | p[3] = (desc[j] & (1 << 4) ? 1.f : 0.f); 178 | p[4] = (desc[j] & (1 << 3) ? 1.f : 0.f); 179 | p[5] = (desc[j] & (1 << 2) ? 1.f : 0.f); 180 | p[6] = (desc[j] & (1 << 1) ? 1.f : 0.f); 181 | p[7] = (desc[j] & (1) ? 1.f : 0.f); 182 | } 183 | } 184 | } 185 | 186 | // -------------------------------------------------------------------------- 187 | 188 | void FORB::toMat32F(const cv::Mat &descriptors, cv::Mat &mat) 189 | { 190 | descriptors.convertTo(mat, CV_32F); 191 | } 192 | 193 | // -------------------------------------------------------------------------- 194 | 195 | void FORB::toMat8U(const std::vector &descriptors, 196 | cv::Mat &mat) 197 | { 198 | mat.create(descriptors.size(), FORB::L, CV_8U); 199 | 200 | unsigned char *p = mat.ptr(); 201 | 202 | for(size_t i = 0; i < descriptors.size(); ++i, p += FORB::L) 203 | { 204 | const unsigned char *d = descriptors[i].ptr(); 205 | std::copy(d, d + FORB::L, p); 206 | } 207 | 208 | } 209 | 210 | // -------------------------------------------------------------------------- 211 | 212 | } // namespace DBoW2 213 | 214 | -------------------------------------------------------------------------------- /DBoW2/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 | -------------------------------------------------------------------------------- /DBoW2/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 | -------------------------------------------------------------------------------- /DBoW2/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 | -------------------------------------------------------------------------------- /DBoW2/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 | -------------------------------------------------------------------------------- /ORB_SLAM_txt/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 2.8) 2 | project(ORB_SLAM_txt) 3 | 4 | IF(NOT CMAKE_BUILD_TYPE) 5 | SET(CMAKE_BUILD_TYPE Release) 6 | ENDIF() 7 | 8 | MESSAGE("Build type: " ${CMAKE_BUILD_TYPE}) 9 | 10 | set(CMAKE_C_FLAGS "${CMAKE_C_FLAGS} -Wall -O3 -march=native ") 11 | set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -Wall -O3 -march=native") 12 | 13 | # Check C++11 or C++0x support 14 | include(CheckCXXCompilerFlag) 15 | CHECK_CXX_COMPILER_FLAG("-std=c++11" COMPILER_SUPPORTS_CXX11) 16 | CHECK_CXX_COMPILER_FLAG("-std=c++0x" COMPILER_SUPPORTS_CXX0X) 17 | if(COMPILER_SUPPORTS_CXX11) 18 | set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -std=c++11") 19 | add_definitions(-DCOMPILEDWITHC11) 20 | message(STATUS "Using flag -std=c++11.") 21 | elseif(COMPILER_SUPPORTS_CXX0X) 22 | set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -std=c++0x") 23 | add_definitions(-DCOMPILEDWITHC0X) 24 | message(STATUS "Using flag -std=c++0x.") 25 | else() 26 | message(FATAL_ERROR "The compiler ${CMAKE_CXX_COMPILER} has no C++11 support. Please use a different C++ compiler.") 27 | endif() 28 | 29 | LIST(APPEND CMAKE_MODULE_PATH ${PROJECT_SOURCE_DIR}/cmake_modules) 30 | 31 | find_package(OpenCV 3.0 QUIET) 32 | if(NOT OpenCV_FOUND) 33 | find_package(OpenCV 2.4.3 QUIET) 34 | if(NOT OpenCV_FOUND) 35 | message(FATAL_ERROR "OpenCV > 2.4.3 not found.") 36 | endif() 37 | endif() 38 | 39 | find_package(Eigen3 3.1.0 REQUIRED) 40 | 41 | include_directories( 42 | ${PROJECT_SOURCE_DIR} 43 | ${PROJECT_SOURCE_DIR}/include 44 | ${EIGEN3_INCLUDE_DIR} 45 | ) 46 | 47 | set(CMAKE_LIBRARY_OUTPUT_DIRECTORY ${PROJECT_SOURCE_DIR}/lib) 48 | 49 | add_library(${PROJECT_NAME} SHARED 50 | src/Orb_vocab.cc 51 | ) 52 | 53 | target_link_libraries(${PROJECT_NAME} 54 | ${OpenCV_LIBS} 55 | ${EIGEN3_LIBS} 56 | ${PROJECT_SOURCE_DIR}/Thirdparty/DBoW2/lib/libDBoW2.so 57 | ) 58 | 59 | # Build examples 60 | 61 | set(CMAKE_RUNTIME_OUTPUT_DIRECTORY ${PROJECT_SOURCE_DIR}/Vocab) 62 | 63 | add_executable(convert_to_txt ${PROJECT_SOURCE_DIR}/Vocab/convert_to_txt.cpp) 64 | target_link_libraries(convert_to_txt ${PROJECT_NAME} ${PROJECT_SOURCE_DIR}/Thirdparty/DBoW2/lib/libDBoW2.so) -------------------------------------------------------------------------------- /ORB_SLAM_txt/Example_Vocab/Castle_Ruins_voc.zip: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manthan99/ORB_SLAM_vocab-build/7f99fefa293fdf9b670e15985944fbb494c0d618/ORB_SLAM_txt/Example_Vocab/Castle_Ruins_voc.zip -------------------------------------------------------------------------------- /ORB_SLAM_txt/Example_Vocab/ORBvoc.txt.tar.gz: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/manthan99/ORB_SLAM_vocab-build/7f99fefa293fdf9b670e15985944fbb494c0d618/ORB_SLAM_txt/Example_Vocab/ORBvoc.txt.tar.gz -------------------------------------------------------------------------------- /ORB_SLAM_txt/README.md: -------------------------------------------------------------------------------- 1 | Reference - https://github.com/raulmur/ORB_SLAM2 2 | -------------------------------------------------------------------------------- /ORB_SLAM_txt/Thirdparty/DBoW2/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 2.8) 2 | project(DBoW2) 3 | 4 | set(CMAKE_C_FLAGS "${CMAKE_C_FLAGS} -Wall -O3 -march=native ") 5 | set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -Wall -O3 -march=native") 6 | 7 | set(HDRS_DBOW2 8 | DBoW2/BowVector.h 9 | DBoW2/FORB.h 10 | DBoW2/FClass.h 11 | DBoW2/FeatureVector.h 12 | DBoW2/ScoringObject.h 13 | DBoW2/TemplatedVocabulary.h) 14 | set(SRCS_DBOW2 15 | DBoW2/BowVector.cpp 16 | DBoW2/FORB.cpp 17 | DBoW2/FeatureVector.cpp 18 | DBoW2/ScoringObject.cpp) 19 | 20 | set(HDRS_DUTILS 21 | DUtils/Random.h 22 | DUtils/Timestamp.h) 23 | set(SRCS_DUTILS 24 | DUtils/Random.cpp 25 | DUtils/Timestamp.cpp) 26 | 27 | find_package(OpenCV 3.0 QUIET) 28 | if(NOT OpenCV_FOUND) 29 | find_package(OpenCV 2.4.3 QUIET) 30 | if(NOT OpenCV_FOUND) 31 | message(FATAL_ERROR "OpenCV > 2.4.3 not found.") 32 | endif() 33 | endif() 34 | 35 | set(LIBRARY_OUTPUT_PATH ${PROJECT_SOURCE_DIR}/lib) 36 | 37 | include_directories(${OpenCV_INCLUDE_DIRS}) 38 | add_library(DBoW2 SHARED ${SRCS_DBOW2} ${SRCS_DUTILS}) 39 | target_link_libraries(DBoW2 ${OpenCV_LIBS}) 40 | 41 | -------------------------------------------------------------------------------- /ORB_SLAM_txt/Thirdparty/DBoW2/DBoW2/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 | -------------------------------------------------------------------------------- /ORB_SLAM_txt/Thirdparty/DBoW2/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 | -------------------------------------------------------------------------------- /ORB_SLAM_txt/Thirdparty/DBoW2/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 | -------------------------------------------------------------------------------- /ORB_SLAM_txt/Thirdparty/DBoW2/DBoW2/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 | * Distance function has been modified 9 | * 10 | */ 11 | 12 | 13 | #include 14 | #include 15 | #include 16 | #include 17 | 18 | #include "FORB.h" 19 | 20 | using namespace std; 21 | 22 | namespace DBoW2 { 23 | 24 | // -------------------------------------------------------------------------- 25 | 26 | const int FORB::L=32; 27 | 28 | void FORB::meanValue(const std::vector &descriptors, 29 | FORB::TDescriptor &mean) 30 | { 31 | if(descriptors.empty()) 32 | { 33 | mean.release(); 34 | return; 35 | } 36 | else if(descriptors.size() == 1) 37 | { 38 | mean = descriptors[0]->clone(); 39 | } 40 | else 41 | { 42 | vector sum(FORB::L * 8, 0); 43 | 44 | for(size_t i = 0; i < descriptors.size(); ++i) 45 | { 46 | const cv::Mat &d = *descriptors[i]; 47 | const unsigned char *p = d.ptr(); 48 | 49 | for(int j = 0; j < d.cols; ++j, ++p) 50 | { 51 | if(*p & (1 << 7)) ++sum[ j*8 ]; 52 | if(*p & (1 << 6)) ++sum[ j*8 + 1 ]; 53 | if(*p & (1 << 5)) ++sum[ j*8 + 2 ]; 54 | if(*p & (1 << 4)) ++sum[ j*8 + 3 ]; 55 | if(*p & (1 << 3)) ++sum[ j*8 + 4 ]; 56 | if(*p & (1 << 2)) ++sum[ j*8 + 5 ]; 57 | if(*p & (1 << 1)) ++sum[ j*8 + 6 ]; 58 | if(*p & (1)) ++sum[ j*8 + 7 ]; 59 | } 60 | } 61 | 62 | mean = cv::Mat::zeros(1, FORB::L, CV_8U); 63 | unsigned char *p = mean.ptr(); 64 | 65 | const int N2 = (int)descriptors.size() / 2 + descriptors.size() % 2; 66 | for(size_t i = 0; i < sum.size(); ++i) 67 | { 68 | if(sum[i] >= N2) 69 | { 70 | // set bit 71 | *p |= 1 << (7 - (i % 8)); 72 | } 73 | 74 | if(i % 8 == 7) ++p; 75 | } 76 | } 77 | } 78 | 79 | // -------------------------------------------------------------------------- 80 | 81 | int FORB::distance(const FORB::TDescriptor &a, 82 | const FORB::TDescriptor &b) 83 | { 84 | // Bit set count operation from 85 | // http://graphics.stanford.edu/~seander/bithacks.html#CountBitsSetParallel 86 | 87 | const int *pa = a.ptr(); 88 | const int *pb = b.ptr(); 89 | 90 | int dist=0; 91 | 92 | for(int i=0; i<8; i++, pa++, pb++) 93 | { 94 | unsigned int v = *pa ^ *pb; 95 | v = v - ((v >> 1) & 0x55555555); 96 | v = (v & 0x33333333) + ((v >> 2) & 0x33333333); 97 | dist += (((v + (v >> 4)) & 0xF0F0F0F) * 0x1010101) >> 24; 98 | } 99 | 100 | return dist; 101 | } 102 | 103 | // -------------------------------------------------------------------------- 104 | 105 | std::string FORB::toString(const FORB::TDescriptor &a) 106 | { 107 | stringstream ss; 108 | const unsigned char *p = a.ptr(); 109 | 110 | for(int i = 0; i < a.cols; ++i, ++p) 111 | { 112 | ss << (int)*p << " "; 113 | } 114 | 115 | return ss.str(); 116 | } 117 | 118 | // -------------------------------------------------------------------------- 119 | 120 | void FORB::fromString(FORB::TDescriptor &a, const std::string &s) 121 | { 122 | a.create(1, FORB::L, CV_8U); 123 | unsigned char *p = a.ptr(); 124 | 125 | stringstream ss(s); 126 | for(int i = 0; i < FORB::L; ++i, ++p) 127 | { 128 | int n; 129 | ss >> n; 130 | 131 | if(!ss.fail()) 132 | *p = (unsigned char)n; 133 | } 134 | 135 | } 136 | 137 | // -------------------------------------------------------------------------- 138 | 139 | void FORB::toMat32F(const std::vector &descriptors, 140 | cv::Mat &mat) 141 | { 142 | if(descriptors.empty()) 143 | { 144 | mat.release(); 145 | return; 146 | } 147 | 148 | const size_t N = descriptors.size(); 149 | 150 | mat.create(N, FORB::L*8, CV_32F); 151 | float *p = mat.ptr(); 152 | 153 | for(size_t i = 0; i < N; ++i) 154 | { 155 | const int C = descriptors[i].cols; 156 | const unsigned char *desc = descriptors[i].ptr(); 157 | 158 | for(int j = 0; j < C; ++j, p += 8) 159 | { 160 | p[0] = (desc[j] & (1 << 7) ? 1 : 0); 161 | p[1] = (desc[j] & (1 << 6) ? 1 : 0); 162 | p[2] = (desc[j] & (1 << 5) ? 1 : 0); 163 | p[3] = (desc[j] & (1 << 4) ? 1 : 0); 164 | p[4] = (desc[j] & (1 << 3) ? 1 : 0); 165 | p[5] = (desc[j] & (1 << 2) ? 1 : 0); 166 | p[6] = (desc[j] & (1 << 1) ? 1 : 0); 167 | p[7] = desc[j] & (1); 168 | } 169 | } 170 | } 171 | 172 | // -------------------------------------------------------------------------- 173 | 174 | void FORB::toMat8U(const std::vector &descriptors, 175 | cv::Mat &mat) 176 | { 177 | mat.create(descriptors.size(), 32, CV_8U); 178 | 179 | unsigned char *p = mat.ptr(); 180 | 181 | for(size_t i = 0; i < descriptors.size(); ++i, p += 32) 182 | { 183 | const unsigned char *d = descriptors[i].ptr(); 184 | std::copy(d, d+32, p); 185 | } 186 | 187 | } 188 | 189 | // -------------------------------------------------------------------------- 190 | 191 | } // namespace DBoW2 192 | 193 | 194 | -------------------------------------------------------------------------------- /ORB_SLAM_txt/Thirdparty/DBoW2/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 ORB 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 | 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 int 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 | static void toMat8U(const std::vector &descriptors, 72 | cv::Mat &mat); 73 | 74 | }; 75 | 76 | } // namespace DBoW2 77 | 78 | #endif 79 | 80 | -------------------------------------------------------------------------------- /ORB_SLAM_txt/Thirdparty/DBoW2/DBoW2/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 | -------------------------------------------------------------------------------- /ORB_SLAM_txt/Thirdparty/DBoW2/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 | -------------------------------------------------------------------------------- /ORB_SLAM_txt/Thirdparty/DBoW2/DBoW2/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 | -------------------------------------------------------------------------------- /ORB_SLAM_txt/Thirdparty/DBoW2/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 | /** 48 | * Macro for defining Scoring classes 49 | * @param NAME name of class 50 | * @param MUSTNORMALIZE if vectors must be normalized to compute the score 51 | * @param NORM type of norm to use when MUSTNORMALIZE 52 | */ 53 | #define __SCORING_CLASS(NAME, MUSTNORMALIZE, NORM) \ 54 | NAME: public GeneralScoring \ 55 | { public: \ 56 | /** \ 57 | * Computes score between two vectors \ 58 | * @param v \ 59 | * @param w \ 60 | * @return score between v and w \ 61 | */ \ 62 | virtual double score(const BowVector &v, const BowVector &w) const; \ 63 | \ 64 | /** \ 65 | * Says if a vector must be normalized according to the scoring function \ 66 | * @param norm (out) if true, norm to use 67 | * @return true iff vectors must be normalized \ 68 | */ \ 69 | virtual inline bool mustNormalize(LNorm &norm) const \ 70 | { norm = NORM; return MUSTNORMALIZE; } \ 71 | } 72 | 73 | /// L1 Scoring object 74 | class __SCORING_CLASS(L1Scoring, true, L1); 75 | 76 | /// L2 Scoring object 77 | class __SCORING_CLASS(L2Scoring, true, L2); 78 | 79 | /// Chi square Scoring object 80 | class __SCORING_CLASS(ChiSquareScoring, true, L1); 81 | 82 | /// KL divergence Scoring object 83 | class __SCORING_CLASS(KLScoring, true, L1); 84 | 85 | /// Bhattacharyya Scoring object 86 | class __SCORING_CLASS(BhattacharyyaScoring, true, L1); 87 | 88 | /// Dot product Scoring object 89 | class __SCORING_CLASS(DotProductScoring, false, L1); 90 | 91 | #undef __SCORING_CLASS 92 | 93 | } // namespace DBoW2 94 | 95 | #endif 96 | 97 | -------------------------------------------------------------------------------- /ORB_SLAM_txt/Thirdparty/DBoW2/DUtils/Random.cpp: -------------------------------------------------------------------------------- 1 | /* 2 | * File: Random.cpp 3 | * Project: DUtils library 4 | * Author: Dorian Galvez-Lopez 5 | * Date: April 2010 6 | * Description: manages pseudo-random numbers 7 | * License: see the LICENSE.txt file 8 | * 9 | */ 10 | 11 | #include "Random.h" 12 | #include "Timestamp.h" 13 | #include 14 | using namespace std; 15 | 16 | bool DUtils::Random::m_already_seeded = false; 17 | 18 | void DUtils::Random::SeedRand(){ 19 | Timestamp time; 20 | time.setToCurrentTime(); 21 | srand((unsigned)time.getFloatTime()); 22 | } 23 | 24 | void DUtils::Random::SeedRandOnce() 25 | { 26 | if(!m_already_seeded) 27 | { 28 | DUtils::Random::SeedRand(); 29 | m_already_seeded = true; 30 | } 31 | } 32 | 33 | void DUtils::Random::SeedRand(int seed) 34 | { 35 | srand(seed); 36 | } 37 | 38 | void DUtils::Random::SeedRandOnce(int seed) 39 | { 40 | if(!m_already_seeded) 41 | { 42 | DUtils::Random::SeedRand(seed); 43 | m_already_seeded = true; 44 | } 45 | } 46 | 47 | int DUtils::Random::RandomInt(int min, int max){ 48 | int d = max - min + 1; 49 | return int(((double)rand()/((double)RAND_MAX + 1.0)) * d) + min; 50 | } 51 | 52 | // --------------------------------------------------------------------------- 53 | // --------------------------------------------------------------------------- 54 | 55 | DUtils::Random::UnrepeatedRandomizer::UnrepeatedRandomizer(int min, int max) 56 | { 57 | if(min <= max) 58 | { 59 | m_min = min; 60 | m_max = max; 61 | } 62 | else 63 | { 64 | m_min = max; 65 | m_max = min; 66 | } 67 | 68 | createValues(); 69 | } 70 | 71 | // --------------------------------------------------------------------------- 72 | 73 | DUtils::Random::UnrepeatedRandomizer::UnrepeatedRandomizer 74 | (const DUtils::Random::UnrepeatedRandomizer& rnd) 75 | { 76 | *this = rnd; 77 | } 78 | 79 | // --------------------------------------------------------------------------- 80 | 81 | int DUtils::Random::UnrepeatedRandomizer::get() 82 | { 83 | if(empty()) createValues(); 84 | 85 | DUtils::Random::SeedRandOnce(); 86 | 87 | int k = DUtils::Random::RandomInt(0, m_values.size()-1); 88 | int ret = m_values[k]; 89 | m_values[k] = m_values.back(); 90 | m_values.pop_back(); 91 | 92 | return ret; 93 | } 94 | 95 | // --------------------------------------------------------------------------- 96 | 97 | void DUtils::Random::UnrepeatedRandomizer::createValues() 98 | { 99 | int n = m_max - m_min + 1; 100 | 101 | m_values.resize(n); 102 | for(int i = 0; i < n; ++i) m_values[i] = m_min + i; 103 | } 104 | 105 | // --------------------------------------------------------------------------- 106 | 107 | void DUtils::Random::UnrepeatedRandomizer::reset() 108 | { 109 | if((int)m_values.size() != m_max - m_min + 1) createValues(); 110 | } 111 | 112 | // --------------------------------------------------------------------------- 113 | 114 | DUtils::Random::UnrepeatedRandomizer& 115 | DUtils::Random::UnrepeatedRandomizer::operator= 116 | (const DUtils::Random::UnrepeatedRandomizer& rnd) 117 | { 118 | if(this != &rnd) 119 | { 120 | this->m_min = rnd.m_min; 121 | this->m_max = rnd.m_max; 122 | this->m_values = rnd.m_values; 123 | } 124 | return *this; 125 | } 126 | 127 | // --------------------------------------------------------------------------- 128 | 129 | 130 | -------------------------------------------------------------------------------- /ORB_SLAM_txt/Thirdparty/DBoW2/DUtils/Random.h: -------------------------------------------------------------------------------- 1 | /* 2 | * File: Random.h 3 | * Project: DUtils library 4 | * Author: Dorian Galvez-Lopez 5 | * Date: April 2010, November 2011 6 | * Description: manages pseudo-random numbers 7 | * License: see the LICENSE.txt file 8 | * 9 | */ 10 | 11 | #pragma once 12 | #ifndef __D_RANDOM__ 13 | #define __D_RANDOM__ 14 | 15 | #include 16 | #include 17 | 18 | namespace DUtils { 19 | 20 | /// Functions to generate pseudo-random numbers 21 | class Random 22 | { 23 | public: 24 | class UnrepeatedRandomizer; 25 | 26 | public: 27 | /** 28 | * Sets the random number seed to the current time 29 | */ 30 | static void SeedRand(); 31 | 32 | /** 33 | * Sets the random number seed to the current time only the first 34 | * time this function is called 35 | */ 36 | static void SeedRandOnce(); 37 | 38 | /** 39 | * Sets the given random number seed 40 | * @param seed 41 | */ 42 | static void SeedRand(int seed); 43 | 44 | /** 45 | * Sets the given random number seed only the first time this function 46 | * is called 47 | * @param seed 48 | */ 49 | static void SeedRandOnce(int seed); 50 | 51 | /** 52 | * Returns a random number in the range [0..1] 53 | * @return random T number in [0..1] 54 | */ 55 | template 56 | static T RandomValue(){ 57 | return (T)rand()/(T)RAND_MAX; 58 | } 59 | 60 | /** 61 | * Returns a random number in the range [min..max] 62 | * @param min 63 | * @param max 64 | * @return random T number in [min..max] 65 | */ 66 | template 67 | static T RandomValue(T min, T max){ 68 | return Random::RandomValue() * (max - min) + min; 69 | } 70 | 71 | /** 72 | * Returns a random int in the range [min..max] 73 | * @param min 74 | * @param max 75 | * @return random int in [min..max] 76 | */ 77 | static int RandomInt(int min, int max); 78 | 79 | /** 80 | * Returns a random number from a gaussian distribution 81 | * @param mean 82 | * @param sigma standard deviation 83 | */ 84 | template 85 | static T RandomGaussianValue(T mean, T sigma) 86 | { 87 | // Box-Muller transformation 88 | T x1, x2, w, y1; 89 | 90 | do { 91 | x1 = (T)2. * RandomValue() - (T)1.; 92 | x2 = (T)2. * RandomValue() - (T)1.; 93 | w = x1 * x1 + x2 * x2; 94 | } while ( w >= (T)1. || w == (T)0. ); 95 | 96 | w = sqrt( ((T)-2.0 * log( w ) ) / w ); 97 | y1 = x1 * w; 98 | 99 | return( mean + y1 * sigma ); 100 | } 101 | 102 | private: 103 | 104 | /// If SeedRandOnce() or SeedRandOnce(int) have already been called 105 | static bool m_already_seeded; 106 | 107 | }; 108 | 109 | // --------------------------------------------------------------------------- 110 | 111 | /// Provides pseudo-random numbers with no repetitions 112 | class Random::UnrepeatedRandomizer 113 | { 114 | public: 115 | 116 | /** 117 | * Creates a randomizer that returns numbers in the range [min, max] 118 | * @param min 119 | * @param max 120 | */ 121 | UnrepeatedRandomizer(int min, int max); 122 | ~UnrepeatedRandomizer(){} 123 | 124 | /** 125 | * Copies a randomizer 126 | * @param rnd 127 | */ 128 | UnrepeatedRandomizer(const UnrepeatedRandomizer& rnd); 129 | 130 | /** 131 | * Copies a randomizer 132 | * @param rnd 133 | */ 134 | UnrepeatedRandomizer& operator=(const UnrepeatedRandomizer& rnd); 135 | 136 | /** 137 | * Returns a random number not given before. If all the possible values 138 | * were already given, the process starts again 139 | * @return unrepeated random number 140 | */ 141 | int get(); 142 | 143 | /** 144 | * Returns whether all the possible values between min and max were 145 | * already given. If get() is called when empty() is true, the behaviour 146 | * is the same than after creating the randomizer 147 | * @return true iff all the values were returned 148 | */ 149 | inline bool empty() const { return m_values.empty(); } 150 | 151 | /** 152 | * Returns the number of values still to be returned 153 | * @return amount of values to return 154 | */ 155 | inline unsigned int left() const { return m_values.size(); } 156 | 157 | /** 158 | * Resets the randomizer as it were just created 159 | */ 160 | void reset(); 161 | 162 | protected: 163 | 164 | /** 165 | * Creates the vector with available values 166 | */ 167 | void createValues(); 168 | 169 | protected: 170 | 171 | /// Min of range of values 172 | int m_min; 173 | /// Max of range of values 174 | int m_max; 175 | 176 | /// Available values 177 | std::vector m_values; 178 | 179 | }; 180 | 181 | } 182 | 183 | #endif 184 | 185 | -------------------------------------------------------------------------------- /ORB_SLAM_txt/Thirdparty/DBoW2/DUtils/Timestamp.cpp: -------------------------------------------------------------------------------- 1 | /* 2 | * File: Timestamp.cpp 3 | * Author: Dorian Galvez-Lopez 4 | * Date: March 2009 5 | * Description: timestamping functions 6 | * 7 | * Note: in windows, this class has a 1ms resolution 8 | * 9 | * License: see the LICENSE.txt file 10 | * 11 | */ 12 | 13 | #include 14 | #include 15 | #include 16 | #include 17 | #include 18 | #include 19 | 20 | #ifdef _WIN32 21 | #ifndef WIN32 22 | #define WIN32 23 | #endif 24 | #endif 25 | 26 | #ifdef WIN32 27 | #include 28 | #define sprintf sprintf_s 29 | #else 30 | #include 31 | #endif 32 | 33 | #include "Timestamp.h" 34 | 35 | using namespace std; 36 | 37 | using namespace DUtils; 38 | 39 | Timestamp::Timestamp(Timestamp::tOptions option) 40 | { 41 | if(option & CURRENT_TIME) 42 | setToCurrentTime(); 43 | else if(option & ZERO) 44 | setTime(0.); 45 | } 46 | 47 | Timestamp::~Timestamp(void) 48 | { 49 | } 50 | 51 | bool Timestamp::empty() const 52 | { 53 | return m_secs == 0 && m_usecs == 0; 54 | } 55 | 56 | void Timestamp::setToCurrentTime(){ 57 | 58 | #ifdef WIN32 59 | struct __timeb32 timebuffer; 60 | _ftime32_s( &timebuffer ); // C4996 61 | // Note: _ftime is deprecated; consider using _ftime_s instead 62 | m_secs = timebuffer.time; 63 | m_usecs = timebuffer.millitm * 1000; 64 | #else 65 | struct timeval now; 66 | gettimeofday(&now, NULL); 67 | m_secs = now.tv_sec; 68 | m_usecs = now.tv_usec; 69 | #endif 70 | 71 | } 72 | 73 | void Timestamp::setTime(const string &stime){ 74 | string::size_type p = stime.find('.'); 75 | if(p == string::npos){ 76 | m_secs = atol(stime.c_str()); 77 | m_usecs = 0; 78 | }else{ 79 | m_secs = atol(stime.substr(0, p).c_str()); 80 | 81 | string s_usecs = stime.substr(p+1, 6); 82 | m_usecs = atol(stime.substr(p+1).c_str()); 83 | m_usecs *= (unsigned long)pow(10.0, double(6 - s_usecs.length())); 84 | } 85 | } 86 | 87 | void Timestamp::setTime(double s) 88 | { 89 | m_secs = (unsigned long)s; 90 | m_usecs = (s - (double)m_secs) * 1e6; 91 | } 92 | 93 | double Timestamp::getFloatTime() const { 94 | return double(m_secs) + double(m_usecs)/1000000.0; 95 | } 96 | 97 | string Timestamp::getStringTime() const { 98 | char buf[32]; 99 | sprintf(buf, "%.6lf", this->getFloatTime()); 100 | return string(buf); 101 | } 102 | 103 | double Timestamp::operator- (const Timestamp &t) const { 104 | return this->getFloatTime() - t.getFloatTime(); 105 | } 106 | 107 | Timestamp& Timestamp::operator+= (double s) 108 | { 109 | *this = *this + s; 110 | return *this; 111 | } 112 | 113 | Timestamp& Timestamp::operator-= (double s) 114 | { 115 | *this = *this - s; 116 | return *this; 117 | } 118 | 119 | Timestamp Timestamp::operator+ (double s) const 120 | { 121 | unsigned long secs = (long)floor(s); 122 | unsigned long usecs = (long)((s - (double)secs) * 1e6); 123 | 124 | return this->plus(secs, usecs); 125 | } 126 | 127 | Timestamp Timestamp::plus(unsigned long secs, unsigned long usecs) const 128 | { 129 | Timestamp t; 130 | 131 | const unsigned long max = 1000000ul; 132 | 133 | if(m_usecs + usecs >= max) 134 | t.setTime(m_secs + secs + 1, m_usecs + usecs - max); 135 | else 136 | t.setTime(m_secs + secs, m_usecs + usecs); 137 | 138 | return t; 139 | } 140 | 141 | Timestamp Timestamp::operator- (double s) const 142 | { 143 | unsigned long secs = (long)floor(s); 144 | unsigned long usecs = (long)((s - (double)secs) * 1e6); 145 | 146 | return this->minus(secs, usecs); 147 | } 148 | 149 | Timestamp Timestamp::minus(unsigned long secs, unsigned long usecs) const 150 | { 151 | Timestamp t; 152 | 153 | const unsigned long max = 1000000ul; 154 | 155 | if(m_usecs < usecs) 156 | t.setTime(m_secs - secs - 1, max - (usecs - m_usecs)); 157 | else 158 | t.setTime(m_secs - secs, m_usecs - usecs); 159 | 160 | return t; 161 | } 162 | 163 | bool Timestamp::operator> (const Timestamp &t) const 164 | { 165 | if(m_secs > t.m_secs) return true; 166 | else if(m_secs == t.m_secs) return m_usecs > t.m_usecs; 167 | else return false; 168 | } 169 | 170 | bool Timestamp::operator>= (const Timestamp &t) const 171 | { 172 | if(m_secs > t.m_secs) return true; 173 | else if(m_secs == t.m_secs) return m_usecs >= t.m_usecs; 174 | else return false; 175 | } 176 | 177 | bool Timestamp::operator< (const Timestamp &t) const 178 | { 179 | if(m_secs < t.m_secs) return true; 180 | else if(m_secs == t.m_secs) return m_usecs < t.m_usecs; 181 | else return false; 182 | } 183 | 184 | bool Timestamp::operator<= (const Timestamp &t) const 185 | { 186 | if(m_secs < t.m_secs) return true; 187 | else if(m_secs == t.m_secs) return m_usecs <= t.m_usecs; 188 | else return false; 189 | } 190 | 191 | bool Timestamp::operator== (const Timestamp &t) const 192 | { 193 | return(m_secs == t.m_secs && m_usecs == t.m_usecs); 194 | } 195 | 196 | 197 | string Timestamp::Format(bool machine_friendly) const 198 | { 199 | struct tm tm_time; 200 | 201 | time_t t = (time_t)getFloatTime(); 202 | 203 | #ifdef WIN32 204 | localtime_s(&tm_time, &t); 205 | #else 206 | localtime_r(&t, &tm_time); 207 | #endif 208 | 209 | char buffer[128]; 210 | 211 | if(machine_friendly) 212 | { 213 | strftime(buffer, 128, "%Y%m%d_%H%M%S", &tm_time); 214 | } 215 | else 216 | { 217 | strftime(buffer, 128, "%c", &tm_time); // Thu Aug 23 14:55:02 2001 218 | } 219 | 220 | return string(buffer); 221 | } 222 | 223 | string Timestamp::Format(double s) { 224 | int days = int(s / (24. * 3600.0)); 225 | s -= days * (24. * 3600.0); 226 | int hours = int(s / 3600.0); 227 | s -= hours * 3600; 228 | int minutes = int(s / 60.0); 229 | s -= minutes * 60; 230 | int seconds = int(s); 231 | int ms = int((s - seconds)*1e6); 232 | 233 | stringstream ss; 234 | ss.fill('0'); 235 | bool b; 236 | if((b = (days > 0))) ss << days << "d "; 237 | if((b = (b || hours > 0))) ss << setw(2) << hours << ":"; 238 | if((b = (b || minutes > 0))) ss << setw(2) << minutes << ":"; 239 | if(b) ss << setw(2); 240 | ss << seconds; 241 | if(!b) ss << "." << setw(6) << ms; 242 | 243 | return ss.str(); 244 | } 245 | 246 | 247 | -------------------------------------------------------------------------------- /ORB_SLAM_txt/Thirdparty/DBoW2/DUtils/Timestamp.h: -------------------------------------------------------------------------------- 1 | /* 2 | * File: Timestamp.h 3 | * Author: Dorian Galvez-Lopez 4 | * Date: March 2009 5 | * Description: timestamping functions 6 | * License: see the LICENSE.txt file 7 | * 8 | */ 9 | 10 | #ifndef __D_TIMESTAMP__ 11 | #define __D_TIMESTAMP__ 12 | 13 | #include 14 | using namespace std; 15 | 16 | namespace DUtils { 17 | 18 | /// Timestamp 19 | class Timestamp 20 | { 21 | public: 22 | 23 | /// Options to initiate a timestamp 24 | enum tOptions 25 | { 26 | NONE = 0, 27 | CURRENT_TIME = 0x1, 28 | ZERO = 0x2 29 | }; 30 | 31 | public: 32 | 33 | /** 34 | * Creates a timestamp 35 | * @param option option to set the initial time stamp 36 | */ 37 | Timestamp(Timestamp::tOptions option = NONE); 38 | 39 | /** 40 | * Destructor 41 | */ 42 | virtual ~Timestamp(void); 43 | 44 | /** 45 | * Says if the timestamp is "empty": seconds and usecs are both 0, as 46 | * when initiated with the ZERO flag 47 | * @return true iif secs == usecs == 0 48 | */ 49 | bool empty() const; 50 | 51 | /** 52 | * Sets this instance to the current time 53 | */ 54 | void setToCurrentTime(); 55 | 56 | /** 57 | * Sets the timestamp from seconds and microseconds 58 | * @param secs: seconds 59 | * @param usecs: microseconds 60 | */ 61 | inline void setTime(unsigned long secs, unsigned long usecs){ 62 | m_secs = secs; 63 | m_usecs = usecs; 64 | } 65 | 66 | /** 67 | * Returns the timestamp in seconds and microseconds 68 | * @param secs seconds 69 | * @param usecs microseconds 70 | */ 71 | inline void getTime(unsigned long &secs, unsigned long &usecs) const 72 | { 73 | secs = m_secs; 74 | usecs = m_usecs; 75 | } 76 | 77 | /** 78 | * Sets the timestamp from a string with the time in seconds 79 | * @param stime: string such as "1235603336.036609" 80 | */ 81 | void setTime(const string &stime); 82 | 83 | /** 84 | * Sets the timestamp from a number of seconds from the epoch 85 | * @param s seconds from the epoch 86 | */ 87 | void setTime(double s); 88 | 89 | /** 90 | * Returns this timestamp as the number of seconds in (long) float format 91 | */ 92 | double getFloatTime() const; 93 | 94 | /** 95 | * Returns this timestamp as the number of seconds in fixed length string format 96 | */ 97 | string getStringTime() const; 98 | 99 | /** 100 | * Returns the difference in seconds between this timestamp (greater) and t (smaller) 101 | * If the order is swapped, a negative number is returned 102 | * @param t: timestamp to subtract from this timestamp 103 | * @return difference in seconds 104 | */ 105 | double operator- (const Timestamp &t) const; 106 | 107 | /** 108 | * Returns a copy of this timestamp + s seconds + us microseconds 109 | * @param s seconds 110 | * @param us microseconds 111 | */ 112 | Timestamp plus(unsigned long s, unsigned long us) const; 113 | 114 | /** 115 | * Returns a copy of this timestamp - s seconds - us microseconds 116 | * @param s seconds 117 | * @param us microseconds 118 | */ 119 | Timestamp minus(unsigned long s, unsigned long us) const; 120 | 121 | /** 122 | * Adds s seconds to this timestamp and returns a reference to itself 123 | * @param s seconds 124 | * @return reference to this timestamp 125 | */ 126 | Timestamp& operator+= (double s); 127 | 128 | /** 129 | * Substracts s seconds to this timestamp and returns a reference to itself 130 | * @param s seconds 131 | * @return reference to this timestamp 132 | */ 133 | Timestamp& operator-= (double s); 134 | 135 | /** 136 | * Returns a copy of this timestamp + s seconds 137 | * @param s: seconds 138 | */ 139 | Timestamp operator+ (double s) const; 140 | 141 | /** 142 | * Returns a copy of this timestamp - s seconds 143 | * @param s: seconds 144 | */ 145 | Timestamp operator- (double s) const; 146 | 147 | /** 148 | * Returns whether this timestamp is at the future of t 149 | * @param t 150 | */ 151 | bool operator> (const Timestamp &t) const; 152 | 153 | /** 154 | * Returns whether this timestamp is at the future of (or is the same as) t 155 | * @param t 156 | */ 157 | bool operator>= (const Timestamp &t) const; 158 | 159 | /** 160 | * Returns whether this timestamp and t represent the same instant 161 | * @param t 162 | */ 163 | bool operator== (const Timestamp &t) const; 164 | 165 | /** 166 | * Returns whether this timestamp is at the past of t 167 | * @param t 168 | */ 169 | bool operator< (const Timestamp &t) const; 170 | 171 | /** 172 | * Returns whether this timestamp is at the past of (or is the same as) t 173 | * @param t 174 | */ 175 | bool operator<= (const Timestamp &t) const; 176 | 177 | /** 178 | * Returns the timestamp in a human-readable string 179 | * @param machine_friendly if true, the returned string is formatted 180 | * to yyyymmdd_hhmmss, without weekday or spaces 181 | * @note This has not been tested under Windows 182 | * @note The timestamp is truncated to seconds 183 | */ 184 | string Format(bool machine_friendly = false) const; 185 | 186 | /** 187 | * Returns a string version of the elapsed time in seconds, with the format 188 | * xd hh:mm:ss, hh:mm:ss, mm:ss or s.us 189 | * @param s: elapsed seconds (given by getFloatTime) to format 190 | */ 191 | static string Format(double s); 192 | 193 | 194 | protected: 195 | /// Seconds 196 | unsigned long m_secs; // seconds 197 | /// Microseconds 198 | unsigned long m_usecs; // microseconds 199 | }; 200 | 201 | } 202 | 203 | #endif 204 | 205 | -------------------------------------------------------------------------------- /ORB_SLAM_txt/Thirdparty/DBoW2/LICENSE.txt: -------------------------------------------------------------------------------- 1 | DBoW2: bag-of-words library for C++ with generic descriptors 2 | 3 | Copyright (c) 2015 Dorian Galvez-Lopez (Universidad de Zaragoza) 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. Neither the name of copyright holders nor the names of its 15 | contributors may be used to endorse or promote products derived 16 | from this software without specific prior written permission. 17 | 18 | THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 19 | ''AS IS'' AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED 20 | TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR 21 | PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL COPYRIGHT HOLDERS OR CONTRIBUTORS 22 | BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR 23 | CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 24 | SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 25 | INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 26 | CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 27 | ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 28 | POSSIBILITY OF SUCH DAMAGE. 29 | 30 | If you use it in an academic work, please cite: 31 | 32 | @ARTICLE{GalvezTRO12, 33 | author={G\'alvez-L\'opez, Dorian and Tard\'os, J. D.}, 34 | journal={IEEE Transactions on Robotics}, 35 | title={Bags of Binary Words for Fast Place Recognition in Image Sequences}, 36 | year={2012}, 37 | month={October}, 38 | volume={28}, 39 | number={5}, 40 | pages={1188--1197}, 41 | doi={10.1109/TRO.2012.2197158}, 42 | ISSN={1552-3098} 43 | } 44 | 45 | -------------------------------------------------------------------------------- /ORB_SLAM_txt/Thirdparty/DBoW2/README.txt: -------------------------------------------------------------------------------- 1 | You should have received this DBoW2 version along with ORB-SLAM2 (https://github.com/raulmur/ORB_SLAM2). 2 | See the original DBoW2 library at: https://github.com/dorian3d/DBoW2 3 | All files included in this version are BSD, see LICENSE.txt 4 | 5 | We also use Random.h, Random.cpp, Timestamp.pp and Timestamp.h from DLib/DUtils. 6 | See the original DLib library at: https://github.com/dorian3d/DLib 7 | All files included in this version are BSD, see LICENSE.txt 8 | -------------------------------------------------------------------------------- /ORB_SLAM_txt/Vocab/convert_to_txt.cpp: -------------------------------------------------------------------------------- 1 | /** 2 | * File: Demo.cpp 3 | * Date: November 2011 4 | * Author: Dorian Galvez-Lopez 5 | * Description: demo application of DBoW2 6 | * License: see the LICENSE.txt file 7 | */ 8 | 9 | #include 10 | #include 11 | 12 | #include "ORBVocabulary.h" 13 | 14 | using namespace ORB_SLAM2; 15 | using namespace std; 16 | 17 | 18 | int main() 19 | { 20 | ORBVocabulary voc("castle_ruins.yml.gz"); 21 | voc.saveToTextFile("castle_ruins.txt"); 22 | return 0; 23 | } 24 | 25 | 26 | 27 | -------------------------------------------------------------------------------- /ORB_SLAM_txt/cmake_modules/FindEigen3.cmake: -------------------------------------------------------------------------------- 1 | # - Try to find Eigen3 lib 2 | # 3 | # This module supports requiring a minimum version, e.g. you can do 4 | # find_package(Eigen3 3.1.2) 5 | # to require version 3.1.2 or newer of Eigen3. 6 | # 7 | # Once done this will define 8 | # 9 | # EIGEN3_FOUND - system has eigen lib with correct version 10 | # EIGEN3_INCLUDE_DIR - the eigen include directory 11 | # EIGEN3_VERSION - eigen version 12 | 13 | # Copyright (c) 2006, 2007 Montel Laurent, 14 | # Copyright (c) 2008, 2009 Gael Guennebaud, 15 | # Copyright (c) 2009 Benoit Jacob 16 | # Redistribution and use is allowed according to the terms of the 2-clause BSD license. 17 | 18 | if(NOT Eigen3_FIND_VERSION) 19 | if(NOT Eigen3_FIND_VERSION_MAJOR) 20 | set(Eigen3_FIND_VERSION_MAJOR 2) 21 | endif(NOT Eigen3_FIND_VERSION_MAJOR) 22 | if(NOT Eigen3_FIND_VERSION_MINOR) 23 | set(Eigen3_FIND_VERSION_MINOR 91) 24 | endif(NOT Eigen3_FIND_VERSION_MINOR) 25 | if(NOT Eigen3_FIND_VERSION_PATCH) 26 | set(Eigen3_FIND_VERSION_PATCH 0) 27 | endif(NOT Eigen3_FIND_VERSION_PATCH) 28 | 29 | set(Eigen3_FIND_VERSION "${Eigen3_FIND_VERSION_MAJOR}.${Eigen3_FIND_VERSION_MINOR}.${Eigen3_FIND_VERSION_PATCH}") 30 | endif(NOT Eigen3_FIND_VERSION) 31 | 32 | macro(_eigen3_check_version) 33 | file(READ "${EIGEN3_INCLUDE_DIR}/Eigen/src/Core/util/Macros.h" _eigen3_version_header) 34 | 35 | string(REGEX MATCH "define[ \t]+EIGEN_WORLD_VERSION[ \t]+([0-9]+)" _eigen3_world_version_match "${_eigen3_version_header}") 36 | set(EIGEN3_WORLD_VERSION "${CMAKE_MATCH_1}") 37 | string(REGEX MATCH "define[ \t]+EIGEN_MAJOR_VERSION[ \t]+([0-9]+)" _eigen3_major_version_match "${_eigen3_version_header}") 38 | set(EIGEN3_MAJOR_VERSION "${CMAKE_MATCH_1}") 39 | string(REGEX MATCH "define[ \t]+EIGEN_MINOR_VERSION[ \t]+([0-9]+)" _eigen3_minor_version_match "${_eigen3_version_header}") 40 | set(EIGEN3_MINOR_VERSION "${CMAKE_MATCH_1}") 41 | 42 | set(EIGEN3_VERSION ${EIGEN3_WORLD_VERSION}.${EIGEN3_MAJOR_VERSION}.${EIGEN3_MINOR_VERSION}) 43 | if(${EIGEN3_VERSION} VERSION_LESS ${Eigen3_FIND_VERSION}) 44 | set(EIGEN3_VERSION_OK FALSE) 45 | else(${EIGEN3_VERSION} VERSION_LESS ${Eigen3_FIND_VERSION}) 46 | set(EIGEN3_VERSION_OK TRUE) 47 | endif(${EIGEN3_VERSION} VERSION_LESS ${Eigen3_FIND_VERSION}) 48 | 49 | if(NOT EIGEN3_VERSION_OK) 50 | 51 | message(STATUS "Eigen3 version ${EIGEN3_VERSION} found in ${EIGEN3_INCLUDE_DIR}, " 52 | "but at least version ${Eigen3_FIND_VERSION} is required") 53 | endif(NOT EIGEN3_VERSION_OK) 54 | endmacro(_eigen3_check_version) 55 | 56 | if (EIGEN3_INCLUDE_DIR) 57 | 58 | # in cache already 59 | _eigen3_check_version() 60 | set(EIGEN3_FOUND ${EIGEN3_VERSION_OK}) 61 | 62 | else (EIGEN3_INCLUDE_DIR) 63 | 64 | # specific additional paths for some OS 65 | if (WIN32) 66 | set(EIGEN_ADDITIONAL_SEARCH_PATHS ${EIGEN_ADDITIONAL_SEARCH_PATHS} "C:/Program Files/Eigen/include" "C:/Program Files (x86)/Eigen/include") 67 | endif(WIN32) 68 | 69 | find_path(EIGEN3_INCLUDE_DIR NAMES signature_of_eigen3_matrix_library 70 | PATHS 71 | ${CMAKE_INSTALL_PREFIX}/include 72 | ${EIGEN_ADDITIONAL_SEARCH_PATHS} 73 | ${KDE4_INCLUDE_DIR} 74 | PATH_SUFFIXES eigen3 eigen 75 | ) 76 | 77 | if(EIGEN3_INCLUDE_DIR) 78 | _eigen3_check_version() 79 | endif(EIGEN3_INCLUDE_DIR) 80 | 81 | include(FindPackageHandleStandardArgs) 82 | find_package_handle_standard_args(Eigen3 DEFAULT_MSG EIGEN3_INCLUDE_DIR EIGEN3_VERSION_OK) 83 | 84 | mark_as_advanced(EIGEN3_INCLUDE_DIR) 85 | 86 | endif(EIGEN3_INCLUDE_DIR) 87 | 88 | -------------------------------------------------------------------------------- /ORB_SLAM_txt/include/ORBVocabulary.h: -------------------------------------------------------------------------------- 1 | /** 2 | * This file is part of ORB-SLAM2. 3 | * 4 | * Copyright (C) 2014-2016 Raúl Mur-Artal (University of Zaragoza) 5 | * For more information see 6 | * 7 | * ORB-SLAM2 is free software: you can redistribute it and/or modify 8 | * it under the terms of the GNU General Public License as published by 9 | * the Free Software Foundation, either version 3 of the License, or 10 | * (at your option) any later version. 11 | * 12 | * ORB-SLAM2 is distributed in the hope that it will be useful, 13 | * but WITHOUT ANY WARRANTY; without even the implied warranty of 14 | * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the 15 | * GNU General Public License for more details. 16 | * 17 | * You should have received a copy of the GNU General Public License 18 | * along with ORB-SLAM2. If not, see . 19 | */ 20 | 21 | 22 | #ifndef ORBVOCABULARY_H 23 | #define ORBVOCABULARY_H 24 | 25 | #include"Thirdparty/DBoW2/DBoW2/FORB.h" 26 | #include"Thirdparty/DBoW2/DBoW2/TemplatedVocabulary.h" 27 | 28 | namespace ORB_SLAM2 29 | { 30 | 31 | typedef DBoW2::TemplatedVocabulary 32 | ORBVocabulary; 33 | 34 | } //namespace ORB_SLAM 35 | 36 | #endif // ORBVOCABULARY_H 37 | -------------------------------------------------------------------------------- /ORB_SLAM_txt/src/Orb_vocab.cc: -------------------------------------------------------------------------------- 1 | 2 | #include "ORBVocabulary.h" -------------------------------------------------------------------------------- /README.md: -------------------------------------------------------------------------------- 1 | # ORB_SLAM_vocab-build 2 | 3 | The state of the art SLAM algorithms like ORB SLAM use a bag-of-words approach to create a vocabulary of words which can be used for the purpose of place recognition and detection of loop closures. The default dictionary ```ORBvoc.txt``` is sufficient in most of the cases of indoor and outdoor environments, though it is observed that the performance drops in a highly specialised environment like underwater or non common environments. No proper instructions have been provided which can be used to create your own custom vocabulary. Thus this repository contains step by step procedure to create your own vocabulary using custom dataset which can be directly used for ORB SLAM. 4 | 5 | This repository can be used to create custom bag of words vocabulary which can be directly used for ORB SLAM/ORB SLAM2. 6 | It consists of 2 major sub-folders: 7 | 8 | 1.DBoW2 (Forked from [dorian3d/DBoW2](https://github.com/dorian3d/DBoW2)) 9 | 2.ORB_SLAM_txt (modified and used from [ORB_SLAM2](https://github.com/raulmur/ORB_SLAM2)) 10 | 11 | Here is the step by step procedure to build your own bag of words vocabulary and save it as .txt file format (which is required for ORB_SLAM): 12 | 13 | ## 1. Prerequisites 14 | We have tested the library in **Ubuntu 12.04**, **14.04**, **16.04** & **18.04**, but it should be easy to compile in other platforms. 15 | ### 1.1 C++11 or C++0x Compiler 16 | We use the new thread and chrono functionalities of C++11. 17 | ### 1.2 OpenCV 18 | We use [OpenCV](http://opencv.org) to manipulate images and features. Dowload and install instructions can be found at: http://opencv.org. **Required at leat 2.4.3. Tested with OpenCV 2.4.11 and OpenCV 3.2**. 19 | 20 | 21 | ## 2. Installation 22 | 23 | ### 2.1. Clone the repository 24 | ``` 25 | cd ~/ 26 | git clone https://github.com/manthan99/ORB_SLAM_vocab-build.git 27 | ``` 28 | 29 | ### 2.2. Compile *DBoW2* 30 | ``` 31 | cd ~/ORB_SLAM_vocab-build/DBoW2/ 32 | mkdir build 33 | cd build 34 | cmake .. 35 | make -j 36 | ``` 37 | ### 2.3. Compile *ORB_SLAM_txt* 38 | 39 | 2.3.1 Compile thirdparty DBoW2 40 | ``` 41 | cd ~/ORB_SLAM_vocab-build/ORB_SLAM_txt/Thirdparty/DBoW2/ 42 | mkdir build 43 | cd build 44 | cmake .. 45 | make -j 46 | ``` 47 | 48 | 2.3.2 Compile Vocab 49 | ``` 50 | cd ~/ORB_SLAM_vocab-build/ORB_SLAM_txt/ 51 | mkdir build 52 | cd build 53 | cmake .. 54 | make -j 55 | ``` 56 | 57 | 58 | ## 3. Creating a vocabulary as yml 59 | 60 | * We will use demo.cpp (```~/ORB_SLAM_vocab-build/DBoW2/demo/demo.cpp```) to first create a vocabulary and save it as a yml file. 61 | * Please go through the publication given here [dorian3d/DBoW2](https://github.com/dorian3d/DBoW2) to understand about the branching factor(K) and levels(L). 62 | * The ORB SLAM uses a vocabulary having branching factor as 10 and depth levels as 6, thus creating a dictionary of 10^6 (1 Million) words. 63 | * You will require a dataset of images for creating the vocabulary. The images **n** must be named as *image0.png, image1.png ... image**n**.png*. Copy the dataset to the following folder: ```~/ORB_SLAM_vocab-build/DBoW2/demo/images/``` 64 | * Alternatively, if you are using ROS and have a bag file which you intend to use for training, you may use the *bag_to_img* launch file to create a dataset of images from the bag file. In the launch file, do the following changes 65 | 1. Replace ```~/castle_ruins_vocab.bag``` with the location of your bag file. 66 | 2. Replace ```/airsim_node/drone_1/front_center/Scene``` with the image topic 67 | 3. You may set the output location in the param ```filename_format```. Default is ```~/ORB_SLAM_vocab-build/DBoW2/demo/images/image%i.png```, which will directly export the images to the required images folder. 68 | 4. You may set the param ```"_sec_per_frame"``` to your required frequency. Setting it to **0.1** will extract the images at 10 Hz. 69 | * Open the ```demo.cpp``` to edit the values of **K** & **L** in line no. *105*. 70 | * Change the value of *NIMAGES* in line *35* to the no. of images in the training dataset. 71 | * You may change the output name of the vocabulary file from line no. *136* and *147*. Default is ```"castle_ruins.yml.gz"```. 72 | * Now we need to create the executable for demo.cpp 73 | ``` 74 | cd ~/ORB_SLAM_vocab-build/DBoW2/build 75 | cmake .. 76 | make -j 77 | ``` 78 | * Execute *demo*. This will create a vocabulary and save it as a yml file. It may take upto a few hours if you have images in the order of *10^3*. 79 | ``` 80 | ./demo 81 | ``` 82 | 83 | ## 4. Converting yml vocabulary to txt 84 | 85 | * This is a necessary step in order to use the vocabulary for ORB_SLAM. ORB_SLAM does not support yml file format. 86 | * Copy the created yml file (default - ```castle_ruins.yml.gz```) to the following folder - ```~/ORB_SLAM_vocab-build_copy/ORB_SLAM_txt/Vocab``` 87 | * Edit the input and output file in line no. *20* and *21* of ```covert_to_txt.cpp```(```~/ORB_SLAM_vocab-build/ORB_SLAM_txt/Vocab/convert_to_txt.cpp```) 88 | * Create a executable and run- 89 | ``` 90 | cd ~/ORB_SLAM_vocab-build/ORB_SLAM_txt/build/ 91 | make -j 92 | cd ~/ORB_SLAM_vocab-build/ORB_SLAM_txt/Vocab 93 | ./convert_to_txt 94 | ``` 95 | * This will create the required vocabulary in txt file format. It will just take a few seconds. 96 | 97 | ## 5. Examples 98 | 99 | * A couple of vocabulary files have been provided in the Example_Vocab folder(```~/ORB_SLAM_vocab-build/ORB_SLAM_txt/Example_Vocab```). 100 | 1. ORBvoc.txt.tar.gz (The default vocabulary for ORB SLAM) 101 | 2. Castle_Ruins_voc.zip (Vocabulary for the Castle Ruins Airsim Environment)([Link](http://patelmanthan.in/castle-ruins-airsim/)) 102 | 103 | -------------------------------------------------------------------------------- /bag_to_img.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | --------------------------------------------------------------------------------