FlannIndex.h
Go to the documentation of this file.
00001 /*
00002 Copyright (c) 2010-2016, Mathieu Labbe - IntRoLab - Universite de Sherbrooke
00003 All rights reserved.
00004 
00005 Redistribution and use in source and binary forms, with or without
00006 modification, are permitted provided that the following conditions are met:
00007     * Redistributions of source code must retain the above copyright
00008       notice, this list of conditions and the following disclaimer.
00009     * Redistributions in binary form must reproduce the above copyright
00010       notice, this list of conditions and the following disclaimer in the
00011       documentation and/or other materials provided with the distribution.
00012     * Neither the name of the Universite de Sherbrooke nor the
00013       names of its contributors may be used to endorse or promote products
00014       derived from this software without specific prior written permission.
00015 
00016 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
00017 ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
00018 WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
00019 DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY
00020 DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
00021 (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00022 LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
00023 ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
00024 (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
00025 SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
00026 */
00027 
00028 #ifndef CORELIB_SRC_FLANNINDEX_H_
00029 #define CORELIB_SRC_FLANNINDEX_H_
00030 
00031 #include "rtabmap/core/RtabmapExp.h" // DLL export/import defines
00032 #include <list>
00033 #include <opencv2/opencv.hpp>
00034 
00035 namespace rtabmap {
00036 
00037 class RTABMAP_EXP FlannIndex
00038 {
00039 public:
00040         FlannIndex();
00041         virtual ~FlannIndex();
00042 
00043         void release();
00044         unsigned int indexedFeatures() const;
00045 
00046         // return KB
00047         unsigned int memoryUsed() const;
00048 
00049         // Note that useDistanceL1 doesn't have any effect if LSH is used
00050         void buildLinearIndex(
00051                         const cv::Mat & features,
00052                         bool useDistanceL1 = false,
00053                         float rebalancingFactor = 2.0f);
00054         void buildKDTreeIndex(
00055                         const cv::Mat & features,
00056                         int trees = 4,
00057                         bool useDistanceL1 = false,
00058                         float rebalancingFactor = 2.0f);
00059         void buildKDTreeSingleIndex(
00060                         const cv::Mat & features,
00061                         int leafMaxSize = 10,
00062                         bool reorder = true,
00063                         bool useDistanceL1 = false,
00064                         float rebalancingFactor = 2.0f);
00065         void buildLSHIndex(
00066                         const cv::Mat & features,
00067                         unsigned int table_number = 12,
00068                         unsigned int key_size = 20,
00069                         unsigned int multi_probe_level = 2,
00070                         float rebalancingFactor = 2.0f);
00071 
00072         bool isBuilt();
00073 
00074         int featuresType() const {return featuresType_;}
00075         int featuresDim() const {return featuresDim_;}
00076 
00077         unsigned int addPoints(const cv::Mat & features);
00078 
00079         void removePoint(unsigned int index);
00080 
00081         // return squared distances (indices should be casted in size_t)
00082         void knnSearch(
00083                         const cv::Mat & query,
00084                         cv::Mat & indices,
00085                         cv::Mat & dists,
00086                 int knn,
00087                         int checks = 32,
00088                         float eps = 0.0,
00089                         bool sorted = true) const;
00090 
00091         // return squared distances
00092         void radiusSearch(
00093                         const cv::Mat & query,
00094                         std::vector<std::vector<size_t> > & indices,
00095                         std::vector<std::vector<float> > & dists,
00096                         float radius,
00097                         int maxNeighbors = 0,
00098                         int checks = 32,
00099                         float eps = 0.0,
00100                         bool sorted = true) const;
00101 
00102 private:
00103         void * index_;
00104         unsigned int nextIndex_;
00105         int featuresType_;
00106         int featuresDim_;
00107         bool isLSH_;
00108         bool useDistanceL1_; // true=EUCLEDIAN_L2 false=MANHATTAN_L1
00109         float rebalancingFactor_;
00110 
00111         // keep feature in memory until the tree is rebuilt
00112         // (in case the word is deleted when removed from the VWDictionary)
00113         std::map<int, cv::Mat> addedDescriptors_;
00114         std::list<int> removedIndexes_;
00115 };
00116 
00117 } /* namespace rtabmap */
00118 
00119 #endif /* CORELIB_SRC_FLANNINDEX_H_ */


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