36 #if EIGEN_VERSION_AT_LEAST(2,92,0) 40 #include "Eigen/Array" 211 #define NABO_VERSION "1.0.7" 212 #define NABO_VERSION_INT 10007 216 template <
typename IndexType>
218 static_assert(std::is_integral<IndexType>::value,
"");
219 return std::is_unsigned<IndexType>::value ? std::numeric_limits<IndexType>::max() : IndexType(-1);
222 template <
typename ValueType>
224 static_assert(std::is_floating_point<ValueType>::value,
"");
225 return std::numeric_limits<ValueType>::infinity();
246 T
get(
const std::string& key,
const T& defaultValue)
const 248 const_iterator it(find(key));
257 template<
typename T,
typename Cloud_T = Eigen::Matrix<T, Eigen::Dynamic, Eigen::Dynamic> >
261 typedef typename Eigen::Matrix<T, Eigen::Dynamic, 1>
Vector;
263 typedef typename Eigen::Matrix<T, Eigen::Dynamic, Eigen::Dynamic>
Matrix;
269 typedef typename Eigen::Matrix<Index, Eigen::Dynamic, 1>
IndexVector;
271 typedef typename Eigen::Matrix<Index, Eigen::Dynamic, Eigen::Dynamic>
IndexMatrix;
285 static constexpr Index InvalidIndex = invalidIndex<Index>();
287 static constexpr T InvalidValue = invalidValue<T>();
310 ALLOW_SELF_MATCH = 1,
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;
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;
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;
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());
368 static NearestNeighbourSearch* createBruteForce(
const CloudType& cloud,
const Index dim = std::numeric_limits<Index>::max(),
const unsigned creationOptionFlags = 0);
377 static NearestNeighbourSearch* createKDTreeLinearHeap(
const CloudType& cloud,
const Index dim = std::numeric_limits<Index>::max(),
const unsigned creationOptionFlags = 0,
const Parameters& additionalParameters =
Parameters());
386 static NearestNeighbourSearch* createKDTreeTreeHeap(
const CloudType& cloud,
const Index dim = std::numeric_limits<Index>::max(),
const unsigned creationOptionFlags = 0,
const Parameters& additionalParameters =
Parameters());
391 template <
typename WrongMatrixType>
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;
400 template <
typename WrongMatrixType>
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;
409 template <
typename WrongMatrixType>
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;
418 template <
typename WrongMatrixType>
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;
440 void checkSizesKnn(
const Matrix& query,
const IndexMatrix& indices,
const Matrix& dists2,
const Index k,
const unsigned optionFlags,
const Vector* maxRadii = 0)
const;
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 ...
Parameters()
Create an empty parameter vector.
const unsigned creationOptionFlags
creation options
virtual ~NearestNeighbourSearch()
virtual destructor
kd-tree with tree heap, good for large k (~from 30)
kd-tree using openCL, pt in nodes, only available if OpenCL enabled, UNSTABLE API ...
Nearest neighbour search interface, templatized on scalar type.
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...
constexpr ValueType invalidValue()
ValueType any_cast(const any &operand)
Performs *any_cast<add_const_t<remove_reference_t<ValueType>>>(&operand), or throws bad_any_cast on f...
SearchOptionFlags
search option
const CloudType & cloud
the reference to the data-point cloud, which must remain valid during the lifetime of the NearestNeig...
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...
Eigen::Matrix< T, Eigen::Dynamic, 1 > Vector
an Eigen vector of type T, to hold the coordinates of a point
NearestNeighbourSearch< double > NNSearchD
nearest neighbour search with scalars of type double
int Index
an index to a Vector or a Matrix, for refering to data points
Eigen::Matrix< Index, Eigen::Dynamic, Eigen::Dynamic > IndexMatrix
a matrix of indices to data points
CreationOptionFlags
creation option
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...
brute-force using openCL, only available if OpenCL enabled, UNSTABLE API
Eigen::Matrix< Index, Eigen::Dynamic, 1 > IndexVector
a vector of indices to data points
const Vector maxBound
the high bound of the search space (axis-aligned bounding box)
const Vector minBound
the low bound of the search space (axis-aligned bounding box)
kd-tree using openCL, pt in leaves, only available if OpenCL enabled, UNSTABLE API ...
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...
constexpr IndexType invalidIndex()
const Index dim
the dimensionality of the data-point cloud
Cloud_T CloudType
a column-major Eigen matrix in which each column is a point; this matrix has dim rows ...
kd-tree with linear heap, good for small k (~up to 30)
Parameters(const std::string &key, const linb::any &value)
Create a parameter vector with a single entry.
NearestNeighbourSearch< float > NNSearchF
nearest neighbour search with scalars of type float