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 <boost/any.hpp>
00045
00206
00207 namespace Nabo
00208 {
00210
00211
00213 #define NABO_VERSION "1.0.6"
00214
00215 #define NABO_VERSION_INT 10006
00216
00218 struct Parameters: public std::map<std::string, boost::any>
00219 {
00221 Parameters(){}
00223
00226 Parameters(const std::string& key, const boost::any& value){(*this)[key] = value;}
00228
00232 template<typename T>
00233 T get(const std::string& key, const T& defaultValue) const
00234 {
00235 const_iterator it(find(key));
00236 if (it != end())
00237 return boost::any_cast<T>(it->second);
00238 else
00239 return defaultValue;
00240 }
00241 };
00242
00244 template<typename T, typename Cloud_T = Eigen::Matrix<T, Eigen::Dynamic, Eigen::Dynamic> >
00245 struct NearestNeighbourSearch
00246 {
00248 typedef typename Eigen::Matrix<T, Eigen::Dynamic, 1> Vector;
00250 typedef typename Eigen::Matrix<T, Eigen::Dynamic, Eigen::Dynamic> Matrix;
00252 typedef Cloud_T CloudType;
00254 typedef int Index;
00256 typedef typename Eigen::Matrix<Index, Eigen::Dynamic, 1> IndexVector;
00258 typedef typename Eigen::Matrix<Index, Eigen::Dynamic, Eigen::Dynamic> IndexMatrix;
00259
00261 const CloudType& cloud;
00263 const Index dim;
00265 const unsigned creationOptionFlags;
00267 const Vector minBound;
00269 const Vector maxBound;
00270
00272 enum SearchType
00273 {
00274 BRUTE_FORCE = 0,
00275 KDTREE_LINEAR_HEAP,
00276 KDTREE_TREE_HEAP,
00277 KDTREE_CL_PT_IN_NODES,
00278 KDTREE_CL_PT_IN_LEAVES,
00279 BRUTE_FORCE_CL,
00280 SEARCH_TYPE_COUNT
00281 };
00282
00284 enum CreationOptionFlags
00285 {
00286 TOUCH_STATISTICS = 1
00287 };
00288
00290 enum SearchOptionFlags
00291 {
00292 ALLOW_SELF_MATCH = 1,
00293 SORT_RESULTS = 2
00294 };
00295
00297
00307 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;
00308
00310
00320 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;
00321
00323
00333 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;
00334
00336
00342 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());
00343
00345
00350 static NearestNeighbourSearch* createBruteForce(const CloudType& cloud, const Index dim = std::numeric_limits<Index>::max(), const unsigned creationOptionFlags = 0);
00351
00353
00359 static NearestNeighbourSearch* createKDTreeLinearHeap(const CloudType& cloud, const Index dim = std::numeric_limits<Index>::max(), const unsigned creationOptionFlags = 0, const Parameters& additionalParameters = Parameters());
00360
00362
00368 static NearestNeighbourSearch* createKDTreeTreeHeap(const CloudType& cloud, const Index dim = std::numeric_limits<Index>::max(), const unsigned creationOptionFlags = 0, const Parameters& additionalParameters = Parameters());
00369
00370
00371
00373 template <typename WrongMatrixType>
00374 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())
00375 {
00376 typedef int Please_make_sure_that_the_decltype_of_the_first_parameter_is_equal_to_the_Matrix_typedef[sizeof(WrongMatrixType) > 0 ? -1 : 1];
00377 Please_make_sure_that_the_decltype_of_the_first_parameter_is_equal_to_the_Matrix_typedef dummy;
00378 return NULL;
00379 }
00380
00382 template <typename WrongMatrixType>
00383 static NearestNeighbourSearch* createBruteForce(const WrongMatrixType& cloud, const Index dim = std::numeric_limits<Index>::max(), const unsigned creationOptionFlags = 0)
00384 {
00385 typedef int Please_make_sure_that_the_decltype_of_the_first_parameter_is_equal_to_the_Matrix_typedef[sizeof(WrongMatrixType) > 0 ? -1 : 1];
00386 Please_make_sure_that_the_decltype_of_the_first_parameter_is_equal_to_the_Matrix_typedef dummy;
00387 return NULL;
00388 }
00389
00391 template <typename WrongMatrixType>
00392 static NearestNeighbourSearch* createKDTreeLinearHeap(const WrongMatrixType& cloud, const Index dim = std::numeric_limits<Index>::max(), 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* createKDTreeTreeHeap(const WrongMatrixType&, const Index dim = std::numeric_limits<Index>::max(), const unsigned creationOptionFlags = 0, const Parameters& additionalParameters = Parameters())
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 virtual ~NearestNeighbourSearch() {}
00410
00411 protected:
00413 NearestNeighbourSearch(const CloudType& cloud, const Index dim, const unsigned creationOptionFlags);
00414
00416
00422 void checkSizesKnn(const Matrix& query, const IndexMatrix& indices, const Matrix& dists2, const Index k, const unsigned optionFlags, const Vector* maxRadii = 0) const;
00423 };
00424
00425
00426
00428 typedef NearestNeighbourSearch<float> NNSearchF;
00430 typedef NearestNeighbourSearch<double> NNSearchD;
00431
00433 }
00434
00435 #endif // __NABO_H