00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032 #ifndef __NABO_H
00033 #define __NABO_H
00034
00035 #include "Eigen/Core"
00036 #if EIGEN_VERSION_AT_LEAST(2,92,0)
00037 #define EIGEN3_API
00038 #endif
00039 #ifndef EIGEN3_API
00040 #include "Eigen/Array"
00041 #endif
00042 #include <vector>
00043 #include <map>
00044 #include "third_party/any.hpp"
00045
00204
00205 namespace Nabo
00206 {
00208
00209
00211 #define NABO_VERSION "1.0.7"
00212
00213 #define NABO_VERSION_INT 10007
00214
00215
00216 template <typename IndexType>
00217 inline constexpr IndexType invalidIndex() {
00218 static_assert(std::is_integral<IndexType>::value, "");
00219 return std::is_unsigned<IndexType>::value ? std::numeric_limits<IndexType>::max() : IndexType(-1);
00220 }
00221
00222 template <typename ValueType>
00223 inline constexpr ValueType invalidValue() {
00224 static_assert(std::is_floating_point<ValueType>::value, "");
00225 return std::numeric_limits<ValueType>::infinity();
00226 }
00227
00229
00230
00231 struct Parameters: public std::map<std::string, linb::any>
00232 {
00234 Parameters(){}
00236
00239 Parameters(const std::string& key, const linb::any& value){(*this)[key] = value;}
00241
00245 template<typename T>
00246 T get(const std::string& key, const T& defaultValue) const
00247 {
00248 const_iterator it(find(key));
00249 if (it != end())
00250 return linb::any_cast<T>(it->second);
00251 else
00252 return defaultValue;
00253 }
00254 };
00255
00257 template<typename T, typename Cloud_T = Eigen::Matrix<T, Eigen::Dynamic, Eigen::Dynamic> >
00258 struct NearestNeighbourSearch
00259 {
00261 typedef typename Eigen::Matrix<T, Eigen::Dynamic, 1> Vector;
00263 typedef typename Eigen::Matrix<T, Eigen::Dynamic, Eigen::Dynamic> Matrix;
00265 typedef Cloud_T CloudType;
00267 typedef int Index;
00269 typedef typename Eigen::Matrix<Index, Eigen::Dynamic, 1> IndexVector;
00271 typedef typename Eigen::Matrix<Index, Eigen::Dynamic, Eigen::Dynamic> IndexMatrix;
00272
00274 const CloudType& cloud;
00276 const Index dim;
00278 const unsigned creationOptionFlags;
00280 const Vector minBound;
00282 const Vector maxBound;
00283
00285 static constexpr Index InvalidIndex = invalidIndex<Index>();
00287 static constexpr T InvalidValue = invalidValue<T>();
00288
00290 enum SearchType
00291 {
00292 BRUTE_FORCE = 0,
00293 KDTREE_LINEAR_HEAP,
00294 KDTREE_TREE_HEAP,
00295 KDTREE_CL_PT_IN_NODES,
00296 KDTREE_CL_PT_IN_LEAVES,
00297 BRUTE_FORCE_CL,
00298 SEARCH_TYPE_COUNT
00299 };
00300
00302 enum CreationOptionFlags
00303 {
00304 TOUCH_STATISTICS = 1
00305 };
00306
00308 enum SearchOptionFlags
00309 {
00310 ALLOW_SELF_MATCH = 1,
00311 SORT_RESULTS = 2
00312 };
00313
00315
00325 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;
00326
00328
00338 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;
00339
00341
00351 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;
00352
00354
00360 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());
00361
00363
00368 static NearestNeighbourSearch* createBruteForce(const CloudType& cloud, const Index dim = std::numeric_limits<Index>::max(), const unsigned creationOptionFlags = 0);
00369
00371
00377 static NearestNeighbourSearch* createKDTreeLinearHeap(const CloudType& cloud, const Index dim = std::numeric_limits<Index>::max(), const unsigned creationOptionFlags = 0, const Parameters& additionalParameters = Parameters());
00378
00380
00386 static NearestNeighbourSearch* createKDTreeTreeHeap(const CloudType& cloud, const Index dim = std::numeric_limits<Index>::max(), const unsigned creationOptionFlags = 0, const Parameters& additionalParameters = Parameters());
00387
00388
00389
00391 template <typename WrongMatrixType>
00392 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())
00393 {
00394 typedef int Please_make_sure_that_the_decltype_of_the_first_parameter_is_equal_to_the_Matrix_typedef[sizeof(WrongMatrixType) > 0 ? -1 : 1];
00395 Please_make_sure_that_the_decltype_of_the_first_parameter_is_equal_to_the_Matrix_typedef dummy;
00396 return NULL;
00397 }
00398
00400 template <typename WrongMatrixType>
00401 static NearestNeighbourSearch* createBruteForce(const WrongMatrixType& cloud, const Index dim = std::numeric_limits<Index>::max(), const unsigned creationOptionFlags = 0)
00402 {
00403 typedef int Please_make_sure_that_the_decltype_of_the_first_parameter_is_equal_to_the_Matrix_typedef[sizeof(WrongMatrixType) > 0 ? -1 : 1];
00404 Please_make_sure_that_the_decltype_of_the_first_parameter_is_equal_to_the_Matrix_typedef dummy;
00405 return NULL;
00406 }
00407
00409 template <typename WrongMatrixType>
00410 static NearestNeighbourSearch* createKDTreeLinearHeap(const WrongMatrixType& cloud, const Index dim = std::numeric_limits<Index>::max(), const unsigned creationOptionFlags = 0, const Parameters& additionalParameters = Parameters())
00411 {
00412 typedef int Please_make_sure_that_the_decltype_of_the_first_parameter_is_equal_to_the_Matrix_typedef[sizeof(WrongMatrixType) > 0 ? -1 : 1];
00413 Please_make_sure_that_the_decltype_of_the_first_parameter_is_equal_to_the_Matrix_typedef dummy;
00414 return NULL;
00415 }
00416
00418 template <typename WrongMatrixType>
00419 static NearestNeighbourSearch* createKDTreeTreeHeap(const WrongMatrixType&, const Index dim = std::numeric_limits<Index>::max(), const unsigned creationOptionFlags = 0, const Parameters& additionalParameters = Parameters())
00420 {
00421 typedef int Please_make_sure_that_the_decltype_of_the_first_parameter_is_equal_to_the_Matrix_typedef[sizeof(WrongMatrixType) > 0 ? -1 : 1];
00422 Please_make_sure_that_the_decltype_of_the_first_parameter_is_equal_to_the_Matrix_typedef dummy;
00423 return NULL;
00424 }
00425
00427 virtual ~NearestNeighbourSearch() {}
00428
00429 protected:
00431 NearestNeighbourSearch(const CloudType& cloud, const Index dim, const unsigned creationOptionFlags);
00432
00434
00440 void checkSizesKnn(const Matrix& query, const IndexMatrix& indices, const Matrix& dists2, const Index k, const unsigned optionFlags, const Vector* maxRadii = 0) const;
00441 };
00442
00443
00444
00446 typedef NearestNeighbourSearch<float> NNSearchF;
00448 typedef NearestNeighbourSearch<double> NNSearchD;
00449
00451 }
00452
00453 #endif // __NABO_H