autotuned_index.h
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 #ifndef RTABMAP_FLANN_AUTOTUNED_INDEX_H_
00031 #define RTABMAP_FLANN_AUTOTUNED_INDEX_H_
00032 
00033 #include "rtflann/general.h"
00034 #include "rtflann/algorithms/nn_index.h"
00035 #include "rtflann/nn/ground_truth.h"
00036 #include "rtflann/nn/index_testing.h"
00037 #include "rtflann/util/sampling.h"
00038 #include "rtflann/algorithms/kdtree_index.h"
00039 #include "rtflann/algorithms/kdtree_single_index.h"
00040 #include "rtflann/algorithms/kmeans_index.h"
00041 #include "rtflann/algorithms/composite_index.h"
00042 #include "rtflann/algorithms/linear_index.h"
00043 #include "rtflann/util/logger.h"
00044 
00045 
00046 namespace rtflann
00047 {
00048 
00049 template<typename Distance>
00050 inline NNIndex<Distance>*
00051   create_index_by_type(const flann_algorithm_t index_type,
00052         const Matrix<typename Distance::ElementType>& dataset, const IndexParams& params, const Distance& distance = Distance());
00053 
00054 
00055 struct AutotunedIndexParams : public IndexParams
00056 {
00057     AutotunedIndexParams(float target_precision = 0.8, float build_weight = 0.01, float memory_weight = 0, float sample_fraction = 0.1)
00058     {
00059         (*this)["algorithm"] = FLANN_INDEX_AUTOTUNED;
00060         // precision desired (used for autotuning, -1 otherwise)
00061         (*this)["target_precision"] = target_precision;
00062         // build tree time weighting factor
00063         (*this)["build_weight"] = build_weight;
00064         // index memory weighting factor
00065         (*this)["memory_weight"] = memory_weight;
00066         // what fraction of the dataset to use for autotuning
00067         (*this)["sample_fraction"] = sample_fraction;
00068     }
00069 };
00070 
00071 
00072 template <typename Distance>
00073 class AutotunedIndex : public NNIndex<Distance>
00074 {
00075 public:
00076     typedef typename Distance::ElementType ElementType;
00077     typedef typename Distance::ResultType DistanceType;
00078     
00079     typedef NNIndex<Distance> BaseClass;
00080 
00081     typedef AutotunedIndex<Distance> IndexType;
00082 
00083     typedef bool needs_kdtree_distance;
00084 
00085     AutotunedIndex(const Matrix<ElementType>& inputData, const IndexParams& params = AutotunedIndexParams(), Distance d = Distance()) :
00086         BaseClass(params, d), bestIndex_(NULL), speedup_(0), dataset_(inputData)
00087     {
00088         target_precision_ = get_param(params, "target_precision",0.8f);
00089         build_weight_ =  get_param(params,"build_weight", 0.01f);
00090         memory_weight_ = get_param(params, "memory_weight", 0.0f);
00091         sample_fraction_ = get_param(params,"sample_fraction", 0.1f);
00092     }
00093 
00094     AutotunedIndex(const IndexParams& params = AutotunedIndexParams(), Distance d = Distance()) :
00095         BaseClass(params, d), bestIndex_(NULL), speedup_(0)
00096     {
00097         target_precision_ = get_param(params, "target_precision",0.8f);
00098         build_weight_ =  get_param(params,"build_weight", 0.01f);
00099         memory_weight_ = get_param(params, "memory_weight", 0.0f);
00100         sample_fraction_ = get_param(params,"sample_fraction", 0.1f);
00101     }
00102 
00103     AutotunedIndex(const AutotunedIndex& other) : BaseClass(other),
00104                 bestParams_(other.bestParams_),
00105                 bestSearchParams_(other.bestSearchParams_),
00106                 speedup_(other.speedup_),
00107                 dataset_(other.dataset_),
00108                 target_precision_(other.target_precision_),
00109                 build_weight_(other.build_weight_),
00110                 memory_weight_(other.memory_weight_),
00111                 sample_fraction_(other.sample_fraction_)
00112     {
00113                 bestIndex_ = other.bestIndex_->clone();
00114     }
00115 
00116     AutotunedIndex& operator=(AutotunedIndex other)
00117     {
00118         this->swap(other);
00119         return * this;
00120     }
00121 
00122     virtual ~AutotunedIndex()
00123     {
00124         delete bestIndex_;
00125     }
00126 
00127     BaseClass* clone() const
00128     {
00129         return new AutotunedIndex(*this);
00130     }
00131 
00135     void buildIndex()
00136     {
00137         bestParams_ = estimateBuildParams();
00138         Logger::info("----------------------------------------------------\n");
00139         Logger::info("Autotuned parameters:\n");
00140         if (Logger::getLevel()>=FLANN_LOG_INFO)
00141                 print_params(bestParams_);
00142         Logger::info("----------------------------------------------------\n");
00143 
00144         flann_algorithm_t index_type = get_param<flann_algorithm_t>(bestParams_,"algorithm");
00145         bestIndex_ = create_index_by_type(index_type, dataset_, bestParams_, distance_);
00146         bestIndex_->buildIndex();
00147         speedup_ = estimateSearchParams(bestSearchParams_);
00148         Logger::info("----------------------------------------------------\n");
00149         Logger::info("Search parameters:\n");
00150         if (Logger::getLevel()>=FLANN_LOG_INFO)
00151                 print_params(bestSearchParams_);
00152         Logger::info("----------------------------------------------------\n");
00153         bestParams_["search_params"] = bestSearchParams_;
00154         bestParams_["speedup"] = speedup_;
00155     }
00156     
00157     void buildIndex(const Matrix<ElementType>& dataset)
00158     {
00159         dataset_ = dataset;
00160         this->buildIndex();
00161     }
00162 
00163 
00164     void addPoints(const Matrix<ElementType>& points, float rebuild_threshold = 2)
00165     {
00166         if (bestIndex_) {
00167             bestIndex_->addPoints(points, rebuild_threshold);
00168         }
00169     }
00170     
00171     void removePoint(size_t id)
00172     {
00173         if (bestIndex_) {
00174             bestIndex_->removePoint(id);
00175         }
00176     }
00177 
00178     
00179     template<typename Archive>
00180     void serialize(Archive& ar)
00181     {
00182         ar.setObject(this);
00183 
00184         ar & *static_cast<NNIndex<Distance>*>(this);
00185 
00186         ar & target_precision_;
00187         ar & build_weight_;
00188         ar & memory_weight_;
00189         ar & sample_fraction_;
00190 
00191         flann_algorithm_t index_type;
00192         if (Archive::is_saving::value) {
00193                 index_type = get_param<flann_algorithm_t>(bestParams_,"algorithm");
00194         }
00195         ar & index_type;
00196         ar & bestSearchParams_.checks;
00197 
00198         if (Archive::is_loading::value) {
00199                 bestParams_["algorithm"] = index_type;
00200 
00201                 index_params_["algorithm"] = getType();
00202             index_params_["target_precision_"] = target_precision_;
00203             index_params_["build_weight_"] = build_weight_;
00204             index_params_["memory_weight_"] = memory_weight_;
00205             index_params_["sample_fraction_"] = sample_fraction_;
00206         }
00207     }
00208 
00209     void saveIndex(FILE* stream)
00210     {
00211         {
00212             serialization::SaveArchive sa(stream);
00213             sa & *this;
00214         }
00215 
00216         bestIndex_->saveIndex(stream);
00217     }
00218 
00219     void loadIndex(FILE* stream)
00220     {
00221         {
00222             serialization::LoadArchive la(stream);
00223             la & *this;
00224         }
00225         
00226         IndexParams params;
00227         flann_algorithm_t index_type = get_param<flann_algorithm_t>(bestParams_,"algorithm");
00228         bestIndex_ = create_index_by_type<Distance>((flann_algorithm_t)index_type, dataset_, params, distance_);
00229         bestIndex_->loadIndex(stream);
00230     }
00231 
00232     int knnSearch(const Matrix<ElementType>& queries,
00233             Matrix<size_t>& indices,
00234             Matrix<DistanceType>& dists,
00235             size_t knn,
00236             const SearchParams& params) const
00237     {
00238         if (params.checks == FLANN_CHECKS_AUTOTUNED) {
00239             return bestIndex_->knnSearch(queries, indices, dists, knn, bestSearchParams_);
00240         }
00241         else {
00242             return bestIndex_->knnSearch(queries, indices, dists, knn, params);
00243         }
00244     }
00245 
00246     int knnSearch(const Matrix<ElementType>& queries,
00247             std::vector< std::vector<size_t> >& indices,
00248             std::vector<std::vector<DistanceType> >& dists,
00249             size_t knn,
00250             const SearchParams& params) const
00251     {
00252         if (params.checks == FLANN_CHECKS_AUTOTUNED) {
00253             return bestIndex_->knnSearch(queries, indices, dists, knn, bestSearchParams_);
00254         }
00255         else {
00256             return bestIndex_->knnSearch(queries, indices, dists, knn, params);
00257         }
00258 
00259     }
00260     
00261     int radiusSearch(const Matrix<ElementType>& queries,
00262             Matrix<size_t>& indices,
00263             Matrix<DistanceType>& dists,
00264             DistanceType radius,
00265             const SearchParams& params) const
00266     {
00267         if (params.checks == FLANN_CHECKS_AUTOTUNED) {
00268             return bestIndex_->radiusSearch(queries, indices, dists, radius, bestSearchParams_);
00269         }
00270         else {
00271             return bestIndex_->radiusSearch(queries, indices, dists, radius, params);
00272         }
00273     }
00274 
00275     int radiusSearch(const Matrix<ElementType>& queries,
00276             std::vector< std::vector<size_t> >& indices,
00277             std::vector<std::vector<DistanceType> >& dists,
00278             DistanceType radius,
00279             const SearchParams& params) const
00280     {
00281         if (params.checks == FLANN_CHECKS_AUTOTUNED) {
00282             return bestIndex_->radiusSearch(queries, indices, dists, radius, bestSearchParams_);
00283         }
00284         else {
00285             return bestIndex_->radiusSearch(queries, indices, dists, radius, params);
00286         }        
00287     }
00288 
00289     
00290     
00294     void findNeighbors(ResultSet<DistanceType>& result, const ElementType* vec, const SearchParams& searchParams) const
00295     {
00296         // should not get here
00297         assert(false);
00298     }
00299 
00300     IndexParams getParameters() const
00301     {
00302         return bestParams_;
00303     }
00304 
00305     FLANN_DEPRECATED SearchParams getSearchParameters() const
00306     {
00307         return bestSearchParams_;
00308     }
00309 
00310     FLANN_DEPRECATED float getSpeedup() const
00311     {
00312         return speedup_;
00313     }
00314 
00315 
00319     size_t size() const
00320     {
00321         return bestIndex_->size();
00322     }
00323 
00327     size_t veclen() const
00328     {
00329         return bestIndex_->veclen();
00330     }
00331 
00335     int usedMemory() const
00336     {
00337         return bestIndex_->usedMemory();
00338     }
00339 
00343     flann_algorithm_t getType() const
00344     {
00345         return FLANN_INDEX_AUTOTUNED;
00346     }
00347 
00348 protected:
00349     void buildIndexImpl()
00350     {
00351         /* nothing to do here */
00352     }
00353 
00354     void freeIndex()
00355     {
00356         /* nothing to do here */
00357     }
00358 
00359 private:
00360 
00361     struct CostData
00362     {
00363         float searchTimeCost;
00364         float buildTimeCost;
00365         float memoryCost;
00366         float totalCost;
00367         IndexParams params;
00368     };
00369 
00370     void evaluate_kmeans(CostData& cost)
00371     {
00372         StartStopTimer t;
00373         int checks;
00374         const int nn = 1;
00375 
00376         Logger::info("KMeansTree using params: max_iterations=%d, branching=%d\n",
00377                      get_param<int>(cost.params,"iterations"),
00378                      get_param<int>(cost.params,"branching"));
00379         KMeansIndex<Distance> kmeans(sampledDataset_, cost.params, distance_);
00380         // measure index build time
00381         t.start();
00382         kmeans.buildIndex();
00383         t.stop();
00384         float buildTime = (float)t.value;
00385 
00386         // measure search time
00387         float searchTime = test_index_precision(kmeans, sampledDataset_, testDataset_, gt_matches_, target_precision_, checks, distance_, nn);
00388 
00389         float datasetMemory = float(sampledDataset_.rows * sampledDataset_.cols * sizeof(float));
00390         cost.memoryCost = (kmeans.usedMemory() + datasetMemory) / datasetMemory;
00391         cost.searchTimeCost = searchTime;
00392         cost.buildTimeCost = buildTime;
00393         Logger::info("KMeansTree buildTime=%g, searchTime=%g, build_weight=%g\n", buildTime, searchTime, build_weight_);
00394     }
00395 
00396 
00397     void evaluate_kdtree(CostData& cost)
00398     {
00399         StartStopTimer t;
00400         int checks;
00401         const int nn = 1;
00402 
00403         Logger::info("KDTree using params: trees=%d\n", get_param<int>(cost.params,"trees"));
00404         KDTreeIndex<Distance> kdtree(sampledDataset_, cost.params, distance_);
00405 
00406         t.start();
00407         kdtree.buildIndex();
00408         t.stop();
00409         float buildTime = (float)t.value;
00410 
00411         //measure search time
00412         float searchTime = test_index_precision(kdtree, sampledDataset_, testDataset_, gt_matches_, target_precision_, checks, distance_, nn);
00413 
00414         float datasetMemory = float(sampledDataset_.rows * sampledDataset_.cols * sizeof(float));
00415         cost.memoryCost = (kdtree.usedMemory() + datasetMemory) / datasetMemory;
00416         cost.searchTimeCost = searchTime;
00417         cost.buildTimeCost = buildTime;
00418         Logger::info("KDTree buildTime=%g, searchTime=%g\n", buildTime, searchTime);
00419     }
00420 
00421 
00422     //    struct KMeansSimpleDownhillFunctor {
00423     //
00424     //        Autotune& autotuner;
00425     //        KMeansSimpleDownhillFunctor(Autotune& autotuner_) : autotuner(autotuner_) {};
00426     //
00427     //        float operator()(int* params) {
00428     //
00429     //            float maxFloat = numeric_limits<float>::max();
00430     //
00431     //            if (params[0]<2) return maxFloat;
00432     //            if (params[1]<0) return maxFloat;
00433     //
00434     //            CostData c;
00435     //            c.params["algorithm"] = KMEANS;
00436     //            c.params["centers-init"] = CENTERS_RANDOM;
00437     //            c.params["branching"] = params[0];
00438     //            c.params["max-iterations"] = params[1];
00439     //
00440     //            autotuner.evaluate_kmeans(c);
00441     //
00442     //            return c.timeCost;
00443     //
00444     //        }
00445     //    };
00446     //
00447     //    struct KDTreeSimpleDownhillFunctor {
00448     //
00449     //        Autotune& autotuner;
00450     //        KDTreeSimpleDownhillFunctor(Autotune& autotuner_) : autotuner(autotuner_) {};
00451     //
00452     //        float operator()(int* params) {
00453     //            float maxFloat = numeric_limits<float>::max();
00454     //
00455     //            if (params[0]<1) return maxFloat;
00456     //
00457     //            CostData c;
00458     //            c.params["algorithm"] = KDTREE;
00459     //            c.params["trees"] = params[0];
00460     //
00461     //            autotuner.evaluate_kdtree(c);
00462     //
00463     //            return c.timeCost;
00464     //
00465     //        }
00466     //    };
00467 
00468 
00469 
00470     void optimizeKMeans(std::vector<CostData>& costs)
00471     {
00472         Logger::info("KMEANS, Step 1: Exploring parameter space\n");
00473 
00474         // explore kmeans parameters space using combinations of the parameters below
00475         int maxIterations[] = { 1, 5, 10, 15 };
00476         int branchingFactors[] = { 16, 32, 64, 128, 256 };
00477 
00478         int kmeansParamSpaceSize = FLANN_ARRAY_LEN(maxIterations) * FLANN_ARRAY_LEN(branchingFactors);
00479         costs.reserve(costs.size() + kmeansParamSpaceSize);
00480 
00481         // evaluate kmeans for all parameter combinations
00482         for (size_t i = 0; i < FLANN_ARRAY_LEN(maxIterations); ++i) {
00483             for (size_t j = 0; j < FLANN_ARRAY_LEN(branchingFactors); ++j) {
00484                 CostData cost;
00485                 cost.params["algorithm"] = FLANN_INDEX_KMEANS;
00486                 cost.params["centers_init"] = FLANN_CENTERS_RANDOM;
00487                 cost.params["iterations"] = maxIterations[i];
00488                 cost.params["branching"] = branchingFactors[j];
00489 
00490                 evaluate_kmeans(cost);
00491                 costs.push_back(cost);
00492             }
00493         }
00494 
00495         //         Logger::info("KMEANS, Step 2: simplex-downhill optimization\n");
00496         //
00497         //         const int n = 2;
00498         //         // choose initial simplex points as the best parameters so far
00499         //         int kmeansNMPoints[n*(n+1)];
00500         //         float kmeansVals[n+1];
00501         //         for (int i=0;i<n+1;++i) {
00502         //             kmeansNMPoints[i*n] = (int)kmeansCosts[i].params["branching"];
00503         //             kmeansNMPoints[i*n+1] = (int)kmeansCosts[i].params["max-iterations"];
00504         //             kmeansVals[i] = kmeansCosts[i].timeCost;
00505         //         }
00506         //         KMeansSimpleDownhillFunctor kmeans_cost_func(*this);
00507         //         // run optimization
00508         //         optimizeSimplexDownhill(kmeansNMPoints,n,kmeans_cost_func,kmeansVals);
00509         //         // store results
00510         //         for (int i=0;i<n+1;++i) {
00511         //             kmeansCosts[i].params["branching"] = kmeansNMPoints[i*2];
00512         //             kmeansCosts[i].params["max-iterations"] = kmeansNMPoints[i*2+1];
00513         //             kmeansCosts[i].timeCost = kmeansVals[i];
00514         //         }
00515     }
00516 
00517 
00518     void optimizeKDTree(std::vector<CostData>& costs)
00519     {
00520         Logger::info("KD-TREE, Step 1: Exploring parameter space\n");
00521 
00522         // explore kd-tree parameters space using the parameters below
00523         int testTrees[] = { 1, 4, 8, 16, 32 };
00524 
00525         // evaluate kdtree for all parameter combinations
00526         for (size_t i = 0; i < FLANN_ARRAY_LEN(testTrees); ++i) {
00527             CostData cost;
00528             cost.params["algorithm"] = FLANN_INDEX_KDTREE;
00529             cost.params["trees"] = testTrees[i];
00530 
00531             evaluate_kdtree(cost);
00532             costs.push_back(cost);
00533         }
00534 
00535         //         Logger::info("KD-TREE, Step 2: simplex-downhill optimization\n");
00536         //
00537         //         const int n = 1;
00538         //         // choose initial simplex points as the best parameters so far
00539         //         int kdtreeNMPoints[n*(n+1)];
00540         //         float kdtreeVals[n+1];
00541         //         for (int i=0;i<n+1;++i) {
00542         //             kdtreeNMPoints[i] = (int)kdtreeCosts[i].params["trees"];
00543         //             kdtreeVals[i] = kdtreeCosts[i].timeCost;
00544         //         }
00545         //         KDTreeSimpleDownhillFunctor kdtree_cost_func(*this);
00546         //         // run optimization
00547         //         optimizeSimplexDownhill(kdtreeNMPoints,n,kdtree_cost_func,kdtreeVals);
00548         //         // store results
00549         //         for (int i=0;i<n+1;++i) {
00550         //             kdtreeCosts[i].params["trees"] = kdtreeNMPoints[i];
00551         //             kdtreeCosts[i].timeCost = kdtreeVals[i];
00552         //         }
00553     }
00554 
00560     IndexParams estimateBuildParams()
00561     {
00562         std::vector<CostData> costs;
00563 
00564         int sampleSize = int(sample_fraction_ * dataset_.rows);
00565         int testSampleSize = std::min(sampleSize / 10, 1000);
00566 
00567         Logger::info("Entering autotuning, dataset size: %d, sampleSize: %d, testSampleSize: %d, target precision: %g\n", dataset_.rows, sampleSize, testSampleSize, target_precision_);
00568 
00569         // For a very small dataset, it makes no sense to build any fancy index, just
00570         // use linear search
00571         if (testSampleSize < 10) {
00572             Logger::info("Choosing linear, dataset too small\n");
00573             return LinearIndexParams();
00574         }
00575 
00576         // We use a fraction of the original dataset to speedup the autotune algorithm
00577         sampledDataset_ = random_sample(dataset_, sampleSize);
00578         // We use a cross-validation approach, first we sample a testset from the dataset
00579         testDataset_ = random_sample(sampledDataset_, testSampleSize, true);
00580 
00581         // We compute the ground truth using linear search
00582         Logger::info("Computing ground truth... \n");
00583         gt_matches_ = Matrix<size_t>(new size_t[testDataset_.rows], testDataset_.rows, 1);
00584         StartStopTimer t;
00585         int repeats = 0;
00586         t.reset();
00587         while (t.value<0.2) {
00588                 repeats++;
00589             t.start();
00590                 compute_ground_truth<Distance>(sampledDataset_, testDataset_, gt_matches_, 0, distance_);
00591             t.stop();
00592         }
00593 
00594         CostData linear_cost;
00595         linear_cost.searchTimeCost = (float)t.value/repeats;
00596         linear_cost.buildTimeCost = 0;
00597         linear_cost.memoryCost = 0;
00598         linear_cost.params["algorithm"] = FLANN_INDEX_LINEAR;
00599 
00600         costs.push_back(linear_cost);
00601 
00602         // Start parameter autotune process
00603         Logger::info("Autotuning parameters...\n");
00604 
00605         optimizeKMeans(costs);
00606         optimizeKDTree(costs);
00607 
00608         float bestTimeCost = costs[0].buildTimeCost * build_weight_ + costs[0].searchTimeCost;
00609         for (size_t i = 0; i < costs.size(); ++i) {
00610             float timeCost = costs[i].buildTimeCost * build_weight_ + costs[i].searchTimeCost;
00611             Logger::debug("Time cost: %g\n", timeCost);
00612             if (timeCost < bestTimeCost) {
00613                 bestTimeCost = timeCost;
00614             }
00615         }
00616         Logger::debug("Best time cost: %g\n", bestTimeCost);
00617 
00618         IndexParams bestParams = costs[0].params;
00619         if (bestTimeCost > 0) {
00620                 float bestCost = (costs[0].buildTimeCost * build_weight_ + costs[0].searchTimeCost) / bestTimeCost;
00621                 for (size_t i = 0; i < costs.size(); ++i) {
00622                         float crtCost = (costs[i].buildTimeCost * build_weight_ + costs[i].searchTimeCost) / bestTimeCost +
00623                                         memory_weight_ * costs[i].memoryCost;
00624                         Logger::debug("Cost: %g\n", crtCost);
00625                         if (crtCost < bestCost) {
00626                                 bestCost = crtCost;
00627                                 bestParams = costs[i].params;
00628                         }
00629                 }
00630             Logger::debug("Best cost: %g\n", bestCost);
00631         }
00632 
00633         delete[] gt_matches_.ptr();
00634         delete[] testDataset_.ptr();
00635         delete[] sampledDataset_.ptr();
00636 
00637         return bestParams;
00638     }
00639 
00640 
00641 
00647     float estimateSearchParams(SearchParams& searchParams)
00648     {
00649         const int nn = 1;
00650         const size_t SAMPLE_COUNT = 1000;
00651 
00652         assert(bestIndex_ != NULL); // must have a valid index
00653 
00654         float speedup = 0;
00655 
00656         int samples = (int)std::min(dataset_.rows / 10, SAMPLE_COUNT);
00657         if (samples > 0) {
00658             Matrix<ElementType> testDataset = random_sample(dataset_, samples);
00659 
00660             Logger::info("Computing ground truth\n");
00661 
00662             // we need to compute the ground truth first
00663             Matrix<size_t> gt_matches(new size_t[testDataset.rows], testDataset.rows, 1);
00664             StartStopTimer t;
00665             int repeats = 0;
00666             t.reset();
00667             while (t.value<0.2) {
00668                 repeats++;
00669                 t.start();
00670                 compute_ground_truth<Distance>(dataset_, testDataset, gt_matches, 1, distance_);
00671                 t.stop();
00672             }
00673             float linear = (float)t.value/repeats;
00674 
00675             int checks;
00676             Logger::info("Estimating number of checks\n");
00677 
00678             float searchTime;
00679             float cb_index;
00680             if (bestIndex_->getType() == FLANN_INDEX_KMEANS) {
00681                 Logger::info("KMeans algorithm, estimating cluster border factor\n");
00682                 KMeansIndex<Distance>* kmeans = static_cast<KMeansIndex<Distance>*>(bestIndex_);
00683                 float bestSearchTime = -1;
00684                 float best_cb_index = -1;
00685                 int best_checks = -1;
00686                 for (cb_index = 0; cb_index < 1.1f; cb_index += 0.2f) {
00687                     kmeans->set_cb_index(cb_index);
00688                     searchTime = test_index_precision(*kmeans, dataset_, testDataset, gt_matches, target_precision_, checks, distance_, nn, 1);
00689                     if ((searchTime < bestSearchTime) || (bestSearchTime == -1)) {
00690                         bestSearchTime = searchTime;
00691                         best_cb_index = cb_index;
00692                         best_checks = checks;
00693                     }
00694                 }
00695                 searchTime = bestSearchTime;
00696                 cb_index = best_cb_index;
00697                 checks = best_checks;
00698 
00699                 kmeans->set_cb_index(best_cb_index);
00700                 Logger::info("Optimum cb_index: %g\n", cb_index);
00701                 bestParams_["cb_index"] = cb_index;
00702             }
00703             else {
00704                 searchTime = test_index_precision(*bestIndex_, dataset_, testDataset, gt_matches, target_precision_, checks, distance_, nn, 1);
00705             }
00706 
00707             Logger::info("Required number of checks: %d \n", checks);
00708             searchParams.checks = checks;
00709 
00710             speedup = linear / searchTime;
00711 
00712             delete[] gt_matches.ptr();
00713             delete[] testDataset.ptr();
00714         }
00715 
00716         return speedup;
00717     }
00718 
00719 
00720     void swap(AutotunedIndex& other)
00721     {
00722         BaseClass::swap(other);
00723         std::swap(bestIndex_, other.bestIndex_);
00724         std::swap(bestParams_, other.bestParams_);
00725         std::swap(bestSearchParams_, other.bestSearchParams_);
00726         std::swap(speedup_, other.speedup_);
00727         std::swap(dataset_, other.dataset_);
00728         std::swap(target_precision_, other.target_precision_);
00729         std::swap(build_weight_, other.build_weight_);
00730         std::swap(memory_weight_, other.memory_weight_);
00731         std::swap(sample_fraction_, other.sample_fraction_);
00732     }
00733 
00734 private:
00735     NNIndex<Distance>* bestIndex_;
00736 
00737     IndexParams bestParams_;
00738     SearchParams bestSearchParams_;
00739 
00740     Matrix<ElementType> sampledDataset_;
00741     Matrix<ElementType> testDataset_;
00742     Matrix<size_t> gt_matches_;
00743 
00744     float speedup_;
00745 
00749     Matrix<ElementType> dataset_;
00750 
00754     float target_precision_;
00755     float build_weight_;
00756     float memory_weight_;
00757     float sample_fraction_;
00758 
00759     USING_BASECLASS_SYMBOLS
00760 };
00761 }
00762 
00763 #endif /* RTABMAP_FLANN_AUTOTUNED_INDEX_H_ */


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