linear_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_LINEAR_INDEX_H_
32 #define RTABMAP_FLANN_LINEAR_INDEX_H_
33 
34 #include "rtflann/general.h"
35 #include "nn_index.h"
36 
37 namespace rtflann
38 {
39 
40 struct LinearIndexParams : public IndexParams
41 {
43  {
44  (* this)["algorithm"] = FLANN_INDEX_LINEAR;
45  }
46 };
47 
48 template <typename Distance>
49 class LinearIndex : public NNIndex<Distance>
50 {
51 public:
52 
53  typedef typename Distance::ElementType ElementType;
54  typedef typename Distance::ResultType DistanceType;
55 
56  typedef NNIndex<Distance> BaseClass;
57 
58  LinearIndex(const IndexParams& params = LinearIndexParams(), Distance d = Distance()) :
60  {
61  }
62 
63  LinearIndex(const Matrix<ElementType>& input_data, const IndexParams& params = LinearIndexParams(), Distance d = Distance()) :
65  {
66  setDataset(input_data);
67  }
68 
69  LinearIndex(const LinearIndex& other) : BaseClass(other)
70  {
71  }
72 
74  {
75  this->swap(other);
76  return *this;
77  }
78 
79  virtual ~LinearIndex()
80  {
81  }
82 
83  BaseClass* clone() const
84  {
85  return new LinearIndex(*this);
86  }
87 
88  void addPoints(const Matrix<ElementType>& points, float rebuild_threshold = 2)
89  {
90  assert(points.cols==veclen_);
91  extendDataset(points);
92  }
93 
95  {
96  return FLANN_INDEX_LINEAR;
97  }
98 
99 
100  int usedMemory() const
101  {
102  return 0;
103  }
104 
105  template<typename Archive>
106  void serialize(Archive& ar)
107  {
108  ar.setObject(this);
109 
110  ar & *static_cast<NNIndex<Distance>*>(this);
111 
112  if (Archive::is_loading::value) {
113  index_params_["algorithm"] = getType();
114  }
115  }
116 
117  void saveIndex(FILE* stream)
118  {
120  sa & *this;
121  }
122 
123  void loadIndex(FILE* stream)
124  {
126  la & *this;
127  }
128 
129  void findNeighbors(ResultSet<DistanceType>& resultSet, const ElementType* vec, const SearchParams& /*searchParams*/) const
130  {
131  if (removed_) {
132  for (size_t i = 0; i < points_.size(); ++i) {
133  if (removed_points_.test(i)) continue;
135  resultSet.addPoint(dist, i);
136  }
137  }
138  else {
139  for (size_t i = 0; i < points_.size(); ++i) {
141  resultSet.addPoint(dist, i);
142  }
143  }
144  }
145 protected:
146  void buildIndexImpl()
147  {
148  /* nothing to do here for linear search */
149  }
150 
151  void freeIndex()
152  {
153  /* nothing to do here for linear search */
154  }
155 
156 private:
157 
159 };
160 
161 }
162 
163 #endif // FLANN_LINEAR_INDEX_H_
general.h
rtflann::ResultSet
Definition: result_set.h:110
rtflann::NNIndex
Definition: nn_index.h:101
rtflann::LinearIndex::findNeighbors
void findNeighbors(ResultSet< DistanceType > &resultSet, const ElementType *vec, const SearchParams &) const
Definition: linear_index.h:157
rtflann::serialization::SaveArchive
Definition: serialization.h:376
stream
stream
rtflann::Matrix_::cols
size_t cols
Definition: matrix.h:101
rtflann::LinearIndex::~LinearIndex
virtual ~LinearIndex()
Definition: linear_index.h:107
rtflann::LinearIndex::LinearIndex
LinearIndex(const IndexParams &params=LinearIndexParams(), Distance d=Distance())
Definition: linear_index.h:86
nn_index.h
rtflann::NNIndex::points_
std::vector< ElementType * > points_
Definition: nn_index.h:914
rtflann::LinearIndex::BaseClass
NNIndex< Distance > BaseClass
Definition: linear_index.h:84
rtflann::LinearIndex::saveIndex
void saveIndex(FILE *stream)
Definition: linear_index.h:145
rtflann::DynamicBitset::test
bool test(size_t index) const
Definition: dynamic_bitset.h:199
rtflann::LinearIndex::freeIndex
void freeIndex()
Definition: linear_index.h:179
rtflann::LinearIndex::addPoints
void addPoints(const Matrix< ElementType > &points, float rebuild_threshold=2)
Incrementally add points to the index.
Definition: linear_index.h:116
rtflann::serialization::LoadArchive
Definition: serialization.h:550
rtflann::NNIndex::veclen_
size_t veclen_
Definition: nn_index.h:884
rtflann::NNIndex::removed_points_
DynamicBitset removed_points_
Definition: nn_index.h:899
rtflann::ResultSet::addPoint
virtual void addPoint(DistanceType dist, size_t index)=0
rtflann::LinearIndex::usedMemory
int usedMemory() const
Definition: linear_index.h:128
rtflann::SearchParams
Definition: params.h:87
rtflann::LinearIndex::getType
flann_algorithm_t getType() const
Definition: linear_index.h:122
rtflann::LinearIndexParams::LinearIndexParams
LinearIndexParams()
Definition: linear_index.h:98
rtflann::NNIndex::setDataset
void setDataset(const Matrix< ElementType > &dataset)
Definition: nn_index.h:784
d
d
params
SmartProjectionParams params(gtsam::HESSIAN, gtsam::ZERO_ON_DEGENERACY)
rtflann::NNIndex::distance_
Distance distance_
Definition: nn_index.h:861
rtflann::NNIndex::removed_
bool removed_
Definition: nn_index.h:894
rtflann::LinearIndex::serialize
void serialize(Archive &ar)
Definition: linear_index.h:134
rtflann::LinearIndex::DistanceType
Distance::ResultType DistanceType
Definition: linear_index.h:82
rtflann::flann_algorithm_t
flann_algorithm_t
Definition: defines.h:79
rtflann::NNIndex::swap
void swap(NNIndex &other)
Definition: nn_index.h:840
rtflann::LinearIndex::loadIndex
void loadIndex(FILE *stream)
Definition: linear_index.h:151
rtflann::LinearIndex
Definition: linear_index.h:77
Eigen.Matrix< double, Eigen::Dynamic, Eigen::Dynamic, Eigen::RowMajor >
rtflann::IndexParams
std::map< std::string, any > IndexParams
Definition: params.h:77
rtflann::LinearIndex::buildIndexImpl
void buildIndexImpl()
Definition: linear_index.h:174
dist
dist
USING_BASECLASS_SYMBOLS
#define USING_BASECLASS_SYMBOLS
Definition: nn_index.h:925
rtflann::LinearIndex::ElementType
Distance::ElementType ElementType
Definition: linear_index.h:81
rtflann::LinearIndex::operator=
LinearIndex & operator=(LinearIndex other)
Definition: linear_index.h:101
rtflann::NNIndex::extendDataset
void extendDataset(const Matrix< ElementType > &new_points)
Definition: nn_index.h:801
rtflann::FLANN_INDEX_LINEAR
@ FLANN_INDEX_LINEAR
Definition: defines.h:81
rtflann
Definition: all_indices.h:49
i
int i
other
other
rtflann::NNIndex::index_params_
IndexParams index_params_
Definition: nn_index.h:889
rtflann::LinearIndex::clone
BaseClass * clone() const
Definition: linear_index.h:111
rtflann::Matrix< ElementType >


rtabmap
Author(s): Mathieu Labbe
autogenerated on Thu Jul 25 2024 02:50:11