flann.hpp
Go to the documentation of this file.
00001 /***********************************************************************
00002  * Software License Agreement (BSD License)
00003  *
00004  * Copyright 2008-2009  Marius Muja (mariusm@cs.ubc.ca). All rights reserved.
00005  * Copyright 2008-2009  David G. Lowe (lowe@cs.ubc.ca). All rights reserved.
00006  *
00007  * THE BSD LICENSE
00008  *
00009  * Redistribution and use in source and binary forms, with or without
00010  * modification, are permitted provided that the following conditions
00011  * are met:
00012  *
00013  * 1. Redistributions of source code must retain the above copyright
00014  *    notice, this list of conditions and the following disclaimer.
00015  * 2. Redistributions in binary form must reproduce the above copyright
00016  *    notice, this list of conditions and the following disclaimer in the
00017  *    documentation and/or other materials provided with the distribution.
00018  *
00019  * THIS SOFTWARE IS PROVIDED BY THE AUTHOR ``AS IS'' AND ANY EXPRESS OR
00020  * IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES
00021  * OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED.
00022  * IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR ANY DIRECT, INDIRECT,
00023  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT
00024  * NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
00025  * DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY
00026  * THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
00027  * (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF
00028  * THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
00029  *************************************************************************/
00030 
00031 #ifndef RTABMAP_FLANN_HPP_
00032 #define RTABMAP_FLANN_HPP_
00033 
00034 
00035 #include <vector>
00036 #include <string>
00037 #include <cassert>
00038 #include <cstdio>
00039 
00040 #include "general.h"
00041 #include "util/matrix.h"
00042 #include "util/params.h"
00043 #include "util/saving.h"
00044 
00045 #include "algorithms/all_indices.h"
00046 
00047 namespace rtflann
00048 {
00049 
00054 inline void log_verbosity(int level)
00055 {
00056     if (level >= 0) {
00057         Logger::setLevel(level);
00058     }
00059 }
00060 
00064 struct SavedIndexParams : public IndexParams
00065 {
00066     SavedIndexParams(std::string filename)
00067     {
00068         (*this)["algorithm"] = FLANN_INDEX_SAVED;
00069         (*this)["filename"] = filename;
00070     }
00071 };
00072 
00073 
00074 
00075 template<typename Distance>
00076 class Index
00077 {
00078 public:
00079     typedef typename Distance::ElementType ElementType;
00080     typedef typename Distance::ResultType DistanceType;
00081     typedef NNIndex<Distance> IndexType;
00082 
00083     Index(const IndexParams& params, Distance distance = Distance() )
00084         : index_params_(params)
00085     {
00086         flann_algorithm_t index_type = get_param<flann_algorithm_t>(params,"algorithm");
00087         loaded_ = false;
00088 
00089         Matrix<ElementType> features;
00090         if (index_type == FLANN_INDEX_SAVED) {
00091             nnIndex_ = load_saved_index(features, get_param<std::string>(params,"filename"), distance);
00092             loaded_ = true;
00093         }
00094         else {
00095                 flann_algorithm_t index_type = get_param<flann_algorithm_t>(params, "algorithm");
00096             nnIndex_ = create_index_by_type<Distance>(index_type, features, params, distance);
00097         }
00098     }
00099 
00100 
00101     Index(const Matrix<ElementType>& features, const IndexParams& params, Distance distance = Distance() )
00102         : index_params_(params)
00103     {
00104         flann_algorithm_t index_type = get_param<flann_algorithm_t>(params,"algorithm");
00105         loaded_ = false;
00106 
00107         if (index_type == FLANN_INDEX_SAVED) {
00108             nnIndex_ = load_saved_index(features, get_param<std::string>(params,"filename"), distance);
00109             loaded_ = true;
00110         }
00111         else {
00112                 flann_algorithm_t index_type = get_param<flann_algorithm_t>(params, "algorithm");
00113             nnIndex_ = create_index_by_type<Distance>(index_type, features, params, distance);
00114         }
00115     }
00116 
00117 
00118     Index(const Index& other) : loaded_(other.loaded_), index_params_(other.index_params_)
00119     {
00120         nnIndex_ = other.nnIndex_->clone();
00121     }
00122 
00123     Index& operator=(Index other)
00124     {
00125         this->swap(other);
00126         return *this;
00127     }
00128 
00129     virtual ~Index()
00130     {
00131         delete nnIndex_;
00132     }
00133 
00137     void buildIndex()
00138     {
00139         if (!loaded_) {
00140             nnIndex_->buildIndex();
00141         }
00142     }
00143 
00144     void buildIndex(const Matrix<ElementType>& points)
00145     {
00146         nnIndex_->buildIndex(points);
00147     }
00148 
00149     void addPoints(const Matrix<ElementType>& points, float rebuild_threshold = 2)
00150     {
00151         nnIndex_->addPoints(points, rebuild_threshold);
00152     }
00153 
00158     void removePoint(size_t point_id)
00159     {
00160         nnIndex_->removePoint(point_id);
00161     }
00162 
00168     ElementType* getPoint(size_t point_id)
00169     {
00170         return nnIndex_->getPoint(point_id);
00171     }
00172 
00177     void save(std::string filename)
00178     {
00179         FILE* fout = fopen(filename.c_str(), "wb");
00180         if (fout == NULL) {
00181             throw FLANNException("Cannot open file");
00182         }
00183         nnIndex_->saveIndex(fout);
00184         fclose(fout);
00185     }
00186 
00190     size_t veclen() const
00191     {
00192         return nnIndex_->veclen();
00193     }
00194 
00198     size_t size() const
00199     {
00200         return nnIndex_->size();
00201     }
00202 
00203     size_t removedCount() const
00204         {
00205                 return nnIndex_->removedCount();
00206         }
00207 
00208     size_t sizeAtBuild() const
00209         {
00210                 return nnIndex_->sizeAtBuild();
00211         }
00212 
00216     flann_algorithm_t getType() const
00217     {
00218         return nnIndex_->getType();
00219     }
00220 
00224     int usedMemory() const
00225     {
00226         return nnIndex_->usedMemory();
00227     }
00228 
00229 
00233     IndexParams getParameters() const
00234     {
00235         return nnIndex_->getParameters();
00236     }
00237 
00246     int knnSearch(const Matrix<ElementType>& queries,
00247                                  Matrix<size_t>& indices,
00248                                  Matrix<DistanceType>& dists,
00249                                  size_t knn,
00250                            const SearchParams& params) const
00251     {
00252         return nnIndex_->knnSearch(queries, indices, dists, knn, params);
00253     }
00254 
00264     int knnSearch(const Matrix<ElementType>& queries,
00265                                  Matrix<int>& indices,
00266                                  Matrix<DistanceType>& dists,
00267                                  size_t knn,
00268                            const SearchParams& params) const
00269     {
00270         return nnIndex_->knnSearch(queries, indices, dists, knn, params);
00271     }
00272 
00281     int knnSearch(const Matrix<ElementType>& queries,
00282                                  std::vector< std::vector<size_t> >& indices,
00283                                  std::vector<std::vector<DistanceType> >& dists,
00284                                  size_t knn,
00285                            const SearchParams& params) const
00286     {
00287         return nnIndex_->knnSearch(queries, indices, dists, knn, params);
00288     }
00289 
00299     int knnSearch(const Matrix<ElementType>& queries,
00300                                  std::vector< std::vector<int> >& indices,
00301                                  std::vector<std::vector<DistanceType> >& dists,
00302                                  size_t knn,
00303                            const SearchParams& params) const
00304     {
00305         return nnIndex_->knnSearch(queries, indices, dists, knn, params);
00306     }
00307 
00317     int radiusSearch(const Matrix<ElementType>& queries,
00318                                     Matrix<size_t>& indices,
00319                                     Matrix<DistanceType>& dists,
00320                                     float radius,
00321                               const SearchParams& params) const
00322     {
00323         return nnIndex_->radiusSearch(queries, indices, dists, radius, params);
00324     }
00325 
00335     int radiusSearch(const Matrix<ElementType>& queries,
00336                                     Matrix<int>& indices,
00337                                     Matrix<DistanceType>& dists,
00338                                     float radius,
00339                               const SearchParams& params) const
00340     {
00341         return nnIndex_->radiusSearch(queries, indices, dists, radius, params);
00342     }
00343 
00353     int radiusSearch(const Matrix<ElementType>& queries,
00354                                     std::vector< std::vector<size_t> >& indices,
00355                                     std::vector<std::vector<DistanceType> >& dists,
00356                                     float radius,
00357                               const SearchParams& params) const
00358     {
00359         return nnIndex_->radiusSearch(queries, indices, dists, radius, params);
00360     }
00361 
00371     int radiusSearch(const Matrix<ElementType>& queries,
00372                                     std::vector< std::vector<int> >& indices,
00373                                     std::vector<std::vector<DistanceType> >& dists,
00374                                     float radius,
00375                               const SearchParams& params) const
00376     {
00377         return nnIndex_->radiusSearch(queries, indices, dists, radius, params);
00378     }
00379 
00380 private:
00381     IndexType* load_saved_index(const Matrix<ElementType>& dataset, const std::string& filename, Distance distance)
00382     {
00383         FILE* fin = fopen(filename.c_str(), "rb");
00384         if (fin == NULL) {
00385             return NULL;
00386         }
00387         IndexHeader header = load_header(fin);
00388         if (header.h.data_type != flann_datatype_value<ElementType>::value) {
00389             throw FLANNException("Datatype of saved index is different than of the one to be loaded.");
00390         }
00391 
00392         IndexParams params;
00393         params["algorithm"] = header.h.index_type;
00394         IndexType* nnIndex = create_index_by_type<Distance>(header.h.index_type, dataset, params, distance);
00395         rewind(fin);
00396         nnIndex->loadIndex(fin);
00397         fclose(fin);
00398 
00399         return nnIndex;
00400     }
00401 
00402     void swap( Index& other)
00403     {
00404         std::swap(nnIndex_, other.nnIndex_);
00405         std::swap(loaded_, other.loaded_);
00406         std::swap(index_params_, other.index_params_);
00407     }
00408 
00409 private:
00411     IndexType* nnIndex_;
00413     bool loaded_;
00415     IndexParams index_params_;
00416 };
00417 
00418 
00419 
00420 
00421 
00433 template <typename Distance>
00434 int hierarchicalClustering(const Matrix<typename Distance::ElementType>& points, Matrix<typename Distance::ResultType>& centers,
00435                            const KMeansIndexParams& params, Distance d = Distance())
00436 {
00437     KMeansIndex<Distance> kmeans(points, params, d);
00438     kmeans.buildIndex();
00439 
00440     int clusterNum = kmeans.getClusterCenters(centers);
00441     return clusterNum;
00442 }
00443 
00444 }
00445 #endif /* RTABMAP_FLANN_HPP_ */


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