nn_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 
31 #ifndef RTABMAP_FLANN_NNINDEX_H
32 #define RTABMAP_FLANN_NNINDEX_H
33 
34 #include <vector>
35 
36 #include "rtflann/general.h"
37 #include "rtflann/util/matrix.h"
38 #include "rtflann/util/params.h"
41 #include "rtflann/util/saving.h"
42 
43 namespace rtflann
44 {
45 
46 #define KNN_HEAP_THRESHOLD 250
47 
48 
49 class IndexBase
50 {
51 public:
52  virtual ~IndexBase() {};
53 
54  virtual size_t veclen() const = 0;
55 
56  virtual size_t size() const = 0;
57 
58  virtual flann_algorithm_t getType() const = 0;
59 
60  virtual int usedMemory() const = 0;
61 
62  virtual IndexParams getParameters() const = 0;
63 
64  virtual void loadIndex(FILE* stream) = 0;
65 
66  virtual void saveIndex(FILE* stream) = 0;
67 };
68 
72 template <typename Distance>
73 class NNIndex : public IndexBase
74 {
75 public:
76  typedef typename Distance::ElementType ElementType;
77  typedef typename Distance::ResultType DistanceType;
78 
79  NNIndex(Distance d) : distance_(d), last_id_(0), size_(0), size_at_build_(0), veclen_(0),
80  removed_(false), removed_count_(0), data_ptr_(NULL)
81  {
82  }
83 
84  NNIndex(const IndexParams& params, Distance d) : distance_(d), last_id_(0), size_(0), size_at_build_(0), veclen_(0),
85  index_params_(params), removed_(false), removed_count_(0), data_ptr_(NULL)
86  {
87  }
88 
89  NNIndex(const NNIndex& other) :
90  distance_(other.distance_),
91  last_id_(other.last_id_),
92  size_(other.size_),
93  size_at_build_(other.size_at_build_),
94  veclen_(other.veclen_),
95  index_params_(other.index_params_),
96  removed_(other.removed_),
97  removed_points_(other.removed_points_),
98  removed_count_(other.removed_count_),
99  ids_(other.ids_),
100  points_(other.points_),
101  data_ptr_(NULL)
102  {
103  if (other.data_ptr_) {
104  data_ptr_ = new ElementType[size_*veclen_];
105  std::copy(other.data_ptr_, other.data_ptr_+size_*veclen_, data_ptr_);
106  for (size_t i=0;i<size_;++i) {
107  points_[i] = data_ptr_ + i*veclen_;
108  }
109  }
110  }
111 
112  virtual ~NNIndex()
113  {
114  if (data_ptr_) {
115  delete[] data_ptr_;
116  }
117  }
118 
119 
120  virtual NNIndex* clone() const = 0;
121 
125  virtual void buildIndex()
126  {
127  freeIndex();
128  cleanRemovedPoints();
129 
130  // building index
131  buildIndexImpl();
132 
133  size_at_build_ = size_;
134 
135  }
136 
141  virtual void buildIndex(const Matrix<ElementType>& dataset)
142  {
143  setDataset(dataset);
144  this->buildIndex();
145  }
146 
152  virtual void addPoints(const Matrix<ElementType>& points, float rebuild_threshold = 2)
153  {
154  throw FLANNException("Functionality not supported by this index");
155  }
156 
161  virtual void removePoint(size_t id)
162  {
163  if (!removed_) {
164  ids_.resize(size_);
165  for (size_t i=0;i<size_;++i) {
166  ids_[i] = i;
167  }
168  removed_points_.resize(size_);
169  removed_points_.reset();
170  last_id_ = size_;
171  removed_ = true;
172  }
173 
174  size_t point_index = id_to_index(id);
175  if (point_index!=size_t(-1) && !removed_points_.test(point_index)) {
176  removed_points_.set(point_index);
177  removed_count_++;
178  }
179  }
180 
181 
187  virtual ElementType* getPoint(size_t id)
188  {
189  size_t index = id_to_index(id);
190  if (index!=size_t(-1)) {
191  return points_[index];
192  }
193  else {
194  return NULL;
195  }
196  }
197 
201  inline size_t size() const
202  {
203  return size_ - removed_count_;
204  }
205 
206  inline size_t removedCount() const
207  {
208  return removed_count_;
209  }
210 
211  inline size_t sizeAtBuild() const
212  {
213  return size_at_build_;
214  }
215 
219  inline size_t veclen() const
220  {
221  return veclen_;
222  }
223 
230  {
231  return index_params_;
232  }
233 
234 
235  template<typename Archive>
236  void serialize(Archive& ar)
237  {
239 
240  if (Archive::is_saving::value) {
242  header.h.index_type = getType();
243  header.h.rows = size_;
244  header.h.cols = veclen_;
245  }
246  ar & header;
247 
248  // sanity checks
249  if (Archive::is_loading::value) {
250  if (strncmp(header.h.signature,
252  strlen(FLANN_SIGNATURE_) - strlen("v0.0")) != 0) {
253  throw FLANNException("Invalid index file, wrong signature");
254  }
255 
256  if (header.h.data_type != flann_datatype_value<ElementType>::value) {
257  throw FLANNException("Datatype of saved index is different than of the one to be created.");
258  }
259 
260  if (header.h.index_type != getType()) {
261  throw FLANNException("Saved index type is different then the current index type.");
262  }
263  // TODO: check for distance type
264 
265  }
266 
267  ar & size_;
268  ar & veclen_;
269  ar & size_at_build_;
270 
271  bool save_dataset;
272  if (Archive::is_saving::value) {
273  save_dataset = get_param(index_params_,"save_dataset", false);
274  }
275  ar & save_dataset;
276 
277  if (save_dataset) {
278  if (Archive::is_loading::value) {
279  if (data_ptr_) {
280  delete[] data_ptr_;
281  }
282  data_ptr_ = new ElementType[size_*veclen_];
283  points_.resize(size_);
284  for (size_t i=0;i<size_;++i) {
285  points_[i] = data_ptr_ + i*veclen_;
286  }
287  }
288  for (size_t i=0;i<size_;++i) {
289  ar & serialization::make_binary_object (points_[i], veclen_*sizeof(ElementType));
290  }
291  } else {
292  if (points_.size()!=size_) {
293  throw FLANNException("Saved index does not contain the dataset and no dataset was provided.");
294  }
295  }
296 
297  ar & last_id_;
298  ar & ids_;
299  ar & removed_;
300  if (removed_) {
301  ar & removed_points_;
302  }
303  ar & removed_count_;
304  }
305 
306 
315  virtual int knnSearch(const Matrix<ElementType>& queries,
316  Matrix<size_t>& indices,
317  Matrix<DistanceType>& dists,
318  size_t knn,
319  const SearchParams& params) const
320  {
321  assert(queries.cols == veclen());
322  assert(indices.rows >= queries.rows);
323  assert(dists.rows >= queries.rows);
324  assert(indices.cols >= knn);
325  assert(dists.cols >= knn);
326  bool use_heap;
327 
328  if (params.use_heap==FLANN_Undefined) {
329  use_heap = (knn>KNN_HEAP_THRESHOLD)?true:false;
330  }
331  else {
332  use_heap = (params.use_heap==FLANN_True)?true:false;
333  }
334  int count = 0;
335 
336  if (use_heap) {
337 #pragma omp parallel num_threads(params.cores)
338  {
339  KNNResultSet2<DistanceType> resultSet(knn);
340 #pragma omp for schedule(static) reduction(+:count)
341  for (int i = 0; i < (int)queries.rows; i++) {
342  resultSet.clear();
343  findNeighbors(resultSet, queries[i], params);
344  size_t n = std::min(resultSet.size(), knn);
345  resultSet.copy(indices[i], dists[i], n, params.sorted);
346  indices_to_ids(indices[i], indices[i], n);
347  count += n;
348  }
349  }
350  }
351  else {
352 #pragma omp parallel num_threads(params.cores)
353  {
354  KNNSimpleResultSet<DistanceType> resultSet(knn);
355 #pragma omp for schedule(static) reduction(+:count)
356  for (int i = 0; i < (int)queries.rows; i++) {
357  resultSet.clear();
358  findNeighbors(resultSet, queries[i], params);
359  size_t n = std::min(resultSet.size(), knn);
360  resultSet.copy(indices[i], dists[i], n, params.sorted);
361  indices_to_ids(indices[i], indices[i], n);
362  count += n;
363  }
364  }
365  }
366  return count;
367  }
368 
378  /*int knnSearch(const Matrix<ElementType>& queries,
379  Matrix<int>& indices,
380  Matrix<DistanceType>& dists,
381  size_t knn,
382  const SearchParams& params) const
383  {
384  rtflann::Matrix<size_t> indices_(new size_t[indices.rows*indices.cols], indices.rows, indices.cols);
385  int result = knnSearch(queries, indices_, dists, knn, params);
386 
387  for (size_t i=0;i<indices.rows;++i) {
388  for (size_t j=0;j<indices.cols;++j) {
389  indices[i][j] = indices_[i][j];
390  }
391  }
392  delete[] indices_.ptr();
393  return result;
394  }*/
395 
396 
405  virtual int knnSearch(const Matrix<ElementType>& queries,
406  std::vector< std::vector<size_t> >& indices,
407  std::vector<std::vector<DistanceType> >& dists,
408  size_t knn,
409  const SearchParams& params) const
410  {
411  assert(queries.cols == veclen());
412  bool use_heap;
413  if (params.use_heap==FLANN_Undefined) {
414  use_heap = (knn>KNN_HEAP_THRESHOLD)?true:false;
415  }
416  else {
417  use_heap = (params.use_heap==FLANN_True)?true:false;
418  }
419 
420  if (indices.size() < queries.rows ) indices.resize(queries.rows);
421  if (dists.size() < queries.rows ) dists.resize(queries.rows);
422 
423  int count = 0;
424  if (use_heap) {
425 #pragma omp parallel num_threads(params.cores)
426  {
427  KNNResultSet2<DistanceType> resultSet(knn);
428 #pragma omp for schedule(static) reduction(+:count)
429  for (int i = 0; i < (int)queries.rows; i++) {
430  resultSet.clear();
431  findNeighbors(resultSet, queries[i], params);
432  size_t n = std::min(resultSet.size(), knn);
433  indices[i].resize(n);
434  dists[i].resize(n);
435  if (n>0) {
436  resultSet.copy(&indices[i][0], &dists[i][0], n, params.sorted);
437  indices_to_ids(&indices[i][0], &indices[i][0], n);
438  }
439  count += n;
440  }
441  }
442  }
443  else {
444 #pragma omp parallel num_threads(params.cores)
445  {
446  KNNSimpleResultSet<DistanceType> resultSet(knn);
447 #pragma omp for schedule(static) reduction(+:count)
448  for (int i = 0; i < (int)queries.rows; i++) {
449  resultSet.clear();
450  findNeighbors(resultSet, queries[i], params);
451  size_t n = std::min(resultSet.size(), knn);
452  indices[i].resize(n);
453  dists[i].resize(n);
454  if (n>0) {
455  resultSet.copy(&indices[i][0], &dists[i][0], n, params.sorted);
456  indices_to_ids(&indices[i][0], &indices[i][0], n);
457  }
458  count += n;
459  }
460  }
461  }
462 
463  return count;
464  }
465 
466 
476  int knnSearch(const Matrix<ElementType>& queries,
477  std::vector< std::vector<int> >& indices,
478  std::vector<std::vector<DistanceType> >& dists,
479  size_t knn,
480  const SearchParams& params) const
481  {
482  std::vector<std::vector<size_t> > indices_;
483  int result = knnSearch(queries, indices_, dists, knn, params);
484 
485  indices.resize(indices_.size());
486  for (size_t i=0;i<indices_.size();++i) {
487  indices[i].assign(indices_[i].begin(), indices_[i].end());
488  }
489  return result;
490  }
491 
501  virtual int radiusSearch(const Matrix<ElementType>& queries,
502  Matrix<size_t>& indices,
503  Matrix<DistanceType>& dists,
504  float radius,
505  const SearchParams& params) const
506  {
507  assert(queries.cols == veclen());
508  int count = 0;
509  size_t num_neighbors = std::min(indices.cols, dists.cols);
510  int max_neighbors = params.max_neighbors;
511  if (max_neighbors<0) max_neighbors = num_neighbors;
512  else max_neighbors = std::min(max_neighbors,(int)num_neighbors);
513 
514  if (max_neighbors==0) {
515 #pragma omp parallel num_threads(params.cores)
516  {
517  CountRadiusResultSet<DistanceType> resultSet(radius);
518 #pragma omp for schedule(static) reduction(+:count)
519  for (int i = 0; i < (int)queries.rows; i++) {
520  resultSet.clear();
521  findNeighbors(resultSet, queries[i], params);
522  count += resultSet.size();
523  }
524  }
525  }
526  else {
527  // explicitly indicated to use unbounded radius result set
528  // and we know there'll be enough room for resulting indices and dists
529  if (params.max_neighbors<0 && (num_neighbors>=size())) {
530 #pragma omp parallel num_threads(params.cores)
531  {
532  RadiusResultSet<DistanceType> resultSet(radius);
533 #pragma omp for schedule(static) reduction(+:count)
534  for (int i = 0; i < (int)queries.rows; i++) {
535  resultSet.clear();
536  findNeighbors(resultSet, queries[i], params);
537  size_t n = resultSet.size();
538  count += n;
539  if (n>num_neighbors) n = num_neighbors;
540  resultSet.copy(indices[i], dists[i], n, params.sorted);
541 
542  // mark the next element in the output buffers as unused
543  if (n<indices.cols) indices[i][n] = size_t(-1);
544  if (n<dists.cols) dists[i][n] = std::numeric_limits<DistanceType>::infinity();
545  indices_to_ids(indices[i], indices[i], n);
546  }
547  }
548  }
549  else {
550  // number of neighbors limited to max_neighbors
551 #pragma omp parallel num_threads(params.cores)
552  {
553  KNNRadiusResultSet<DistanceType> resultSet(radius, max_neighbors);
554 #pragma omp for schedule(static) reduction(+:count)
555  for (int i = 0; i < (int)queries.rows; i++) {
556  resultSet.clear();
557  findNeighbors(resultSet, queries[i], params);
558  size_t n = resultSet.size();
559  count += n;
560  if ((int)n>max_neighbors) n = max_neighbors;
561  resultSet.copy(indices[i], dists[i], n, params.sorted);
562 
563  // mark the next element in the output buffers as unused
564  if (n<indices.cols) indices[i][n] = size_t(-1);
565  if (n<dists.cols) dists[i][n] = std::numeric_limits<DistanceType>::infinity();
566  indices_to_ids(indices[i], indices[i], n);
567  }
568  }
569  }
570  }
571  return count;
572  }
573 
574 
584  int radiusSearch(const Matrix<ElementType>& queries,
585  Matrix<int>& indices,
586  Matrix<DistanceType>& dists,
587  float radius,
588  const SearchParams& params) const
589  {
590  rtflann::Matrix<size_t> indices_(new size_t[indices.rows*indices.cols], indices.rows, indices.cols);
591  int result = radiusSearch(queries, indices_, dists, radius, params);
592 
593  for (size_t i=0;i<indices.rows;++i) {
594  for (size_t j=0;j<indices.cols;++j) {
595  indices[i][j] = indices_[i][j];
596  }
597  }
598  delete[] indices_.ptr();
599  return result;
600  }
601 
611  virtual int radiusSearch(const Matrix<ElementType>& queries,
612  std::vector< std::vector<size_t> >& indices,
613  std::vector<std::vector<DistanceType> >& dists,
614  float radius,
615  const SearchParams& params) const
616  {
617  assert(queries.cols == veclen());
618  int count = 0;
619  // just count neighbors
620  if (params.max_neighbors==0) {
621 #pragma omp parallel num_threads(params.cores)
622  {
623  CountRadiusResultSet<DistanceType> resultSet(radius);
624 #pragma omp for schedule(static) reduction(+:count)
625  for (int i = 0; i < (int)queries.rows; i++) {
626  resultSet.clear();
627  findNeighbors(resultSet, queries[i], params);
628  count += resultSet.size();
629  }
630  }
631  }
632  else {
633  if (indices.size() < queries.rows ) indices.resize(queries.rows);
634  if (dists.size() < queries.rows ) dists.resize(queries.rows);
635 
636  if (params.max_neighbors<0) {
637  // search for all neighbors
638 #pragma omp parallel num_threads(params.cores)
639  {
640  RadiusResultSet<DistanceType> resultSet(radius);
641 #pragma omp for schedule(static) reduction(+:count)
642  for (int i = 0; i < (int)queries.rows; i++) {
643  resultSet.clear();
644  findNeighbors(resultSet, queries[i], params);
645  size_t n = resultSet.size();
646  count += n;
647  indices[i].resize(n);
648  dists[i].resize(n);
649  if (n > 0) {
650  resultSet.copy(&indices[i][0], &dists[i][0], n, params.sorted);
651  indices_to_ids(&indices[i][0], &indices[i][0], n);
652  }
653  }
654  }
655  }
656  else {
657  // number of neighbors limited to max_neighbors
658 #pragma omp parallel num_threads(params.cores)
659  {
660  KNNRadiusResultSet<DistanceType> resultSet(radius, params.max_neighbors);
661 #pragma omp for schedule(static) reduction(+:count)
662  for (int i = 0; i < (int)queries.rows; i++) {
663  resultSet.clear();
664  findNeighbors(resultSet, queries[i], params);
665  size_t n = resultSet.size();
666  count += n;
667  if ((int)n>params.max_neighbors) n = params.max_neighbors;
668  indices[i].resize(n);
669  dists[i].resize(n);
670  if (n > 0) {
671  resultSet.copy(&indices[i][0], &dists[i][0], n, params.sorted);
672  indices_to_ids(&indices[i][0], &indices[i][0], n);
673  }
674  }
675  }
676  }
677  }
678  return count;
679  }
680 
690  int radiusSearch(const Matrix<ElementType>& queries,
691  std::vector< std::vector<int> >& indices,
692  std::vector<std::vector<DistanceType> >& dists,
693  float radius,
694  const SearchParams& params) const
695  {
696  std::vector<std::vector<size_t> > indices_;
697  int result = radiusSearch(queries, indices_, dists, radius, params);
698 
699  indices.resize(indices_.size());
700  for (size_t i=0;i<indices_.size();++i) {
701  indices[i].assign(indices_[i].begin(), indices_[i].end());
702  }
703  return result;
704  }
705 
706 
707  virtual void findNeighbors(ResultSet<DistanceType>& result, const ElementType* vec, const SearchParams& searchParams) const = 0;
708 
709 protected:
710 
711  virtual void freeIndex() = 0;
712 
713  virtual void buildIndexImpl() = 0;
714 
715  size_t id_to_index(size_t id)
716  {
717  if (ids_.size()==0) {
718  return id;
719  }
720  size_t point_index = size_t(-1);
721  if (id < ids_.size() && ids_[id]==id) {
722  return id;
723  }
724  else {
725  // binary search
726  size_t start = 0;
727  size_t end = ids_.size();
728 
729  while (start<end) {
730  size_t mid = (start+end)/2;
731  if (ids_[mid]==id) {
732  point_index = mid;
733  break;
734  }
735  else if (ids_[mid]<id) {
736  start = mid + 1;
737  }
738  else {
739  end = mid;
740  }
741  }
742  }
743  return point_index;
744  }
745 
746 
747  void indices_to_ids(const size_t* in, size_t* out, size_t size) const
748  {
749  if (removed_) {
750  for (size_t i=0;i<size;++i) {
751  out[i] = ids_[in[i]];
752  }
753  }
754  }
755 
756  void setDataset(const Matrix<ElementType>& dataset)
757  {
758  size_ = dataset.rows;
759  veclen_ = dataset.cols;
760  last_id_ = 0;
761 
762  ids_.clear();
763  removed_points_.clear();
764  removed_ = false;
765  removed_count_ = 0;
766 
767  points_.resize(size_);
768  for (size_t i=0;i<size_;++i) {
769  points_[i] = dataset[i];
770  }
771  }
772 
773  void extendDataset(const Matrix<ElementType>& new_points)
774  {
775  size_t new_size = size_ + new_points.rows;
776  if (removed_) {
777  removed_points_.resize(new_size);
778  ids_.resize(new_size);
779  }
780  points_.resize(new_size);
781  for (size_t i=size_;i<new_size;++i) {
782  points_[i] = new_points[i-size_];
783  if (removed_) {
784  ids_[i] = last_id_++;
785  removed_points_.reset(i);
786  }
787  }
788  size_ = new_size;
789  }
790 
791 
793  {
794  if (!removed_) return;
795 
796  size_t last_idx = 0;
797  for (size_t i=0;i<size_;++i) {
798  if (!removed_points_.test(i)) {
799  points_[last_idx] = points_[i];
800  ids_[last_idx] = ids_[i];
801  removed_points_.reset(last_idx);
802  ++last_idx;
803  }
804  }
805  points_.resize(last_idx);
806  ids_.resize(last_idx);
807  removed_points_.resize(last_idx);
808  size_ = last_idx;
809  removed_count_ = 0;
810  }
811 
812  void swap(NNIndex& other)
813  {
814  std::swap(distance_, other.distance_);
815  std::swap(last_id_, other.last_id_);
816  std::swap(size_, other.size_);
817  std::swap(size_at_build_, other.size_at_build_);
818  std::swap(veclen_, other.veclen_);
819  std::swap(index_params_, other.index_params_);
820  std::swap(removed_, other.removed_);
821  std::swap(removed_points_, other.removed_points_);
822  std::swap(removed_count_, other.removed_count_);
823  std::swap(ids_, other.ids_);
824  std::swap(points_, other.points_);
825  std::swap(data_ptr_, other.data_ptr_);
826  }
827 
828 protected:
829 
833  Distance distance_;
834 
835 
841  size_t last_id_;
842 
846  size_t size_;
847 
852 
856  size_t veclen_;
857 
862 
866  bool removed_;
867 
872 
877 
881  std::vector<size_t> ids_;
882 
886  std::vector<ElementType*> points_;
887 
891  ElementType* data_ptr_;
892 
893 
894 };
895 
896 
897 #define USING_BASECLASS_SYMBOLS \
898  using NNIndex<Distance>::distance_;\
899  using NNIndex<Distance>::size_;\
900  using NNIndex<Distance>::size_at_build_;\
901  using NNIndex<Distance>::veclen_;\
902  using NNIndex<Distance>::index_params_;\
903  using NNIndex<Distance>::removed_points_;\
904  using NNIndex<Distance>::ids_;\
905  using NNIndex<Distance>::removed_;\
906  using NNIndex<Distance>::points_;\
907  using NNIndex<Distance>::extendDataset;\
908  using NNIndex<Distance>::setDataset;\
909  using NNIndex<Distance>::cleanRemovedPoints;\
910  using NNIndex<Distance>::indices_to_ids;
911 
912 
913 
914 }
915 
916 
917 #endif //FLANN_NNINDEX_H
#define NULL
std::map< std::string, any > IndexParams
Definition: params.h:51
int radiusSearch(const Matrix< ElementType > &queries, Matrix< int > &indices, Matrix< DistanceType > &dists, float radius, const SearchParams &params) const
Definition: nn_index.h:584
void indices_to_ids(const size_t *in, size_t *out, size_t size) const
Definition: nn_index.h:747
virtual size_t veclen() const =0
void copy(size_t *indices, DistanceType *dists, size_t num_elements, bool sorted=true)
Definition: result_set.h:388
flann_datatype_t data_type
Definition: serialization.h:18
void swap(NNIndex &other)
Definition: nn_index.h:812
void copy(size_t *indices, DistanceType *dists, size_t num_elements, bool sorted=true)
Definition: result_set.h:612
T get_param(const IndexParams &params, std::string name, const T &default_value)
Definition: params.h:95
GLM_FUNC_DECL genType min(genType const &x, genType const &y)
size_t size() const
Definition: result_set.h:335
virtual void saveIndex(FILE *stream)=0
virtual 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.
Definition: nn_index.h:315
Distance::ResultType DistanceType
Definition: nn_index.h:77
#define FLANN_SIGNATURE_
Definition: saving.h:43
size_t size() const
Definition: nn_index.h:201
virtual ~NNIndex()
Definition: nn_index.h:112
T * ptr() const
Definition: matrix.h:127
IndexParams getParameters() const
Definition: nn_index.h:229
virtual size_t size() const =0
virtual int usedMemory() const =0
size_t rows
Definition: matrix.h:72
std_msgs::Header * header(M &m)
virtual IndexParams getParameters() const =0
void extendDataset(const Matrix< ElementType > &new_points)
Definition: nn_index.h:773
size_t id_to_index(size_t id)
Definition: nn_index.h:715
IndexHeaderStruct h
Definition: saving.h:53
size_t size_at_build_
Definition: nn_index.h:851
virtual ~IndexBase()
Definition: nn_index.h:52
size_t last_id_
Definition: nn_index.h:841
virtual int radiusSearch(const Matrix< ElementType > &queries, Matrix< size_t > &indices, Matrix< DistanceType > &dists, float radius, const SearchParams &params) const
Perform radius search.
Definition: nn_index.h:501
int knnSearch(const Matrix< ElementType > &queries, std::vector< std::vector< int > > &indices, std::vector< std::vector< DistanceType > > &dists, size_t knn, const SearchParams &params) const
Definition: nn_index.h:476
void setDataset(const Matrix< ElementType > &dataset)
Definition: nn_index.h:756
size_t cols
Definition: matrix.h:73
virtual void buildIndex()
Definition: nn_index.h:125
Distance distance_
Definition: nn_index.h:833
virtual void buildIndex(const Matrix< ElementType > &dataset)
Definition: nn_index.h:141
flann_algorithm_t index_type
Definition: serialization.h:19
flann_algorithm_t
Definition: defines.h:79
ElementType * data_ptr_
Definition: nn_index.h:891
virtual 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
Perform k-nearest neighbor search.
Definition: nn_index.h:405
#define KNN_HEAP_THRESHOLD
Definition: nn_index.h:46
const binary_object make_binary_object(void *t, size_t size)
int radiusSearch(const Matrix< ElementType > &queries, std::vector< std::vector< int > > &indices, std::vector< std::vector< DistanceType > > &dists, float radius, const SearchParams &params) const
Definition: nn_index.h:690
tri_type use_heap
Definition: params.h:81
virtual void addPoints(const Matrix< ElementType > &points, float rebuild_threshold=2)
Incrementally add points to the index.
Definition: nn_index.h:152
NNIndex(Distance d)
Definition: nn_index.h:79
virtual int radiusSearch(const Matrix< ElementType > &queries, std::vector< std::vector< size_t > > &indices, std::vector< std::vector< DistanceType > > &dists, float radius, const SearchParams &params) const
Perform radius search.
Definition: nn_index.h:611
#define false
Definition: ConvertUTF.c:56
size_t removed_count_
Definition: nn_index.h:876
virtual void loadIndex(FILE *stream)=0
void copy(size_t *indices, DistanceType *dists, size_t num_elements, bool sorted=true)
Definition: result_set.h:490
virtual void removePoint(size_t id)
Definition: nn_index.h:161
size_t sizeAtBuild() const
Definition: nn_index.h:211
void cleanRemovedPoints()
Definition: nn_index.h:792
void serialize(Archive &ar)
Definition: nn_index.h:236
Distance::ElementType ElementType
Definition: nn_index.h:76
IndexParams index_params_
Definition: nn_index.h:861
static void freeIndex(sqlite3 *db, Index *p)
Definition: sqlite3.c:84627
NNIndex(const NNIndex &other)
Definition: nn_index.h:89
NNIndex(const IndexParams &params, Distance d)
Definition: nn_index.h:84
std::vector< ElementType * > points_
Definition: nn_index.h:886
void copy(size_t *indices, DistanceType *dists, size_t num_elements, bool sorted=true)
Definition: result_set.h:180
virtual ElementType * getPoint(size_t id)
Definition: nn_index.h:187
size_t removedCount() const
Definition: nn_index.h:206
std::vector< size_t > ids_
Definition: nn_index.h:881
size_t size() const
Definition: result_set.h:455
size_t veclen() const
Definition: nn_index.h:219
virtual flann_algorithm_t getType() const =0
size_t veclen_
Definition: nn_index.h:856
DynamicBitset removed_points_
Definition: nn_index.h:871


rtabmap
Author(s): Mathieu Labbe
autogenerated on Mon Dec 14 2020 03:34:59