30 #ifndef RTABMAP_FLANN_AUTOTUNED_INDEX_H_ 31 #define RTABMAP_FLANN_AUTOTUNED_INDEX_H_ 49 template<
typename Distance>
50 inline NNIndex<Distance>*
57 AutotunedIndexParams(
float target_precision = 0.8,
float build_weight = 0.01,
float memory_weight = 0,
float sample_fraction = 0.1)
61 (*this)[
"target_precision"] = target_precision;
63 (*this)[
"build_weight"] = build_weight;
65 (*this)[
"memory_weight"] = memory_weight;
67 (*this)[
"sample_fraction"] = sample_fraction;
72 template <
typename Distance>
86 BaseClass(params,
d), bestIndex_(
NULL), speedup_(0), dataset_(inputData)
88 target_precision_ =
get_param(params,
"target_precision",0.8
f);
89 build_weight_ =
get_param(params,
"build_weight", 0.01
f);
90 memory_weight_ =
get_param(params,
"memory_weight", 0.0
f);
91 sample_fraction_ =
get_param(params,
"sample_fraction", 0.1
f);
95 BaseClass(params,
d), bestIndex_(
NULL), speedup_(0)
97 target_precision_ =
get_param(params,
"target_precision",0.8
f);
98 build_weight_ =
get_param(params,
"build_weight", 0.01
f);
99 memory_weight_ =
get_param(params,
"memory_weight", 0.0
f);
100 sample_fraction_ =
get_param(params,
"sample_fraction", 0.1
f);
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_)
137 bestParams_ = estimateBuildParams();
138 Logger::info(
"----------------------------------------------------\n");
139 Logger::info(
"Autotuned parameters:\n");
142 Logger::info(
"----------------------------------------------------\n");
144 flann_algorithm_t index_type = get_param<flann_algorithm_t>(bestParams_,
"algorithm");
146 bestIndex_->buildIndex();
147 speedup_ = estimateSearchParams(bestSearchParams_);
148 Logger::info(
"----------------------------------------------------\n");
149 Logger::info(
"Search parameters:\n");
152 Logger::info(
"----------------------------------------------------\n");
153 bestParams_[
"search_params"] = bestSearchParams_;
154 bestParams_[
"speedup"] = speedup_;
167 bestIndex_->addPoints(points, rebuild_threshold);
174 bestIndex_->removePoint(
id);
179 template<
typename Archive>
186 ar & target_precision_;
189 ar & sample_fraction_;
192 if (Archive::is_saving::value) {
193 index_type = get_param<flann_algorithm_t>(bestParams_,
"algorithm");
196 ar & bestSearchParams_.checks;
198 if (Archive::is_loading::value) {
199 bestParams_[
"algorithm"] = index_type;
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_;
216 bestIndex_->saveIndex(stream);
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);
239 return bestIndex_->knnSearch(queries, indices, dists, knn, bestSearchParams_);
242 return bestIndex_->knnSearch(queries, indices, dists, knn, params);
247 std::vector< std::vector<size_t> >& indices,
248 std::vector<std::vector<DistanceType> >& dists,
253 return bestIndex_->knnSearch(queries, indices, dists, knn, bestSearchParams_);
256 return bestIndex_->knnSearch(queries, indices, dists, knn, params);
268 return bestIndex_->radiusSearch(queries, indices, dists, radius, bestSearchParams_);
271 return bestIndex_->radiusSearch(queries, indices, dists, radius, params);
276 std::vector< std::vector<size_t> >& indices,
277 std::vector<std::vector<DistanceType> >& dists,
282 return bestIndex_->radiusSearch(queries, indices, dists, radius, bestSearchParams_);
285 return bestIndex_->radiusSearch(queries, indices, dists, radius, params);
307 return bestSearchParams_;
321 return bestIndex_->size();
329 return bestIndex_->veclen();
337 return bestIndex_->usedMemory();
376 Logger::info(
"KMeansTree using params: max_iterations=%d, branching=%d\n",
377 get_param<int>(cost.
params,
"iterations"),
378 get_param<int>(cost.
params,
"branching"));
384 float buildTime = (float)t.
value;
387 float searchTime =
test_index_precision(kmeans, sampledDataset_, testDataset_, gt_matches_, target_precision_, checks, distance_, nn);
389 float datasetMemory = float(sampledDataset_.rows * sampledDataset_.cols *
sizeof(
float));
393 Logger::info(
"KMeansTree buildTime=%g, searchTime=%g, build_weight=%g\n", buildTime, searchTime, build_weight_);
403 Logger::info(
"KDTree using params: trees=%d\n", get_param<int>(cost.
params,
"trees"));
409 float buildTime = (float)t.
value;
412 float searchTime =
test_index_precision(kdtree, sampledDataset_, testDataset_, gt_matches_, target_precision_, checks, distance_, nn);
414 float datasetMemory = float(sampledDataset_.rows * sampledDataset_.cols *
sizeof(
float));
418 Logger::info(
"KDTree buildTime=%g, searchTime=%g\n", buildTime, searchTime);
472 Logger::info(
"KMEANS, Step 1: Exploring parameter space\n");
475 int maxIterations[] = { 1, 5, 10, 15 };
476 int branchingFactors[] = { 16, 32, 64, 128, 256 };
479 costs.reserve(costs.size() + kmeansParamSpaceSize);
487 cost.
params[
"iterations"] = maxIterations[i];
488 cost.
params[
"branching"] = branchingFactors[j];
490 evaluate_kmeans(cost);
491 costs.push_back(cost);
520 Logger::info(
"KD-TREE, Step 1: Exploring parameter space\n");
523 int testTrees[] = { 1, 4, 8, 16, 32 };
529 cost.
params[
"trees"] = testTrees[i];
531 evaluate_kdtree(cost);
532 costs.push_back(cost);
562 std::vector<CostData> costs;
564 int sampleSize = int(sample_fraction_ * dataset_.rows);
565 int testSampleSize =
std::min(sampleSize / 10, 1000);
567 Logger::info(
"Entering autotuning, dataset size: %d, sampleSize: %d, testSampleSize: %d, target precision: %g\n", dataset_.rows, sampleSize, testSampleSize, target_precision_);
571 if (testSampleSize < 10) {
572 Logger::info(
"Choosing linear, dataset too small\n");
579 testDataset_ =
random_sample(sampledDataset_, testSampleSize,
true);
582 Logger::info(
"Computing ground truth... \n");
583 gt_matches_ =
Matrix<size_t>(
new size_t[testDataset_.rows], testDataset_.rows, 1);
587 while (t.value<0.2) {
590 compute_ground_truth<Distance>(sampledDataset_, testDataset_, gt_matches_, 0, distance_);
600 costs.push_back(linear_cost);
603 Logger::info(
"Autotuning parameters...\n");
605 optimizeKMeans(costs);
606 optimizeKDTree(costs);
608 float bestTimeCost = costs[0].buildTimeCost * build_weight_ + costs[0].searchTimeCost;
609 for (
size_t i = 0; i < costs.size(); ++i) {
610 float timeCost = costs[i].buildTimeCost * build_weight_ + costs[i].searchTimeCost;
611 Logger::debug(
"Time cost: %g\n", timeCost);
612 if (timeCost < bestTimeCost) {
613 bestTimeCost = timeCost;
616 Logger::debug(
"Best time cost: %g\n", bestTimeCost);
619 if (bestTimeCost > 0) {
620 float bestCost = (costs[0].buildTimeCost * build_weight_ + costs[0].searchTimeCost) / bestTimeCost;
621 for (
size_t i = 0; i < costs.size(); ++i) {
622 float crtCost = (costs[i].buildTimeCost * build_weight_ + costs[i].searchTimeCost) / bestTimeCost +
623 memory_weight_ * costs[i].memoryCost;
624 Logger::debug(
"Cost: %g\n", crtCost);
625 if (crtCost < bestCost) {
627 bestParams = costs[i].params;
630 Logger::debug(
"Best cost: %g\n", bestCost);
633 delete[] gt_matches_.ptr();
634 delete[] testDataset_.ptr();
635 delete[] sampledDataset_.ptr();
650 const size_t SAMPLE_COUNT = 1000;
652 assert(bestIndex_ !=
NULL);
656 int samples = (int)
std::min(dataset_.rows / 10, SAMPLE_COUNT);
660 Logger::info(
"Computing ground truth\n");
667 while (t.
value<0.2) {
670 compute_ground_truth<Distance>(dataset_, testDataset, gt_matches, 1, distance_);
673 float linear = (float)t.
value/repeats;
676 Logger::info(
"Estimating number of checks\n");
681 Logger::info(
"KMeans algorithm, estimating cluster border factor\n");
683 float bestSearchTime = -1;
684 float best_cb_index = -1;
685 int best_checks = -1;
686 for (cb_index = 0; cb_index < 1.1f; cb_index += 0.2f) {
688 searchTime =
test_index_precision(*kmeans, dataset_, testDataset, gt_matches, target_precision_, checks, distance_, nn, 1);
689 if ((searchTime < bestSearchTime) || (bestSearchTime == -1)) {
690 bestSearchTime = searchTime;
691 best_cb_index = cb_index;
692 best_checks = checks;
695 searchTime = bestSearchTime;
696 cb_index = best_cb_index;
697 checks = best_checks;
700 Logger::info(
"Optimum cb_index: %g\n", cb_index);
701 bestParams_[
"cb_index"] = cb_index;
704 searchTime =
test_index_precision(*bestIndex_, dataset_, testDataset, gt_matches, target_precision_, checks, distance_, nn, 1);
707 Logger::info(
"Required number of checks: %d \n", checks);
708 searchParams.
checks = checks;
710 speedup = linear / searchTime;
712 delete[] gt_matches.
ptr();
713 delete[] testDataset.
ptr();
722 BaseClass::swap(other);
std::map< std::string, any > IndexParams
int radiusSearch(const Matrix< ElementType > &queries, std::vector< std::vector< size_t > > &indices, std::vector< std::vector< DistanceType > > &dists, DistanceType radius, const SearchParams ¶ms) const
T get_param(const IndexParams ¶ms, std::string name, const T &default_value)
void serialize(Archive &ar)
GLM_FUNC_DECL genType min(genType const &x, genType const &y)
void evaluate_kdtree(CostData &cost)
virtual ~AutotunedIndex()
SearchParams bestSearchParams_
void saveIndex(FILE *stream)
int radiusSearch(const Matrix< ElementType > &queries, Matrix< size_t > &indices, Matrix< DistanceType > &dists, DistanceType radius, const SearchParams ¶ms) const
GLM_FUNC_DECL genType::value_type distance(genType const &p0, genType const &p1)
void swap(linb::any &lhs, linb::any &rhs) noexcept
#define FLANN_ARRAY_LEN(a)
void loadIndex(FILE *stream)
int knnSearch(const Matrix< ElementType > &queries, Matrix< size_t > &indices, Matrix< DistanceType > &dists, size_t knn, const SearchParams ¶ms) const
Perform k-nearest neighbor search.
Matrix< ElementType > dataset_
#define USING_BASECLASS_SYMBOLS
AutotunedIndex & operator=(AutotunedIndex other)
float estimateSearchParams(SearchParams &searchParams)
Matrix< size_t > gt_matches_
void optimizeKMeans(std::vector< CostData > &costs)
virtual void buildIndex()
void evaluate_kmeans(CostData &cost)
void findNeighbors(ResultSet< DistanceType > &result, const ElementType *vec, const SearchParams &searchParams) const
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 ¶ms, const Distance &distance)
FLANN_DEPRECATED SearchParams getSearchParameters() const
AutotunedIndex(const Matrix< ElementType > &inputData, const IndexParams ¶ms=AutotunedIndexParams(), Distance d=Distance())
void removePoint(size_t id)
IndexParams getParameters() const
Distance::ElementType ElementType
bool needs_kdtree_distance
void addPoints(const Matrix< ElementType > &points, float rebuild_threshold=2)
Incrementally add points to the index.
void buildIndex(const Matrix< ElementType > &dataset)
Matrix< ElementType > testDataset_
Matrix< T > random_sample(Matrix< T > &srcMatrix, size_t size, bool remove=false)
void print_params(const IndexParams ¶ms)
void optimizeKDTree(std::vector< CostData > &costs)
Matrix< ElementType > sampledDataset_
BaseClass * clone() const
NNIndex< Distance > * bestIndex_
AutotunedIndexParams(float target_precision=0.8, float build_weight=0.01, float memory_weight=0, float sample_fraction=0.1)
Distance::ResultType DistanceType
NNIndex< Distance > BaseClass
void set_cb_index(float index)
AutotunedIndex(const AutotunedIndex &other)
int knnSearch(const Matrix< ElementType > &queries, std::vector< std::vector< size_t > > &indices, std::vector< std::vector< DistanceType > > &dists, size_t knn, const SearchParams ¶ms) const
Perform k-nearest neighbor search.
FLANN_DEPRECATED float getSpeedup() const
AutotunedIndex< Distance > IndexType
void swap(AutotunedIndex &other)
AutotunedIndex(const IndexParams ¶ms=AutotunedIndexParams(), Distance d=Distance())
IndexParams estimateBuildParams()
flann_algorithm_t getType() const