nabo.h
Go to the documentation of this file.
1 /*
2 
3 Copyright (c) 2010--2011, Stephane Magnenat, ASL, ETHZ, Switzerland
4 You can contact the author at <stephane at magnenat dot net>
5 
6 All rights reserved.
7 
8 Redistribution and use in source and binary forms, with or without
9 modification, are permitted provided that the following conditions are met:
10  * Redistributions of source code must retain the above copyright
11  notice, this list of conditions and the following disclaimer.
12  * Redistributions in binary form must reproduce the above copyright
13  notice, this list of conditions and the following disclaimer in the
14  documentation and/or other materials provided with the distribution.
15  * Neither the name of the <organization> nor the
16  names of its contributors may be used to endorse or promote products
17  derived from this software without specific prior written permission.
18 
19 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
20 ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
21 WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
22 DISCLAIMED. IN NO EVENT SHALL ETH-ASL BE LIABLE FOR ANY
23 DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
24 (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
25 LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
26 ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
27 (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
28 SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
29 
30 */
31 
32 #ifndef __NABO_H
33 #define __NABO_H
34 
35 #include "Eigen/Core"
36 #if EIGEN_VERSION_AT_LEAST(2,92,0)
37  #define EIGEN3_API
38 #endif
39 #ifndef EIGEN3_API
40  #include "Eigen/Array"
41 #endif
42 #include <vector>
43 #include <map>
44 #include "third_party/any.hpp"
45 
204 namespace Nabo
206 {
208 
209 
211  #define NABO_VERSION "1.0.7"
212  #define NABO_VERSION_INT 10007
214 
215  // TODO (c++14) Convert invalidIndex, invalidValue to constexpr templated variables.
216  template <typename IndexType>
217  inline constexpr IndexType invalidIndex() {
218  static_assert(std::is_integral<IndexType>::value, "");
219  return std::is_unsigned<IndexType>::value ? std::numeric_limits<IndexType>::max() : IndexType(-1);
220  }
221 
222  template <typename ValueType>
223  inline constexpr ValueType invalidValue() {
224  static_assert(std::is_floating_point<ValueType>::value, "");
225  return std::numeric_limits<ValueType>::infinity();
226  }
227 
229  //
230  // TODO: replace with C++17 std::any.
231  struct Parameters: public std::map<std::string, linb::any>
232  {
236 
239  Parameters(const std::string& key, const linb::any& value){(*this)[key] = value;}
241 
245  template<typename T>
246  T get(const std::string& key, const T& defaultValue) const
247  {
248  const_iterator it(find(key));
249  if (it != end())
250  return linb::any_cast<T>(it->second);
251  else
252  return defaultValue;
253  }
254  };
255 
257  template<typename T, typename Cloud_T = Eigen::Matrix<T, Eigen::Dynamic, Eigen::Dynamic> >
259  {
261  typedef typename Eigen::Matrix<T, Eigen::Dynamic, 1> Vector;
263  typedef typename Eigen::Matrix<T, Eigen::Dynamic, Eigen::Dynamic> Matrix;
265  typedef Cloud_T CloudType;
267  typedef int Index;
269  typedef typename Eigen::Matrix<Index, Eigen::Dynamic, 1> IndexVector;
271  typedef typename Eigen::Matrix<Index, Eigen::Dynamic, Eigen::Dynamic> IndexMatrix;
272 
274  const CloudType& cloud;
276  const Index dim;
278  const unsigned creationOptionFlags;
280  const Vector minBound;
282  const Vector maxBound;
283 
285  static constexpr Index InvalidIndex = invalidIndex<Index>();
287  static constexpr T InvalidValue = invalidValue<T>();
288 
291  {
292  BRUTE_FORCE = 0,
298  SEARCH_TYPE_COUNT
299  };
300 
303  {
304  TOUCH_STATISTICS = 1
305  };
306 
309  {
310  ALLOW_SELF_MATCH = 1,
311  SORT_RESULTS = 2
312  };
313 
315 
325  unsigned long knn(const Vector& query, IndexVector& indices, Vector& dists2, const Index k = 1, const T epsilon = 0, const unsigned optionFlags = 0, const T maxRadius = std::numeric_limits<T>::infinity()) const;
326 
328 
338  virtual unsigned long knn(const Matrix& query, IndexMatrix& indices, Matrix& dists2, const Index k = 1, const T epsilon = 0, const unsigned optionFlags = 0, const T maxRadius = std::numeric_limits<T>::infinity()) const = 0;
339 
341 
351  virtual unsigned long knn(const Matrix& query, IndexMatrix& indices, Matrix& dists2, const Vector& maxRadii, const Index k = 1, const T epsilon = 0, const unsigned optionFlags = 0) const = 0;
352 
354 
360  static NearestNeighbourSearch* create(const CloudType& cloud, const Index dim = std::numeric_limits<Index>::max(), const SearchType preferedType = KDTREE_LINEAR_HEAP, const unsigned creationOptionFlags = 0, const Parameters& additionalParameters = Parameters());
361 
363 
368  static NearestNeighbourSearch* createBruteForce(const CloudType& cloud, const Index dim = std::numeric_limits<Index>::max(), const unsigned creationOptionFlags = 0);
369 
371 
377  static NearestNeighbourSearch* createKDTreeLinearHeap(const CloudType& cloud, const Index dim = std::numeric_limits<Index>::max(), const unsigned creationOptionFlags = 0, const Parameters& additionalParameters = Parameters());
378 
380 
386  static NearestNeighbourSearch* createKDTreeTreeHeap(const CloudType& cloud, const Index dim = std::numeric_limits<Index>::max(), const unsigned creationOptionFlags = 0, const Parameters& additionalParameters = Parameters());
387 
388 
389 
391  template <typename WrongMatrixType>
392  static NearestNeighbourSearch* create(const WrongMatrixType& cloud, const Index dim = std::numeric_limits<Index>::max(), const SearchType preferedType = KDTREE_LINEAR_HEAP, const unsigned creationOptionFlags = 0, const Parameters& additionalParameters = Parameters())
393  {
394  typedef int Please_make_sure_that_the_decltype_of_the_first_parameter_is_equal_to_the_Matrix_typedef[sizeof(WrongMatrixType) > 0 ? -1 : 1];
395  Please_make_sure_that_the_decltype_of_the_first_parameter_is_equal_to_the_Matrix_typedef dummy;
396  return NULL;
397  }
398 
400  template <typename WrongMatrixType>
401  static NearestNeighbourSearch* createBruteForce(const WrongMatrixType& cloud, const Index dim = std::numeric_limits<Index>::max(), const unsigned creationOptionFlags = 0)
402  {
403  typedef int Please_make_sure_that_the_decltype_of_the_first_parameter_is_equal_to_the_Matrix_typedef[sizeof(WrongMatrixType) > 0 ? -1 : 1];
404  Please_make_sure_that_the_decltype_of_the_first_parameter_is_equal_to_the_Matrix_typedef dummy;
405  return NULL;
406  }
407 
409  template <typename WrongMatrixType>
410  static NearestNeighbourSearch* createKDTreeLinearHeap(const WrongMatrixType& cloud, const Index dim = std::numeric_limits<Index>::max(), const unsigned creationOptionFlags = 0, const Parameters& additionalParameters = Parameters())
411  {
412  typedef int Please_make_sure_that_the_decltype_of_the_first_parameter_is_equal_to_the_Matrix_typedef[sizeof(WrongMatrixType) > 0 ? -1 : 1];
413  Please_make_sure_that_the_decltype_of_the_first_parameter_is_equal_to_the_Matrix_typedef dummy;
414  return NULL;
415  }
416 
418  template <typename WrongMatrixType>
419  static NearestNeighbourSearch* createKDTreeTreeHeap(const WrongMatrixType&, const Index dim = std::numeric_limits<Index>::max(), const unsigned creationOptionFlags = 0, const Parameters& additionalParameters = Parameters())
420  {
421  typedef int Please_make_sure_that_the_decltype_of_the_first_parameter_is_equal_to_the_Matrix_typedef[sizeof(WrongMatrixType) > 0 ? -1 : 1];
422  Please_make_sure_that_the_decltype_of_the_first_parameter_is_equal_to_the_Matrix_typedef dummy;
423  return NULL;
424  }
425 
428 
429  protected:
431  NearestNeighbourSearch(const CloudType& cloud, const Index dim, const unsigned creationOptionFlags);
432 
434 
440  void checkSizesKnn(const Matrix& query, const IndexMatrix& indices, const Matrix& dists2, const Index k, const unsigned optionFlags, const Vector* maxRadii = 0) const;
441  };
442 
443  // Convenience typedefs
444 
449 
451 }
452 
453 #endif // __NABO_H
Eigen::Matrix< T, Eigen::Dynamic, Eigen::Dynamic > Matrix
a column-major Eigen matrix in which each column is a point; this matrix has dim rows ...
Definition: nabo.h:263
Parameters()
Create an empty parameter vector.
Definition: nabo.h:234
const unsigned creationOptionFlags
creation options
Definition: nabo.h:278
virtual ~NearestNeighbourSearch()
virtual destructor
Definition: nabo.h:427
kd-tree with tree heap, good for large k (~from 30)
Definition: nabo.h:294
kd-tree using openCL, pt in nodes, only available if OpenCL enabled, UNSTABLE API ...
Definition: nabo.h:295
Nearest neighbour search interface, templatized on scalar type.
Definition: nabo.h:258
static NearestNeighbourSearch * createBruteForce(const WrongMatrixType &cloud, const Index dim=std::numeric_limits< Index >::max(), const unsigned creationOptionFlags=0)
Prevent creation of trees with the wrong matrix type. Currently only dynamic size matrices are suppor...
Definition: nabo.h:401
constexpr ValueType invalidValue()
Definition: nabo.h:223
ValueType any_cast(const any &operand)
Performs *any_cast<add_const_t<remove_reference_t<ValueType>>>(&operand), or throws bad_any_cast on f...
Definition: any.hpp:384
const CloudType & cloud
the reference to the data-point cloud, which must remain valid during the lifetime of the NearestNeig...
Definition: nabo.h:274
static NearestNeighbourSearch * create(const WrongMatrixType &cloud, const Index dim=std::numeric_limits< Index >::max(), const SearchType preferedType=KDTREE_LINEAR_HEAP, const unsigned creationOptionFlags=0, const Parameters &additionalParameters=Parameters())
Prevent creation of trees with the wrong matrix type. Currently only dynamic size matrices are suppor...
Definition: nabo.h:392
Eigen::Matrix< T, Eigen::Dynamic, 1 > Vector
an Eigen vector of type T, to hold the coordinates of a point
Definition: nabo.h:261
NearestNeighbourSearch< double > NNSearchD
nearest neighbour search with scalars of type double
Definition: nabo.h:448
int Index
an index to a Vector or a Matrix, for refering to data points
Definition: nabo.h:267
Eigen::Matrix< Index, Eigen::Dynamic, Eigen::Dynamic > IndexMatrix
a matrix of indices to data points
Definition: nabo.h:271
static NearestNeighbourSearch * createKDTreeTreeHeap(const WrongMatrixType &, const Index dim=std::numeric_limits< Index >::max(), const unsigned creationOptionFlags=0, const Parameters &additionalParameters=Parameters())
Prevent creation of trees with the wrong matrix type. Currently only dynamic size matrices are suppor...
Definition: nabo.h:419
brute-force using openCL, only available if OpenCL enabled, UNSTABLE API
Definition: nabo.h:297
Parameter vector.
Definition: nabo.h:231
Eigen::Matrix< Index, Eigen::Dynamic, 1 > IndexVector
a vector of indices to data points
Definition: nabo.h:269
const Vector maxBound
the high bound of the search space (axis-aligned bounding box)
Definition: nabo.h:282
const Vector minBound
the low bound of the search space (axis-aligned bounding box)
Definition: nabo.h:280
kd-tree using openCL, pt in leaves, only available if OpenCL enabled, UNSTABLE API ...
Definition: nabo.h:296
Namespace for Nabo.
static NearestNeighbourSearch * createKDTreeLinearHeap(const WrongMatrixType &cloud, const Index dim=std::numeric_limits< Index >::max(), const unsigned creationOptionFlags=0, const Parameters &additionalParameters=Parameters())
Prevent creation of trees with the wrong matrix type. Currently only dynamic size matrices are suppor...
Definition: nabo.h:410
constexpr IndexType invalidIndex()
Definition: nabo.h:217
const Index dim
the dimensionality of the data-point cloud
Definition: nabo.h:276
Cloud_T CloudType
a column-major Eigen matrix in which each column is a point; this matrix has dim rows ...
Definition: nabo.h:265
kd-tree with linear heap, good for small k (~up to 30)
Definition: nabo.h:293
Parameters(const std::string &key, const linb::any &value)
Create a parameter vector with a single entry.
Definition: nabo.h:239
NearestNeighbourSearch< float > NNSearchF
nearest neighbour search with scalars of type float
Definition: nabo.h:446


libnabo
Author(s): Stéphane Magnenat
autogenerated on Mon Feb 28 2022 22:41:38