ACloudViewer  3.9.4
A Modern Library for 3D Data Processing
autotuned_index.h
Go to the documentation of this file.
1 /***********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright 2008-2009 Marius Muja (mariusm@cs.ubc.ca). All rights reserved.
5  * Copyright 2008-2009 David G. Lowe (lowe@cs.ubc.ca). All rights reserved.
6  *
7  * THE BSD LICENSE
8  *
9  * Redistribution and use in source and binary forms, with or without
10  * modification, are permitted provided that the following conditions
11  * are met:
12  *
13  * 1. Redistributions of source code must retain the above copyright
14  * notice, this list of conditions and the following disclaimer.
15  * 2. Redistributions in binary form must reproduce the above copyright
16  * notice, this list of conditions and the following disclaimer in the
17  * documentation and/or other materials provided with the distribution.
18  *
19  * THIS SOFTWARE IS PROVIDED BY THE AUTHOR ``AS IS'' AND ANY EXPRESS OR
20  * IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES
21  * OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED.
22  * IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR ANY DIRECT, INDIRECT,
23  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT
24  * NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
25  * DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY
26  * THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
27  * (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF
28  * THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
29  *************************************************************************/
30 #ifndef FLANN_AUTOTUNED_INDEX_H_
31 #define FLANN_AUTOTUNED_INDEX_H_
32 
33 #include "FLANN/general.h"
35 #include "FLANN/nn/ground_truth.h"
36 #include "FLANN/nn/index_testing.h"
37 #include "FLANN/util/sampling.h"
43 #include "FLANN/util/logger.h"
44 
45 
46 namespace flann
47 {
48 
49 template<typename Distance>
50 inline NNIndex<Distance>*
51  create_index_by_type(const flann_algorithm_t index_type,
52  const Matrix<typename Distance::ElementType>& dataset, const IndexParams& params, const Distance& distance = Distance());
53 
54 
56 {
57  AutotunedIndexParams(float target_precision = 0.8, float build_weight = 0.01, float memory_weight = 0, float sample_fraction = 0.1)
58  {
59  (*this)["algorithm"] = FLANN_INDEX_AUTOTUNED;
60  // precision desired (used for autotuning, -1 otherwise)
61  (*this)["target_precision"] = target_precision;
62  // build tree time weighting factor
63  (*this)["build_weight"] = build_weight;
64  // index memory weighting factor
65  (*this)["memory_weight"] = memory_weight;
66  // what fraction of the dataset to use for autotuning
67  (*this)["sample_fraction"] = sample_fraction;
68  }
69 };
70 
71 
72 template <typename Distance>
73 class AutotunedIndex : public NNIndex<Distance>
74 {
75 public:
76  typedef typename Distance::ElementType ElementType;
77  typedef typename Distance::ResultType DistanceType;
78 
80 
82 
83  typedef bool needs_kdtree_distance;
84 
86  BaseClass(params, d), bestIndex_(NULL), speedup_(0), dataset_(inputData)
87  {
88  target_precision_ = get_param(params, "target_precision",0.8f);
89  build_weight_ = get_param(params,"build_weight", 0.01f);
90  memory_weight_ = get_param(params, "memory_weight", 0.0f);
91  sample_fraction_ = get_param(params,"sample_fraction", 0.1f);
92  }
93 
95  BaseClass(params, d), bestIndex_(NULL), speedup_(0)
96  {
97  target_precision_ = get_param(params, "target_precision",0.8f);
98  build_weight_ = get_param(params,"build_weight", 0.01f);
99  memory_weight_ = get_param(params, "memory_weight", 0.0f);
100  sample_fraction_ = get_param(params,"sample_fraction", 0.1f);
101  }
102 
103  AutotunedIndex(const AutotunedIndex& other) : BaseClass(other),
104  bestParams_(other.bestParams_),
105  bestSearchParams_(other.bestSearchParams_),
106  speedup_(other.speedup_),
107  dataset_(other.dataset_),
108  target_precision_(other.target_precision_),
109  build_weight_(other.build_weight_),
110  memory_weight_(other.memory_weight_),
111  sample_fraction_(other.sample_fraction_)
112  {
113  bestIndex_ = other.bestIndex_->clone();
114  }
115 
117  {
118  this->swap(other);
119  return * this;
120  }
121 
122  virtual ~AutotunedIndex()
123  {
124  delete bestIndex_;
125  }
126 
127  BaseClass* clone() const
128  {
129  return new AutotunedIndex(*this);
130  }
131 
135  void buildIndex()
136  {
137  bestParams_ = estimateBuildParams();
138  Logger::info("----------------------------------------------------\n");
139  Logger::info("Autotuned parameters:\n");
141  print_params(bestParams_);
142  Logger::info("----------------------------------------------------\n");
143 
144  flann_algorithm_t index_type = get_param<flann_algorithm_t>(bestParams_,"algorithm");
145  bestIndex_ = create_index_by_type(index_type, dataset_, bestParams_, distance_);
146  bestIndex_->buildIndex();
147  speedup_ = estimateSearchParams(bestSearchParams_);
148  Logger::info("----------------------------------------------------\n");
149  Logger::info("Search parameters:\n");
151  print_params(bestSearchParams_);
152  Logger::info("----------------------------------------------------\n");
153  bestParams_["search_params"] = bestSearchParams_;
154  bestParams_["speedup"] = speedup_;
155  }
156 
157  void buildIndex(const Matrix<ElementType>& dataset)
158  {
159  dataset_ = dataset;
160  this->buildIndex();
161  }
162 
163 
164  void addPoints(const Matrix<ElementType>& points, float rebuild_threshold = 2)
165  {
166  if (bestIndex_) {
167  bestIndex_->addPoints(points, rebuild_threshold);
168  }
169  }
170 
171  void removePoint(size_t id)
172  {
173  if (bestIndex_) {
174  bestIndex_->removePoint(id);
175  }
176  }
177 
178 
179  template<typename Archive>
180  void serialize(Archive& ar)
181  {
182  ar.setObject(this);
183 
184  ar & *static_cast<NNIndex<Distance>*>(this);
185 
186  ar & target_precision_;
187  ar & build_weight_;
188  ar & memory_weight_;
189  ar & sample_fraction_;
190 
191  flann_algorithm_t index_type;
192  if (Archive::is_saving::value) {
193  index_type = get_param<flann_algorithm_t>(bestParams_,"algorithm");
194  }
195  ar & index_type;
196  ar & bestSearchParams_.checks;
197 
198  if (Archive::is_loading::value) {
199  bestParams_["algorithm"] = index_type;
200 
201  index_params_["algorithm"] = getType();
202  index_params_["target_precision_"] = target_precision_;
203  index_params_["build_weight_"] = build_weight_;
204  index_params_["memory_weight_"] = memory_weight_;
205  index_params_["sample_fraction_"] = sample_fraction_;
206  }
207  }
208 
209  void saveIndex(FILE* stream)
210  {
211  {
212  serialization::SaveArchive sa(stream);
213  sa & *this;
214  }
215 
216  bestIndex_->saveIndex(stream);
217  }
218 
219  void loadIndex(FILE* stream)
220  {
221  {
222  serialization::LoadArchive la(stream);
223  la & *this;
224  }
225 
227  flann_algorithm_t index_type = get_param<flann_algorithm_t>(bestParams_,"algorithm");
228  bestIndex_ = create_index_by_type<Distance>((flann_algorithm_t)index_type, dataset_, params, distance_);
229  bestIndex_->loadIndex(stream);
230  }
231 
232  int knnSearch(const Matrix<ElementType>& queries,
233  Matrix<size_t>& indices,
234  Matrix<DistanceType>& dists,
235  size_t knn,
236  const SearchParams& params) const
237  {
238  if (params.checks == FLANN_CHECKS_AUTOTUNED) {
239  SearchParams autotuned_params = params;
240  autotuned_params.checks = bestSearchParams_.checks;
241  return bestIndex_->knnSearch(queries, indices, dists, knn, autotuned_params);
242  }
243  else {
244  return bestIndex_->knnSearch(queries, indices, dists, knn, params);
245  }
246  }
247 
248  int knnSearch(const Matrix<ElementType>& queries,
249  std::vector< std::vector<size_t> >& indices,
250  std::vector<std::vector<DistanceType> >& dists,
251  size_t knn,
252  const SearchParams& params) const
253  {
254  if (params.checks == FLANN_CHECKS_AUTOTUNED) {
255  SearchParams autotuned_params = params;
256  autotuned_params.checks = bestSearchParams_.checks;
257  return bestIndex_->knnSearch(queries, indices, dists, knn, autotuned_params);
258  }
259  else {
260  return bestIndex_->knnSearch(queries, indices, dists, knn, params);
261  }
262 
263  }
264 
265  int radiusSearch(const Matrix<ElementType>& queries,
266  Matrix<size_t>& indices,
267  Matrix<DistanceType>& dists,
268  DistanceType radius,
269  const SearchParams& params) const
270  {
271  if (params.checks == FLANN_CHECKS_AUTOTUNED) {
272  SearchParams autotuned_params = params;
273  autotuned_params.checks = bestSearchParams_.checks;
274  return bestIndex_->radiusSearch(queries, indices, dists, radius, autotuned_params);
275  }
276  else {
277  return bestIndex_->radiusSearch(queries, indices, dists, radius, params);
278  }
279  }
280 
281  int radiusSearch(const Matrix<ElementType>& queries,
282  std::vector< std::vector<size_t> >& indices,
283  std::vector<std::vector<DistanceType> >& dists,
284  DistanceType radius,
285  const SearchParams& params) const
286  {
287  if (params.checks == FLANN_CHECKS_AUTOTUNED) {
288  SearchParams autotuned_params = params;
289  autotuned_params.checks = bestSearchParams_.checks;
290  return bestIndex_->radiusSearch(queries, indices, dists, radius, autotuned_params);
291  }
292  else {
293  return bestIndex_->radiusSearch(queries, indices, dists, radius, params);
294  }
295  }
296 
297 
298 
302  void findNeighbors(ResultSet<DistanceType>& result, const ElementType* vec, const SearchParams& searchParams) const
303  {
304  // should not get here
305  assert(false);
306  }
307 
309  {
310  return bestParams_;
311  }
312 
314  {
315  return bestSearchParams_;
316  }
317 
319  {
320  return speedup_;
321  }
322 
323 
327  size_t size() const
328  {
329  return bestIndex_->size();
330  }
331 
335  size_t veclen() const
336  {
337  return bestIndex_->veclen();
338  }
339 
343  int usedMemory() const
344  {
345  return bestIndex_->usedMemory();
346  }
347 
352  {
353  return FLANN_INDEX_AUTOTUNED;
354  }
355 
356 protected:
358  {
359  /* nothing to do here */
360  }
361 
362  void freeIndex()
363  {
364  /* nothing to do here */
365  }
366 
367 private:
368 
369  struct CostData
370  {
371  float searchTimeCost;
372  float buildTimeCost;
373  float memoryCost;
374  float totalCost;
376  };
377 
378  void evaluate_kmeans(CostData& cost)
379  {
380  StartStopTimer t;
381  int checks;
382  const int nn = 1;
383 
384  Logger::info("KMeansTree using params: max_iterations=%d, branching=%d\n",
385  get_param<int>(cost.params,"iterations"),
386  get_param<int>(cost.params,"branching"));
387  KMeansIndex<Distance> kmeans(sampledDataset_, cost.params, distance_);
388  // measure index build time
389  t.start();
390  kmeans.buildIndex();
391  t.stop();
392  float buildTime = (float)t.value;
393 
394  // measure search time
395  float searchTime = test_index_precision(kmeans, sampledDataset_, testDataset_, gt_matches_, target_precision_, checks, distance_, nn);
396 
397  float datasetMemory = float(sampledDataset_.rows * sampledDataset_.cols * sizeof(float));
398  cost.memoryCost = (kmeans.usedMemory() + datasetMemory) / datasetMemory;
399  cost.searchTimeCost = searchTime;
400  cost.buildTimeCost = buildTime;
401  Logger::info("KMeansTree buildTime=%g, searchTime=%g, build_weight=%g\n", buildTime, searchTime, build_weight_);
402  }
403 
404 
405  void evaluate_kdtree(CostData& cost)
406  {
407  StartStopTimer t;
408  int checks;
409  const int nn = 1;
410 
411  Logger::info("KDTree using params: trees=%d\n", get_param<int>(cost.params,"trees"));
412  KDTreeIndex<Distance> kdtree(sampledDataset_, cost.params, distance_);
413 
414  t.start();
415  kdtree.buildIndex();
416  t.stop();
417  float buildTime = (float)t.value;
418 
419  //measure search time
420  float searchTime = test_index_precision(kdtree, sampledDataset_, testDataset_, gt_matches_, target_precision_, checks, distance_, nn);
421 
422  float datasetMemory = float(sampledDataset_.rows * sampledDataset_.cols * sizeof(float));
423  cost.memoryCost = (kdtree.usedMemory() + datasetMemory) / datasetMemory;
424  cost.searchTimeCost = searchTime;
425  cost.buildTimeCost = buildTime;
426  Logger::info("KDTree buildTime=%g, searchTime=%g\n", buildTime, searchTime);
427  }
428 
429 
430  // struct KMeansSimpleDownhillFunctor {
431  //
432  // Autotune& autotuner;
433  // KMeansSimpleDownhillFunctor(Autotune& autotuner_) : autotuner(autotuner_) {};
434  //
435  // float operator()(int* params) {
436  //
437  // float maxFloat = numeric_limits<float>::max();
438  //
439  // if (params[0]<2) return maxFloat;
440  // if (params[1]<0) return maxFloat;
441  //
442  // CostData c;
443  // c.params["algorithm"] = KMEANS;
444  // c.params["centers-init"] = CENTERS_RANDOM;
445  // c.params["branching"] = params[0];
446  // c.params["max-iterations"] = params[1];
447  //
448  // autotuner.evaluate_kmeans(c);
449  //
450  // return c.timeCost;
451  //
452  // }
453  // };
454  //
455  // struct KDTreeSimpleDownhillFunctor {
456  //
457  // Autotune& autotuner;
458  // KDTreeSimpleDownhillFunctor(Autotune& autotuner_) : autotuner(autotuner_) {};
459  //
460  // float operator()(int* params) {
461  // float maxFloat = numeric_limits<float>::max();
462  //
463  // if (params[0]<1) return maxFloat;
464  //
465  // CostData c;
466  // c.params["algorithm"] = KDTREE;
467  // c.params["trees"] = params[0];
468  //
469  // autotuner.evaluate_kdtree(c);
470  //
471  // return c.timeCost;
472  //
473  // }
474  // };
475 
476 
477 
478  void optimizeKMeans(std::vector<CostData>& costs)
479  {
480  Logger::info("KMEANS, Step 1: Exploring parameter space\n");
481 
482  // explore kmeans parameters space using combinations of the parameters below
483  int maxIterations[] = { 1, 5, 10, 15 };
484  int branchingFactors[] = { 16, 32, 64, 128, 256 };
485 
486  int kmeansParamSpaceSize = FLANN_ARRAY_LEN(maxIterations) * FLANN_ARRAY_LEN(branchingFactors);
487  costs.reserve(costs.size() + kmeansParamSpaceSize);
488 
489  // evaluate kmeans for all parameter combinations
490  for (size_t i = 0; i < FLANN_ARRAY_LEN(maxIterations); ++i) {
491  for (size_t j = 0; j < FLANN_ARRAY_LEN(branchingFactors); ++j) {
492  CostData cost;
493  cost.params["algorithm"] = FLANN_INDEX_KMEANS;
494  cost.params["centers_init"] = FLANN_CENTERS_RANDOM;
495  cost.params["iterations"] = maxIterations[i];
496  cost.params["branching"] = branchingFactors[j];
497 
498  evaluate_kmeans(cost);
499  costs.push_back(cost);
500  }
501  }
502 
503  // Logger::info("KMEANS, Step 2: simplex-downhill optimization\n");
504  //
505  // const int n = 2;
506  // // choose initial simplex points as the best parameters so far
507  // int kmeansNMPoints[n*(n+1)];
508  // float kmeansVals[n+1];
509  // for (int i=0;i<n+1;++i) {
510  // kmeansNMPoints[i*n] = (int)kmeansCosts[i].params["branching"];
511  // kmeansNMPoints[i*n+1] = (int)kmeansCosts[i].params["max-iterations"];
512  // kmeansVals[i] = kmeansCosts[i].timeCost;
513  // }
514  // KMeansSimpleDownhillFunctor kmeans_cost_func(*this);
515  // // run optimization
516  // optimizeSimplexDownhill(kmeansNMPoints,n,kmeans_cost_func,kmeansVals);
517  // // store results
518  // for (int i=0;i<n+1;++i) {
519  // kmeansCosts[i].params["branching"] = kmeansNMPoints[i*2];
520  // kmeansCosts[i].params["max-iterations"] = kmeansNMPoints[i*2+1];
521  // kmeansCosts[i].timeCost = kmeansVals[i];
522  // }
523  }
524 
525 
526  void optimizeKDTree(std::vector<CostData>& costs)
527  {
528  Logger::info("KD-TREE, Step 1: Exploring parameter space\n");
529 
530  // explore kd-tree parameters space using the parameters below
531  int testTrees[] = { 1, 4, 8, 16, 32, 64, 128};
532 
533  // evaluate kdtree for all parameter combinations
534  for (size_t i = 0; i < FLANN_ARRAY_LEN(testTrees); ++i) {
535  CostData cost;
536  cost.params["algorithm"] = FLANN_INDEX_KDTREE;
537  cost.params["trees"] = testTrees[i];
538 
539  evaluate_kdtree(cost);
540  costs.push_back(cost);
541  }
542 
543  // Logger::info("KD-TREE, Step 2: simplex-downhill optimization\n");
544  //
545  // const int n = 1;
546  // // choose initial simplex points as the best parameters so far
547  // int kdtreeNMPoints[n*(n+1)];
548  // float kdtreeVals[n+1];
549  // for (int i=0;i<n+1;++i) {
550  // kdtreeNMPoints[i] = (int)kdtreeCosts[i].params["trees"];
551  // kdtreeVals[i] = kdtreeCosts[i].timeCost;
552  // }
553  // KDTreeSimpleDownhillFunctor kdtree_cost_func(*this);
554  // // run optimization
555  // optimizeSimplexDownhill(kdtreeNMPoints,n,kdtree_cost_func,kdtreeVals);
556  // // store results
557  // for (int i=0;i<n+1;++i) {
558  // kdtreeCosts[i].params["trees"] = kdtreeNMPoints[i];
559  // kdtreeCosts[i].timeCost = kdtreeVals[i];
560  // }
561  }
562 
568  IndexParams estimateBuildParams()
569  {
570  std::vector<CostData> costs;
571 
572  int sampleSize = int(sample_fraction_ * dataset_.rows);
573  int testSampleSize = std::min(sampleSize / 10, 1000);
574 
575  Logger::info("Entering autotuning, dataset size: %d, sampleSize: %d, testSampleSize: %d, target precision: %g\n", dataset_.rows, sampleSize, testSampleSize, target_precision_);
576 
577  // For a very small dataset, it makes no sense to build any fancy index, just
578  // use linear search
579  if (testSampleSize < 10) {
580  Logger::info("Choosing linear, dataset too small\n");
581  return LinearIndexParams();
582  }
583 
584  // We use a fraction of the original dataset to speedup the autotune algorithm
585  sampledDataset_ = random_sample(dataset_, sampleSize);
586  // We use a cross-validation approach, first we sample a testset from the dataset
587  testDataset_ = random_sample(sampledDataset_, testSampleSize, true);
588 
589  // We compute the ground truth using linear search
590  Logger::info("Computing ground truth... \n");
591  gt_matches_ = Matrix<size_t>(new size_t[testDataset_.rows], testDataset_.rows, 1);
592  StartStopTimer t;
593  int repeats = 0;
594  t.reset();
595  while (t.value<0.2) {
596  repeats++;
597  t.start();
598  compute_ground_truth<Distance>(sampledDataset_, testDataset_, gt_matches_, 0, distance_);
599  t.stop();
600  }
601 
602  CostData linear_cost;
603  linear_cost.searchTimeCost = (float)t.value/repeats;
604  linear_cost.buildTimeCost = 0;
605  linear_cost.memoryCost = 0;
606  linear_cost.params["algorithm"] = FLANN_INDEX_LINEAR;
607 
608  costs.push_back(linear_cost);
609 
610  // Start parameter autotune process
611  Logger::info("Autotuning parameters...\n");
612 
613  optimizeKMeans(costs);
614  optimizeKDTree(costs);
615 
616  float bestTimeCost = costs[0].buildTimeCost * build_weight_ + costs[0].searchTimeCost;
617  for (size_t i = 0; i < costs.size(); ++i) {
618  float timeCost = costs[i].buildTimeCost * build_weight_ + costs[i].searchTimeCost;
619  Logger::debug("Time cost: %g\n", timeCost);
620  if (timeCost < bestTimeCost) {
621  bestTimeCost = timeCost;
622  }
623  }
624  Logger::debug("Best time cost: %g\n", bestTimeCost);
625 
626  IndexParams bestParams = costs[0].params;
627  if (bestTimeCost > 0) {
628  float bestCost = (costs[0].buildTimeCost * build_weight_ + costs[0].searchTimeCost) / bestTimeCost;
629  for (size_t i = 0; i < costs.size(); ++i) {
630  float crtCost = (costs[i].buildTimeCost * build_weight_ + costs[i].searchTimeCost) / bestTimeCost +
631  memory_weight_ * costs[i].memoryCost;
632  Logger::debug("Cost: %g\n", crtCost);
633  if (crtCost < bestCost) {
634  bestCost = crtCost;
635  bestParams = costs[i].params;
636  }
637  }
638  Logger::debug("Best cost: %g\n", bestCost);
639  }
640 
641  delete[] gt_matches_.ptr();
642  delete[] testDataset_.ptr();
643  delete[] sampledDataset_.ptr();
644 
645  return bestParams;
646  }
647 
648 
649 
655  float estimateSearchParams(SearchParams& searchParams)
656  {
657  const int nn = 1;
658  const size_t SAMPLE_COUNT = 1000;
659 
660  assert(bestIndex_ != NULL); // must have a valid index
661 
662  float speedup = 0;
663 
664  int samples = (int)std::min(dataset_.rows / 10, SAMPLE_COUNT);
665  if (samples > 0) {
666  Matrix<ElementType> testDataset = random_sample(dataset_, samples);
667 
668  Logger::info("Computing ground truth\n");
669 
670  // we need to compute the ground truth first
671  Matrix<size_t> gt_matches(new size_t[testDataset.rows], testDataset.rows, 1);
672  StartStopTimer t;
673  int repeats = 0;
674  t.reset();
675  while (t.value<0.2) {
676  repeats++;
677  t.start();
678  compute_ground_truth<Distance>(dataset_, testDataset, gt_matches, 1, distance_);
679  t.stop();
680  }
681  float linear = (float)t.value/repeats;
682 
683  int checks;
684  Logger::info("Estimating number of checks\n");
685 
686  float searchTime;
687  float cb_index;
688  if (bestIndex_->getType() == FLANN_INDEX_KMEANS) {
689  Logger::info("KMeans algorithm, estimating cluster border factor\n");
690  KMeansIndex<Distance>* kmeans = static_cast<KMeansIndex<Distance>*>(bestIndex_);
691  float bestSearchTime = -1;
692  float best_cb_index = -1;
693  int best_checks = -1;
694  for (cb_index = 0; cb_index < 1.1f; cb_index += 0.2f) {
695  kmeans->set_cb_index(cb_index);
696  searchTime = test_index_precision(*kmeans, dataset_, testDataset, gt_matches, target_precision_, checks, distance_, nn, 1);
697  if ((searchTime < bestSearchTime) || (bestSearchTime == -1)) {
698  bestSearchTime = searchTime;
699  best_cb_index = cb_index;
700  best_checks = checks;
701  }
702  }
703  searchTime = bestSearchTime;
704  cb_index = best_cb_index;
705  checks = best_checks;
706 
707  kmeans->set_cb_index(best_cb_index);
708  Logger::info("Optimum cb_index: %g\n", cb_index);
709  bestParams_["cb_index"] = cb_index;
710  }
711  else {
712  searchTime = test_index_precision(*bestIndex_, dataset_, testDataset, gt_matches, target_precision_, checks, distance_, nn, 1);
713  }
714 
715  Logger::info("Required number of checks: %d \n", checks);
716  searchParams.checks = checks;
717 
718  speedup = linear / searchTime;
719 
720  delete[] gt_matches.ptr();
721  delete[] testDataset.ptr();
722  }
723 
724  return speedup;
725  }
726 
727 
728  void swap(AutotunedIndex& other)
729  {
730  BaseClass::swap(other);
731  std::swap(bestIndex_, other.bestIndex_);
732  std::swap(bestParams_, other.bestParams_);
733  std::swap(bestSearchParams_, other.bestSearchParams_);
734  std::swap(speedup_, other.speedup_);
735  std::swap(dataset_, other.dataset_);
736  std::swap(target_precision_, other.target_precision_);
737  std::swap(build_weight_, other.build_weight_);
738  std::swap(memory_weight_, other.memory_weight_);
739  std::swap(sample_fraction_, other.sample_fraction_);
740  }
741 
742 private:
743  NNIndex<Distance>* bestIndex_;
744 
745  IndexParams bestParams_;
746  SearchParams bestSearchParams_;
747 
748  Matrix<ElementType> sampledDataset_;
749  Matrix<ElementType> testDataset_;
750  Matrix<size_t> gt_matches_;
751 
752  float speedup_;
753 
757  Matrix<ElementType> dataset_;
758 
762  float target_precision_;
763  float build_weight_;
764  float memory_weight_;
765  float sample_fraction_;
766 
768 };
769 }
770 
771 #endif /* FLANN_AUTOTUNED_INDEX_H_ */
int points
double Distance(const Point3D< Real > &p1, const Point3D< Real > &p2)
@ linear
Definition: Common.h:27
cmdLineReadable * params[]
#define NULL
core::Tensor result
Definition: VtkUtils.cpp:76
void loadIndex(FILE *stream)
void buildIndex(const Matrix< ElementType > &dataset)
Distance::ResultType DistanceType
FLANN_DEPRECATED float getSpeedup() const
void findNeighbors(ResultSet< DistanceType > &result, const ElementType *vec, const SearchParams &searchParams) const
int radiusSearch(const Matrix< ElementType > &queries, std::vector< std::vector< size_t > > &indices, std::vector< std::vector< DistanceType > > &dists, DistanceType radius, const SearchParams &params) const
AutotunedIndex(const Matrix< ElementType > &inputData, const IndexParams &params=AutotunedIndexParams(), Distance d=Distance())
IndexParams getParameters() const
NNIndex< Distance > BaseClass
void addPoints(const Matrix< ElementType > &points, float rebuild_threshold=2)
Incrementally add points to the index.
Distance::ElementType ElementType
BaseClass * clone() const
int knnSearch(const Matrix< ElementType > &queries, std::vector< std::vector< size_t > > &indices, std::vector< std::vector< DistanceType > > &dists, size_t knn, const SearchParams &params) const
AutotunedIndex & operator=(AutotunedIndex other)
void removePoint(size_t id)
void serialize(Archive &ar)
AutotunedIndex(const AutotunedIndex &other)
AutotunedIndex(const IndexParams &params=AutotunedIndexParams(), Distance d=Distance())
FLANN_DEPRECATED SearchParams getSearchParameters() const
void saveIndex(FILE *stream)
flann_algorithm_t getType() const
int radiusSearch(const Matrix< ElementType > &queries, Matrix< size_t > &indices, Matrix< DistanceType > &dists, DistanceType radius, const SearchParams &params) const
AutotunedIndex< Distance > IndexType
int knnSearch(const Matrix< ElementType > &queries, Matrix< size_t > &indices, Matrix< DistanceType > &dists, size_t knn, const SearchParams &params) const
Perform k-nearest neighbor search.
static int debug(const char *fmt,...)
Definition: logger.h:128
static int getLevel()
Definition: logger.h:91
static int info(const char *fmt,...)
Definition: logger.h:127
size_t cols
Definition: matrix.h:73
size_t rows
Definition: matrix.h:72
T * ptr() const
Definition: matrix.h:127
void swap(NNIndex &other)
Definition: nn_index.h:802
Distance distance_
Definition: nn_index.h:823
IndexParams index_params_
Definition: nn_index.h:851
int min(int a, int b)
Definition: cutil_math.h:53
@ FLANN_LOG_INFO
Definition: defines.h:109
#define FLANN_DEPRECATED
Definition: defines.h:60
#define FLANN_ARRAY_LEN(a)
Definition: defines.h:72
@ FLANN_CHECKS_AUTOTUNED
Definition: defines.h:148
flann_algorithm_t
Definition: defines.h:80
@ FLANN_INDEX_KMEANS
Definition: defines.h:83
@ FLANN_INDEX_AUTOTUNED
Definition: defines.h:92
@ FLANN_INDEX_LINEAR
Definition: defines.h:81
@ FLANN_INDEX_KDTREE
Definition: defines.h:82
@ FLANN_CENTERS_RANDOM
Definition: defines.h:97
T get_param(const IndexParams &params, std::string name, const T &default_value)
Definition: params.h:95
Matrix< T > random_sample(Matrix< T > &srcMatrix, size_t size, bool remove=false)
Definition: sampling.h:40
void print_params(const IndexParams &params)
Definition: params.h:118
float test_index_precision(Index &index, const Matrix< typename Distance::ElementType > &inputData, const Matrix< typename Distance::ElementType > &testData, const Matrix< size_t > &matches, float precision, int &checks, const Distance &distance, int nn=1, int skipMatches=0)
NNIndex< Distance > * create_index_by_type(const flann_algorithm_t index_type, const Matrix< typename Distance::ElementType > &dataset, const IndexParams &params, const Distance &distance)
Definition: all_indices.h:144
std::map< std::string, any > IndexParams
Definition: params.h:51
void swap(cloudViewer::core::SmallVectorImpl< T > &LHS, cloudViewer::core::SmallVectorImpl< T > &RHS)
Implement std::swap in terms of SmallVector swap.
Definition: SmallVector.h:1370
#define USING_BASECLASS_SYMBOLS
Definition: nn_index.h:887
AutotunedIndexParams(float target_precision=0.8, float build_weight=0.01, float memory_weight=0, float sample_fraction=0.1)