Nearest neighbour search interface, templatized on scalar type. More...
#include <nabo.h>
Public Types | |
enum | CreationOptionFlags { TOUCH_STATISTICS = 1 } |
creation option More... | |
typedef int | Index |
an index to a Vector or a Matrix, for refering to data points | |
typedef Eigen::Matrix< Index, Eigen::Dynamic, Eigen::Dynamic > | IndexMatrix |
a matrix of indices to data points | |
typedef Eigen::Matrix< Index, Eigen::Dynamic, 1 > | IndexVector |
a vector of indices to data points | |
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 | |
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 | |
Public Member Functions | |
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. | |
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. | |
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. | |
virtual | ~NearestNeighbourSearch () |
virtual destructor | |
Static Public Member Functions | |
static NearestNeighbourSearch * | create (const Matrix &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. | |
static NearestNeighbourSearch * | createBruteForce (const Matrix &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. | |
static NearestNeighbourSearch * | createKDTreeLinearHeap (const Matrix &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) | |
static NearestNeighbourSearch * | createKDTreeTreeHeap (const Matrix &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) | |
Public Attributes | |
const Matrix & | cloud |
the reference to the data-point cloud, which must remain valid during the lifetime of the NearestNeighbourSearch object | |
const unsigned | creationOptionFlags |
creation options | |
const Index | dim |
the dimensionality of the data-point cloud | |
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) | |
Protected Member Functions | |
void | checkSizesKnn (const Matrix &query, const IndexMatrix &indices, const Matrix &dists2, const Index k, const Vector *maxRadii=0) const |
Make sure that the output matrices have the right sizes. Throw an exception otherwise. | |
NearestNeighbourSearch (const Matrix &cloud, const Index dim, const unsigned creationOptionFlags) | |
constructor |
Nearest neighbour search interface, templatized on scalar type.
typedef int Nabo::NearestNeighbourSearch< T >::Index |
an index to a Vector or a Matrix, for refering to data points
Reimplemented in Nabo::KDTreeUnbalancedPtInLeavesImplicitBoundsStackOpt< T, Heap >, and Nabo::BruteForceSearch< T >.
typedef Eigen::Matrix<Index, Eigen::Dynamic, Eigen::Dynamic> Nabo::NearestNeighbourSearch< T >::IndexMatrix |
a matrix of indices to data points
Reimplemented in Nabo::KDTreeUnbalancedPtInLeavesImplicitBoundsStackOpt< T, Heap >, and Nabo::BruteForceSearch< T >.
typedef Eigen::Matrix<Index, Eigen::Dynamic, 1> Nabo::NearestNeighbourSearch< T >::IndexVector |
a vector of indices to data points
Reimplemented in Nabo::KDTreeUnbalancedPtInLeavesImplicitBoundsStackOpt< T, Heap >, and Nabo::BruteForceSearch< T >.
typedef Eigen::Matrix<T, Eigen::Dynamic, Eigen::Dynamic> Nabo::NearestNeighbourSearch< T >::Matrix |
a column-major Eigen matrix in which each column is a point; this matrix has dim rows
Reimplemented in Nabo::KDTreeUnbalancedPtInLeavesImplicitBoundsStackOpt< T, Heap >, and Nabo::BruteForceSearch< T >.
typedef Eigen::Matrix<T, Eigen::Dynamic, 1> Nabo::NearestNeighbourSearch< T >::Vector |
an Eigen vector of type T, to hold the coordinates of a point
Reimplemented in Nabo::KDTreeUnbalancedPtInLeavesImplicitBoundsStackOpt< T, Heap >, and Nabo::BruteForceSearch< T >.
enum Nabo::NearestNeighbourSearch::CreationOptionFlags |
enum Nabo::NearestNeighbourSearch::SearchOptionFlags |
enum Nabo::NearestNeighbourSearch::SearchType |
type of search
virtual Nabo::NearestNeighbourSearch< T >::~NearestNeighbourSearch | ( | ) | [inline, virtual] |
Nabo::NearestNeighbourSearch< T >::NearestNeighbourSearch | ( | const Matrix & | cloud, |
const Index | dim, | ||
const unsigned | creationOptionFlags | ||
) | [protected] |
void Nabo::NearestNeighbourSearch< T >::checkSizesKnn | ( | const Matrix & | query, |
const IndexMatrix & | indices, | ||
const Matrix & | dists2, | ||
const Index | k, | ||
const Vector * | maxRadii = 0 |
||
) | const [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() |
maxRadii | if non 0, maximum radii, must be of size k |
NearestNeighbourSearch< T > * Nabo::NearestNeighbourSearch< T >::create | ( | const Matrix & | cloud, |
const Index | dim = std::numeric_limits<Index>::max() , |
||
const SearchType | preferedType = KDTREE_LINEAR_HEAP , |
||
const unsigned | creationOptionFlags = 0 , |
||
const Parameters & | additionalParameters = Parameters() |
||
) | [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_ |
NearestNeighbourSearch< T > * Nabo::NearestNeighbourSearch< T >::createBruteForce | ( | const Matrix & | cloud, |
const Index | dim = std::numeric_limits<Index>::max() , |
||
const unsigned | creationOptionFlags = 0 |
||
) | [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 |
NearestNeighbourSearch< T > * Nabo::NearestNeighbourSearch< T >::createKDTreeLinearHeap | ( | const Matrix & | cloud, |
const Index | dim = std::numeric_limits<Index>::max() , |
||
const unsigned | creationOptionFlags = 0 , |
||
const Parameters & | additionalParameters = Parameters() |
||
) | [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 |
NearestNeighbourSearch< T > * Nabo::NearestNeighbourSearch< T >::createKDTreeTreeHeap | ( | const Matrix & | cloud, |
const Index | dim = std::numeric_limits<Index>::max() , |
||
const unsigned | creationOptionFlags = 0 , |
||
const Parameters & | additionalParameters = Parameters() |
||
) | [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 |
unsigned long Nabo::NearestNeighbourSearch< T >::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 infinity and the indices with 0. 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 percentage of error for approximate search, 0 for exact search |
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 |
virtual unsigned long Nabo::NearestNeighbourSearch< T >::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 [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 infinity and the indices with 0.
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 percentage of error for approximate search, 0 for exact search |
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 |
Implemented in Nabo::KDTreeUnbalancedPtInLeavesImplicitBoundsStackOpt< T, Heap >, and Nabo::BruteForceSearch< T >.
virtual unsigned long Nabo::NearestNeighbourSearch< T >::knn | ( | const Matrix & | query, |
IndexMatrix & | indices, | ||
Matrix & | dists2, | ||
const Vector & | maxRadii, | ||
const Index | k = 1 , |
||
const T | epsilon = 0 , |
||
const unsigned | optionFlags = 0 |
||
) | const [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 infinity and the indices with 0.
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 percentage of error for approximate search, 0 for exact search |
optionFlags | search options, a bitwise OR of elements of SearchOptionFlags |
Implemented in Nabo::KDTreeUnbalancedPtInLeavesImplicitBoundsStackOpt< T, Heap >, and Nabo::BruteForceSearch< T >.
const Matrix& Nabo::NearestNeighbourSearch< 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 >::creationOptionFlags |
const Index Nabo::NearestNeighbourSearch< T >::dim |
const Vector Nabo::NearestNeighbourSearch< T >::maxBound |
const Vector Nabo::NearestNeighbourSearch< T >::minBound |