Nearest neighbour search interface, templatized on scalar type. More...
#include <nabo.h>
Public Types | |
typedef Cloud_T | CloudType |
a column-major Eigen matrix in which each column is a point; this matrix has dim rows More... | |
enum | CreationOptionFlags { TOUCH_STATISTICS = 1 } |
creation option More... | |
typedef int | Index |
an index to a Vector or a Matrix, for refering to data points More... | |
typedef Eigen::Matrix< Index, Eigen::Dynamic, Eigen::Dynamic > | IndexMatrix |
a matrix of indices to data points More... | |
typedef Eigen::Matrix< Index, Eigen::Dynamic, 1 > | IndexVector |
a vector of indices to data points More... | |
typedef 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 More... | |
enum | SearchOptionFlags { ALLOW_SELF_MATCH = 1, SORT_RESULTS = 2 } |
search option More... | |
enum | SearchType { BRUTE_FORCE = 0, KDTREE_LINEAR_HEAP, KDTREE_TREE_HEAP, KDTREE_CL_PT_IN_NODES, KDTREE_CL_PT_IN_LEAVES, BRUTE_FORCE_CL, SEARCH_TYPE_COUNT } |
type of search More... | |
typedef Eigen::Matrix< T, Eigen::Dynamic, 1 > | Vector |
an Eigen vector of type T, to hold the coordinates of a point More... | |
Public Member Functions | |
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 |
Find the k nearest neighbours for each point of query. More... | |
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 |
Find the k nearest neighbours for each point of query. More... | |
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 |
Find the k nearest neighbours of query. More... | |
virtual | ~NearestNeighbourSearch () |
virtual destructor More... | |
Static Public Member Functions | |
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()) |
Create a nearest-neighbour search. More... | |
template<typename WrongMatrixType > | |
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 supported. More... | |
static NearestNeighbourSearch * | createBruteForce (const CloudType &cloud, const Index dim=std::numeric_limits< Index >::max(), const unsigned creationOptionFlags=0) |
Create a nearest-neighbour search, using brute-force search, useful for comparison only. More... | |
template<typename WrongMatrixType > | |
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 supported. More... | |
static NearestNeighbourSearch * | createKDTreeLinearHeap (const CloudType &cloud, const Index dim=std::numeric_limits< Index >::max(), const unsigned creationOptionFlags=0, const Parameters &additionalParameters=Parameters()) |
Create a nearest-neighbour search, using a kd-tree with linear heap, good for small k (~up to 30) More... | |
template<typename WrongMatrixType > | |
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 supported. More... | |
static NearestNeighbourSearch * | createKDTreeTreeHeap (const CloudType &cloud, const Index dim=std::numeric_limits< Index >::max(), const unsigned creationOptionFlags=0, const Parameters &additionalParameters=Parameters()) |
Create a nearest-neighbour search, using a kd-tree with tree heap, good for large k (~from 30) More... | |
template<typename WrongMatrixType > | |
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 supported. More... | |
Public Attributes | |
const CloudType & | cloud |
the reference to the data-point cloud, which must remain valid during the lifetime of the NearestNeighbourSearch object More... | |
const unsigned | creationOptionFlags |
creation options More... | |
const Index | dim |
the dimensionality of the data-point cloud More... | |
const Vector | maxBound |
the high bound of the search space (axis-aligned bounding box) More... | |
const Vector | minBound |
the low bound of the search space (axis-aligned bounding box) More... | |
Static Public Attributes | |
static constexpr Index | InvalidIndex = invalidIndex<Index>() |
the invalid index More... | |
static constexpr T | InvalidValue = invalidValue<T>() |
the invalid value More... | |
Protected Member Functions | |
void | checkSizesKnn (const Matrix &query, const IndexMatrix &indices, const Matrix &dists2, const Index k, const unsigned optionFlags, const Vector *maxRadii=0) const |
Make sure that the output matrices have the right sizes. Throw an exception otherwise. More... | |
NearestNeighbourSearch (const CloudType &cloud, const Index dim, const unsigned creationOptionFlags) | |
constructor More... | |
Nearest neighbour search interface, templatized on scalar type.
typedef Cloud_T Nabo::NearestNeighbourSearch< T, Cloud_T >::CloudType |
typedef int Nabo::NearestNeighbourSearch< T, Cloud_T >::Index |
typedef Eigen::Matrix<Index, Eigen::Dynamic, Eigen::Dynamic> Nabo::NearestNeighbourSearch< T, Cloud_T >::IndexMatrix |
typedef Eigen::Matrix<Index, Eigen::Dynamic, 1> Nabo::NearestNeighbourSearch< T, Cloud_T >::IndexVector |
typedef Eigen::Matrix<T, Eigen::Dynamic, Eigen::Dynamic> Nabo::NearestNeighbourSearch< T, Cloud_T >::Matrix |
typedef Eigen::Matrix<T, Eigen::Dynamic, 1> Nabo::NearestNeighbourSearch< T, Cloud_T >::Vector |
enum Nabo::NearestNeighbourSearch::CreationOptionFlags |
enum Nabo::NearestNeighbourSearch::SearchOptionFlags |
enum Nabo::NearestNeighbourSearch::SearchType |
type of search
|
inlinevirtual |
|
protected |
constructor
Definition at line 69 of file nabo/nabo.cpp.
|
protected |
Make sure that the output matrices have the right sizes. Throw an exception otherwise.
query | query points |
k | number of nearest neighbour requested |
indices | indices of nearest neighbours, must be of size k x query.cols() |
dists2 | squared distances to nearest neighbours, must be of size k x query.cols() |
optionFlags | the options passed to knn() |
maxRadii | if non 0, maximum radii, must be of size k |
Definition at line 103 of file nabo/nabo.cpp.
|
static |
Create a nearest-neighbour search.
cloud | data-point cloud in which to search |
dim | number of dimensions to consider, must be lower or equal to cloud.rows() |
preferedType | type of search, one of SearchType |
creationOptionFlags | creation options, a bitwise OR of elements of CreationOptionFlags |
additionalParameters | additional parameters, currently only useful for KDTREE_ |
Definition at line 135 of file nabo/nabo.cpp.
|
inlinestatic |
|
static |
Create a nearest-neighbour search, using brute-force search, useful for comparison only.
This is an helper function, you can also use create() with BRUTE_FORCE as preferedType
cloud | data-point cloud in which to search |
dim | number of dimensions to consider, must be lower or equal to cloud.rows() |
creationOptionFlags | creation options, a bitwise OR of elements of CreationOptionFlags |
Definition at line 158 of file nabo/nabo.cpp.
|
inlinestatic |
|
static |
Create a nearest-neighbour search, using a kd-tree with linear heap, good for small k (~up to 30)
This is an helper function, you can also use create() with KDTREE_LINEAR_HEAP as preferedType
cloud | data-point cloud in which to search |
dim | number of dimensions to consider, must be lower or equal to cloud.rows() |
creationOptionFlags | creation options, a bitwise OR of elements of CreationOptionFlags |
additionalParameters | additional parameters |
Definition at line 166 of file nabo/nabo.cpp.
|
inlinestatic |
|
static |
Create a nearest-neighbour search, using a kd-tree with tree heap, good for large k (~from 30)
This is an helper function, you can also use create() with KDTREE_TREE_HEAP as preferedType
cloud | data-point cloud in which to search |
dim | number of dimensions to consider, must be lower or equal to cloud.rows() |
creationOptionFlags | creation options, a bitwise OR of elements of CreationOptionFlags |
additionalParameters | additional parameters |
Definition at line 174 of file nabo/nabo.cpp.
|
inlinestatic |
|
pure virtual |
Find the k nearest neighbours for each point of query.
If the search finds less than k points, the empty entries in dists2 will be filled with InvalidValue and the indices with InvalidIndex.
query | query points |
indices | indices of nearest neighbours, must be of size k x query.cols() |
dists2 | squared distances to nearest neighbours, must be of size k x query.cols() |
k | number of nearest neighbour requested |
epsilon | maximal ratio of error for approximate search, 0 for exact search; has no effect if the number of neighbour found is smaller than the number requested |
optionFlags | search options, a bitwise OR of elements of SearchOptionFlags |
maxRadius | maximum radius in which to search, can be used to prune search, is not affected by epsilon |
|
pure virtual |
Find the k nearest neighbours for each point of query.
If the search finds less than k points, the empty entries in dists2 will be filled with InvalidValue and the indices with InvalidIndex.
query | query points |
indices | indices of nearest neighbours, must be of size k x query.cols() |
dists2 | squared distances to nearest neighbours, must be of size k x query.cols() |
maxRadii | vector of maximum radii in which to search, used to prune search, is not affected by epsilon |
k | number of nearest neighbour requested |
epsilon | maximal ratio of error for approximate search, 0 for exact search; has no effect if the number of neighbour found is smaller than the number requested |
optionFlags | search options, a bitwise OR of elements of SearchOptionFlags |
unsigned long NearestNeighbourSearch::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 |
Find the k nearest neighbours of query.
If the search finds less than k points, the empty entries in dists2 will be filled with InvalidValue and the indices with InvalidIndex. If you must query more than one point at once, use the version of the knn() function taking matrices as input, because it is much faster.
query | query point |
indices | indices of nearest neighbours, must be of size k |
dists2 | squared distances to nearest neighbours, must be of size k |
k | number of nearest neighbour requested |
epsilon | maximal ratio of error for approximate search, 0 for exact search; has no effect if the number of neighbour found is smaller than the number requested |
optionFlags | search options, a bitwise OR of elements of SearchOptionFlags |
maxRadius | maximum radius in which to search, can be used to prune search, is not affected by epsilon |
Definition at line 83 of file nabo/nabo.cpp.
const CloudType& Nabo::NearestNeighbourSearch< T, Cloud_T >::cloud |
the reference to the data-point cloud, which must remain valid during the lifetime of the NearestNeighbourSearch object
const unsigned Nabo::NearestNeighbourSearch< T, Cloud_T >::creationOptionFlags |
const Index Nabo::NearestNeighbourSearch< T, Cloud_T >::dim |
|
staticconstexpr |
|
staticconstexpr |
const Vector Nabo::NearestNeighbourSearch< T, Cloud_T >::maxBound |
const Vector Nabo::NearestNeighbourSearch< T, Cloud_T >::minBound |