35 #ifndef RTABMAP_FLANN_LSH_INDEX_H_ 36 #define RTABMAP_FLANN_LSH_INDEX_H_ 59 LshIndexParams(
unsigned int table_number = 12,
unsigned int key_size = 20,
unsigned int multi_probe_level = 2)
63 (*this)[
"table_number"] = table_number;
65 (*this)[
"key_size"] = key_size;
67 (*this)[
"multi_probe_level"] = multi_probe_level;
77 template<
typename Distance>
93 table_number_ = get_param<unsigned int>(index_params_,
"table_number",12);
94 key_size_ = get_param<unsigned int>(index_params_,
"key_size",20);
95 multi_probe_level_ = get_param<unsigned int>(index_params_,
"multi_probe_level",2);
97 fill_xor_mask(0, key_size_, multi_probe_level_, xor_masks_);
109 table_number_ = get_param<unsigned int>(index_params_,
"table_number",12);
110 key_size_ = get_param<unsigned int>(index_params_,
"key_size",20);
111 multi_probe_level_ = get_param<unsigned int>(index_params_,
"multi_probe_level",2);
113 fill_xor_mask(0, key_size_, multi_probe_level_, xor_masks_);
115 setDataset(input_data);
119 tables_(other.tables_),
120 table_number_(other.table_number_),
121 key_size_(other.key_size_),
122 multi_probe_level_(other.multi_probe_level_),
123 xor_masks_(other.xor_masks_)
144 using BaseClass::buildIndex;
148 assert(points.
cols==veclen_);
149 size_t old_size = size_;
151 extendDataset(points);
153 if (rebuild_threshold>1 && size_at_build_*rebuild_threshold<size_) {
157 for (
unsigned int i = 0; i < table_number_; ++i) {
159 for (
size_t i=old_size;i<size_;++i) {
160 table.
add(i, points_[i]);
173 template<
typename Archive>
182 ar & multi_probe_level_;
187 if (Archive::is_loading::value) {
188 index_params_[
"algorithm"] = getType();
189 index_params_[
"table_number"] = table_number_;
190 index_params_[
"key_size"] = key_size_;
191 index_params_[
"multi_probe_level"] = multi_probe_level_;
213 return size_ *
sizeof(int);
230 assert(queries.
cols == veclen_);
231 assert(indices.
rows >= queries.
rows);
233 assert(indices.
cols >= knn);
234 assert(dists.
cols >= knn);
238 #pragma omp parallel num_threads(params.cores) 241 #pragma omp for schedule(static) reduction(+:count) 242 for (
int i = 0; i < (int)queries.
rows; i++) {
244 findNeighbors(resultSet, queries[i], params);
246 resultSet.
copy(indices[i], dists[i], n, params.
sorted);
247 indices_to_ids(indices[i], indices[i], n);
253 #pragma omp parallel num_threads(params.cores) 256 #pragma omp for schedule(static) reduction(+:count) 257 for (
int i = 0; i < (int)queries.
rows; i++) {
259 findNeighbors(resultSet, queries[i], params);
261 resultSet.
copy(indices[i], dists[i], n, params.
sorted);
262 indices_to_ids(indices[i], indices[i], n);
280 std::vector< std::vector<size_t> >& indices,
281 std::vector<std::vector<DistanceType> >& dists,
285 assert(queries.
cols == veclen_);
286 if (indices.size() < queries.
rows ) indices.resize(queries.
rows);
287 if (dists.size() < queries.
rows ) dists.resize(queries.
rows);
291 #pragma omp parallel num_threads(params.cores) 294 #pragma omp for schedule(static) reduction(+:count) 295 for (
int i = 0; i < (int)queries.
rows; i++) {
297 findNeighbors(resultSet, queries[i], params);
299 indices[i].resize(n);
302 resultSet.
copy(&indices[i][0], &dists[i][0], n, params.
sorted);
303 indices_to_ids(&indices[i][0], &indices[i][0], n);
310 #pragma omp parallel num_threads(params.cores) 313 #pragma omp for schedule(static) reduction(+:count) 314 for (
int i = 0; i < (int)queries.
rows; i++) {
316 findNeighbors(resultSet, queries[i], params);
318 indices[i].resize(n);
321 resultSet.
copy(&indices[i][0], &dists[i][0], n, params.
sorted);
322 indices_to_ids(&indices[i][0], &indices[i][0], n);
343 getNeighbors(vec, result);
353 tables_.resize(table_number_);
354 std::vector<std::pair<size_t,ElementType*> > features;
355 features.reserve(points_.size());
356 for (
size_t i=0;i<points_.size();++i) {
357 features.push_back(std::make_pair(i, points_[i]));
359 for (
unsigned int i = 0; i < table_number_; ++i) {
380 bool operator()(
const ScoreIndexPair& left,
const ScoreIndexPair& right)
const 382 return left.second < right.second;
393 std::vector<lsh::BucketKey>& xor_masks)
395 xor_masks.push_back(key);
396 if (level == 0)
return;
397 for (
int index = lowest_index - 1; index >= 0; --index) {
400 fill_xor_mask(new_key, index, level - 1, xor_masks);
412 void getNeighbors(
const ElementType* vec,
bool do_radius,
float radius,
bool do_k,
unsigned int k_nn,
413 float& checked_average)
415 static std::vector<ScoreIndexPair> score_index_heap;
419 typename std::vector<lsh::LshTable<ElementType> >::const_iterator table = tables_.begin();
420 typename std::vector<lsh::LshTable<ElementType> >::const_iterator table_end = tables_.end();
421 for (; table != table_end; ++table) {
422 size_t key = table->getKey(vec);
423 std::vector<lsh::BucketKey>::const_iterator xor_mask = xor_masks_.begin();
424 std::vector<lsh::BucketKey>::const_iterator xor_mask_end = xor_masks_.end();
425 for (; xor_mask != xor_mask_end; ++xor_mask) {
426 size_t sub_key = key ^ (*xor_mask);
427 const lsh::Bucket* bucket = table->getBucketFromKey(sub_key);
428 if (bucket == 0)
continue;
431 std::vector<lsh::FeatureIndex>::const_iterator training_index = bucket->begin();
432 std::vector<lsh::FeatureIndex>::const_iterator last_training_index = bucket->end();
433 DistanceType hamming_distance;
436 for (; training_index < last_training_index; ++training_index) {
437 if (removed_ && removed_points_.test(*training_index))
continue;
438 hamming_distance = distance_(vec, points_[*training_index].point, veclen_);
440 if (hamming_distance < worst_score) {
442 score_index_heap.push_back(ScoreIndexPair(hamming_distance, training_index));
443 std::push_heap(score_index_heap.begin(), score_index_heap.end());
445 if (score_index_heap.size() > (
unsigned int)k_nn) {
447 std::pop_heap(score_index_heap.begin(), score_index_heap.end());
448 score_index_heap.pop_back();
450 worst_score = score_index_heap.front().first;
458 typename std::vector<lsh::LshTable<ElementType> >::const_iterator table = tables_.begin();
459 typename std::vector<lsh::LshTable<ElementType> >::const_iterator table_end = tables_.end();
460 for (; table != table_end; ++table) {
461 size_t key = table->getKey(vec);
462 std::vector<lsh::BucketKey>::const_iterator xor_mask = xor_masks_.begin();
463 std::vector<lsh::BucketKey>::const_iterator xor_mask_end = xor_masks_.end();
464 for (; xor_mask != xor_mask_end; ++xor_mask) {
465 size_t sub_key = key ^ (*xor_mask);
466 const lsh::Bucket* bucket = table->getBucketFromKey(sub_key);
467 if (bucket == 0)
continue;
470 std::vector<lsh::FeatureIndex>::const_iterator training_index = bucket->begin();
471 std::vector<lsh::FeatureIndex>::const_iterator last_training_index = bucket->end();
472 DistanceType hamming_distance;
475 for (; training_index < last_training_index; ++training_index) {
476 if (removed_ && removed_points_.test(*training_index))
continue;
478 hamming_distance = distance_(vec, points_[*training_index].point, veclen_);
479 if (hamming_distance < radius) score_index_heap.push_back(ScoreIndexPair(hamming_distance, training_index));
492 typename std::vector<lsh::LshTable<ElementType> >::const_iterator table = tables_.begin();
493 typename std::vector<lsh::LshTable<ElementType> >::const_iterator table_end = tables_.end();
494 for (; table != table_end; ++table) {
495 size_t key = table->getKey(vec);
496 std::vector<lsh::BucketKey>::const_iterator xor_mask = xor_masks_.begin();
497 std::vector<lsh::BucketKey>::const_iterator xor_mask_end = xor_masks_.end();
498 for (; xor_mask != xor_mask_end; ++xor_mask) {
499 size_t sub_key = key ^ (*xor_mask);
500 const lsh::Bucket* bucket = table->getBucketFromKey(sub_key);
501 if (bucket == 0)
continue;
504 std::vector<lsh::FeatureIndex>::const_iterator training_index = bucket->begin();
505 std::vector<lsh::FeatureIndex>::const_iterator last_training_index = bucket->end();
506 DistanceType hamming_distance;
509 for (; training_index < last_training_index; ++training_index) {
510 if (removed_ && removed_points_.test(*training_index))
continue;
512 hamming_distance = distance_(vec, points_[*training_index], veclen_);
513 result.
addPoint(hamming_distance, *training_index);
522 BaseClass::swap(other);
523 std::swap(tables_, other.
tables_);
532 std::vector<lsh::LshTable<ElementType> >
tables_;
548 #endif //FLANN_LSH_INDEX_H_
std::map< std::string, any > IndexParams
void copy(size_t *indices, DistanceType *dist, int n_neighbors, bool sorted=true)
void saveIndex(FILE *stream)
unsigned int multi_probe_level_
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.
std::vector< lsh::BucketKey > xor_masks_
flann_algorithm_t getType() const
GLM_FUNC_DECL genType min(genType const &x, genType const &y)
void serialize(Archive &ar)
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.
LshIndex(const IndexParams ¶ms=LshIndexParams(), Distance d=Distance())
void add(unsigned int value, const ElementType *feature)
unsigned int table_number_
LshIndex & operator=(LshIndex other)
bool operator()(const ScoreIndexPair &left, const ScoreIndexPair &right) const
Distance::ResultType DistanceType
#define USING_BASECLASS_SYMBOLS
void findNeighbors(ResultSet< DistanceType > &result, const ElementType *vec, const SearchParams &) const
void addPoints(const Matrix< ElementType > &points, float rebuild_threshold=2)
Incrementally add points to the index.
Distance::ElementType ElementType
std::pair< float, unsigned int > ScoreIndexPair
void getNeighbors(const ElementType *vec, ResultSet< DistanceType > &result) const
LshIndexParams(unsigned int table_number=12, unsigned int key_size=20, unsigned int multi_probe_level=2)
void getNeighbors(const ElementType *vec, bool do_radius, float radius, bool do_k, unsigned int k_nn, float &checked_average)
std::vector< lsh::LshTable< ElementType > > tables_
void copy(size_t *indices, DistanceType *dists, size_t num_elements, bool sorted=true)
GLM_FUNC_DECL genType max(genType const &x, genType const &y)
BaseClass * clone() const
static void freeIndex(sqlite3 *db, Index *p)
void swap(LshIndex &other)
std::vector< FeatureIndex > Bucket
void fill_xor_mask(lsh::BucketKey key, int lowest_index, unsigned int level, std::vector< lsh::BucketKey > &xor_masks)
virtual void addPoint(DistanceType dist, size_t index)=0
NNIndex< Distance > BaseClass
void loadIndex(FILE *stream)
LshIndex(const LshIndex &other)
LshIndex(const Matrix< ElementType > &input_data, const IndexParams ¶ms=LshIndexParams(), Distance d=Distance())