Public Types | Public Member Functions | Static Public Member Functions | Public Attributes | Static Public Attributes | Protected Member Functions
Nabo::NearestNeighbourSearch< T, Cloud_T > Struct Template Reference

Nearest neighbour search interface, templatized on scalar type. More...

#include <nabo.h>

List of all members.

Public Types

typedef Cloud_T CloudType
 a column-major Eigen matrix in which each column is a point; this matrix has dim rows
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 NearestNeighbourSearchcreate (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.
template<typename WrongMatrixType >
static NearestNeighbourSearchcreate (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.
static NearestNeighbourSearchcreateBruteForce (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.
template<typename WrongMatrixType >
static NearestNeighbourSearchcreateBruteForce (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.
static NearestNeighbourSearchcreateKDTreeLinearHeap (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)
template<typename WrongMatrixType >
static NearestNeighbourSearchcreateKDTreeLinearHeap (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.
static NearestNeighbourSearchcreateKDTreeTreeHeap (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)
template<typename WrongMatrixType >
static NearestNeighbourSearchcreateKDTreeTreeHeap (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.

Public Attributes

const CloudTypecloud
 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)

Static Public Attributes

static constexpr Index InvalidIndex = invalidIndex<Index>()
 the invalid index
static constexpr T InvalidValue = invalidValue<T>()
 the invalid value

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.
 NearestNeighbourSearch (const CloudType &cloud, const Index dim, const unsigned creationOptionFlags)
 constructor

Detailed Description

template<typename T, typename Cloud_T = Eigen::Matrix<T, Eigen::Dynamic, Eigen::Dynamic>>
struct Nabo::NearestNeighbourSearch< T, Cloud_T >

Nearest neighbour search interface, templatized on scalar type.

Definition at line 258 of file nabo.h.


Member Typedef Documentation

template<typename T, typename Cloud_T = Eigen::Matrix<T, Eigen::Dynamic, Eigen::Dynamic>>
typedef Cloud_T Nabo::NearestNeighbourSearch< T, Cloud_T >::CloudType

a column-major Eigen matrix in which each column is a point; this matrix has dim rows

Definition at line 265 of file nabo.h.

template<typename T, typename Cloud_T = Eigen::Matrix<T, Eigen::Dynamic, Eigen::Dynamic>>
typedef int Nabo::NearestNeighbourSearch< T, Cloud_T >::Index
template<typename T, typename Cloud_T = Eigen::Matrix<T, Eigen::Dynamic, Eigen::Dynamic>>
typedef Eigen::Matrix<Index, Eigen::Dynamic, Eigen::Dynamic> Nabo::NearestNeighbourSearch< T, Cloud_T >::IndexMatrix
template<typename T, typename Cloud_T = Eigen::Matrix<T, Eigen::Dynamic, Eigen::Dynamic>>
typedef Eigen::Matrix<Index, Eigen::Dynamic, 1> Nabo::NearestNeighbourSearch< T, Cloud_T >::IndexVector
template<typename T, typename Cloud_T = Eigen::Matrix<T, Eigen::Dynamic, Eigen::Dynamic>>
typedef Eigen::Matrix<T, Eigen::Dynamic, Eigen::Dynamic> Nabo::NearestNeighbourSearch< T, Cloud_T >::Matrix
template<typename T, typename Cloud_T = Eigen::Matrix<T, Eigen::Dynamic, Eigen::Dynamic>>
typedef Eigen::Matrix<T, Eigen::Dynamic, 1> Nabo::NearestNeighbourSearch< T, Cloud_T >::Vector

Member Enumeration Documentation

template<typename T, typename Cloud_T = Eigen::Matrix<T, Eigen::Dynamic, Eigen::Dynamic>>
enum Nabo::NearestNeighbourSearch::CreationOptionFlags

creation option

Enumerator:
TOUCH_STATISTICS 

perform statistics on the number of points touched

Definition at line 302 of file nabo.h.

template<typename T, typename Cloud_T = Eigen::Matrix<T, Eigen::Dynamic, Eigen::Dynamic>>
enum Nabo::NearestNeighbourSearch::SearchOptionFlags

search option

Enumerator:
ALLOW_SELF_MATCH 

allows the return of the same point as the query, if this point is in the data cloud; forbidden by default

SORT_RESULTS 

sort points by distances, when k > 1; do not sort by default

Definition at line 308 of file nabo.h.

template<typename T, typename Cloud_T = Eigen::Matrix<T, Eigen::Dynamic, Eigen::Dynamic>>
enum Nabo::NearestNeighbourSearch::SearchType

type of search

Enumerator:
BRUTE_FORCE 

brute force, check distance to every point in the data

KDTREE_LINEAR_HEAP 

kd-tree with linear heap, good for small k (~up to 30)

KDTREE_TREE_HEAP 

kd-tree with tree heap, good for large k (~from 30)

KDTREE_CL_PT_IN_NODES 

kd-tree using openCL, pt in nodes, only available if OpenCL enabled, UNSTABLE API

KDTREE_CL_PT_IN_LEAVES 

kd-tree using openCL, pt in leaves, only available if OpenCL enabled, UNSTABLE API

BRUTE_FORCE_CL 

brute-force using openCL, only available if OpenCL enabled, UNSTABLE API

SEARCH_TYPE_COUNT 

number of search types

Definition at line 290 of file nabo.h.


Constructor & Destructor Documentation

template<typename T, typename Cloud_T = Eigen::Matrix<T, Eigen::Dynamic, Eigen::Dynamic>>
virtual Nabo::NearestNeighbourSearch< T, Cloud_T >::~NearestNeighbourSearch ( ) [inline, virtual]

virtual destructor

Definition at line 427 of file nabo.h.

template<typename T , typename CloudType >
NearestNeighbourSearch::NearestNeighbourSearch ( const CloudType cloud,
const Index  dim,
const unsigned  creationOptionFlags 
) [protected]

constructor

Definition at line 69 of file nabo/nabo.cpp.


Member Function Documentation

template<typename T , typename CloudType >
void NearestNeighbourSearch::checkSizesKnn ( const Matrix query,
const IndexMatrix indices,
const Matrix dists2,
const Index  k,
const unsigned  optionFlags,
const Vector maxRadii = 0 
) const [protected]

Make sure that the output matrices have the right sizes. Throw an exception otherwise.

Parameters:
queryquery points
knumber of nearest neighbour requested
indicesindices of nearest neighbours, must be of size k x query.cols()
dists2squared distances to nearest neighbours, must be of size k x query.cols()
optionFlagsthe options passed to knn()
maxRadiiif non 0, maximum radii, must be of size k

Definition at line 103 of file nabo/nabo.cpp.

template<typename T , typename CloudType >
NearestNeighbourSearch< T, CloudType > * 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() 
) [static]

Create a nearest-neighbour search.

Parameters:
clouddata-point cloud in which to search
dimnumber of dimensions to consider, must be lower or equal to cloud.rows()
preferedTypetype of search, one of SearchType
creationOptionFlagscreation options, a bitwise OR of elements of CreationOptionFlags
additionalParametersadditional parameters, currently only useful for KDTREE_
Returns:
an object on which to run nearest neighbour queries

Definition at line 135 of file nabo/nabo.cpp.

template<typename T, typename Cloud_T = Eigen::Matrix<T, Eigen::Dynamic, Eigen::Dynamic>>
template<typename WrongMatrixType >
static NearestNeighbourSearch* Nabo::NearestNeighbourSearch< T, Cloud_T >::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() 
) [inline, static]

Prevent creation of trees with the wrong matrix type. Currently only dynamic size matrices are supported.

Definition at line 392 of file nabo.h.

template<typename T , typename CloudType >
NearestNeighbourSearch< T, CloudType > * NearestNeighbourSearch::createBruteForce ( const CloudType 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

Parameters:
clouddata-point cloud in which to search
dimnumber of dimensions to consider, must be lower or equal to cloud.rows()
creationOptionFlagscreation options, a bitwise OR of elements of CreationOptionFlags
Returns:
an object on which to run nearest neighbour queries

Definition at line 158 of file nabo/nabo.cpp.

template<typename T, typename Cloud_T = Eigen::Matrix<T, Eigen::Dynamic, Eigen::Dynamic>>
template<typename WrongMatrixType >
static NearestNeighbourSearch* Nabo::NearestNeighbourSearch< T, Cloud_T >::createBruteForce ( const WrongMatrixType &  cloud,
const Index  dim = std::numeric_limits<Index>::max(),
const unsigned  creationOptionFlags = 0 
) [inline, static]

Prevent creation of trees with the wrong matrix type. Currently only dynamic size matrices are supported.

Definition at line 401 of file nabo.h.

template<typename T , typename CloudType >
NearestNeighbourSearch< T, CloudType > * NearestNeighbourSearch::createKDTreeLinearHeap ( const CloudType 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

Parameters:
clouddata-point cloud in which to search
dimnumber of dimensions to consider, must be lower or equal to cloud.rows()
creationOptionFlagscreation options, a bitwise OR of elements of CreationOptionFlags
additionalParametersadditional parameters
Returns:
an object on which to run nearest neighbour queries

Definition at line 166 of file nabo/nabo.cpp.

template<typename T, typename Cloud_T = Eigen::Matrix<T, Eigen::Dynamic, Eigen::Dynamic>>
template<typename WrongMatrixType >
static NearestNeighbourSearch* Nabo::NearestNeighbourSearch< T, Cloud_T >::createKDTreeLinearHeap ( const WrongMatrixType &  cloud,
const Index  dim = std::numeric_limits<Index>::max(),
const unsigned  creationOptionFlags = 0,
const Parameters additionalParameters = Parameters() 
) [inline, static]

Prevent creation of trees with the wrong matrix type. Currently only dynamic size matrices are supported.

Definition at line 410 of file nabo.h.

template<typename T , typename CloudType >
NearestNeighbourSearch< T, CloudType > * NearestNeighbourSearch::createKDTreeTreeHeap ( const CloudType 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

Parameters:
clouddata-point cloud in which to search
dimnumber of dimensions to consider, must be lower or equal to cloud.rows()
creationOptionFlagscreation options, a bitwise OR of elements of CreationOptionFlags
additionalParametersadditional parameters
Returns:
an object on which to run nearest neighbour queries

Definition at line 174 of file nabo/nabo.cpp.

template<typename T, typename Cloud_T = Eigen::Matrix<T, Eigen::Dynamic, Eigen::Dynamic>>
template<typename WrongMatrixType >
static NearestNeighbourSearch* Nabo::NearestNeighbourSearch< T, Cloud_T >::createKDTreeTreeHeap ( const WrongMatrixType &  ,
const Index  dim = std::numeric_limits<Index>::max(),
const unsigned  creationOptionFlags = 0,
const Parameters additionalParameters = Parameters() 
) [inline, static]

Prevent creation of trees with the wrong matrix type. Currently only dynamic size matrices are supported.

Definition at line 419 of file nabo.h.

template<typename T, typename CloudType >
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.

Parameters:
queryquery point
indicesindices of nearest neighbours, must be of size k
dists2squared distances to nearest neighbours, must be of size k
knumber of nearest neighbour requested
epsilonmaximal 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
optionFlagssearch options, a bitwise OR of elements of SearchOptionFlags
maxRadiusmaximum radius in which to search, can be used to prune search, is not affected by epsilon
Returns:
if creationOptionFlags contains TOUCH_STATISTICS, return the number of point touched, otherwise return 0

Definition at line 83 of file nabo/nabo.cpp.

template<typename T, typename Cloud_T = Eigen::Matrix<T, Eigen::Dynamic, Eigen::Dynamic>>
virtual unsigned long Nabo::NearestNeighbourSearch< T, Cloud_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 InvalidValue and the indices with InvalidIndex.

Parameters:
queryquery points
indicesindices of nearest neighbours, must be of size k x query.cols()
dists2squared distances to nearest neighbours, must be of size k x query.cols()
knumber of nearest neighbour requested
epsilonmaximal 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
optionFlagssearch options, a bitwise OR of elements of SearchOptionFlags
maxRadiusmaximum radius in which to search, can be used to prune search, is not affected by epsilon
Returns:
if creationOptionFlags contains TOUCH_STATISTICS, return the number of point touched, otherwise return 0
template<typename T, typename Cloud_T = Eigen::Matrix<T, Eigen::Dynamic, Eigen::Dynamic>>
virtual unsigned long Nabo::NearestNeighbourSearch< T, Cloud_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 InvalidValue and the indices with InvalidIndex.

Parameters:
queryquery points
indicesindices of nearest neighbours, must be of size k x query.cols()
dists2squared distances to nearest neighbours, must be of size k x query.cols()
maxRadiivector of maximum radii in which to search, used to prune search, is not affected by epsilon
knumber of nearest neighbour requested
epsilonmaximal 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
optionFlagssearch options, a bitwise OR of elements of SearchOptionFlags
Returns:
if creationOptionFlags contains TOUCH_STATISTICS, return the number of point touched, otherwise return 0

Member Data Documentation

template<typename T, typename Cloud_T = Eigen::Matrix<T, Eigen::Dynamic, Eigen::Dynamic>>
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

Definition at line 274 of file nabo.h.

template<typename T, typename Cloud_T = Eigen::Matrix<T, Eigen::Dynamic, Eigen::Dynamic>>
const unsigned Nabo::NearestNeighbourSearch< T, Cloud_T >::creationOptionFlags

creation options

Definition at line 278 of file nabo.h.

template<typename T, typename Cloud_T = Eigen::Matrix<T, Eigen::Dynamic, Eigen::Dynamic>>
const Index Nabo::NearestNeighbourSearch< T, Cloud_T >::dim

the dimensionality of the data-point cloud

Definition at line 276 of file nabo.h.

template<typename T, typename Cloud_T = Eigen::Matrix<T, Eigen::Dynamic, Eigen::Dynamic>>
constexpr Index Nabo::NearestNeighbourSearch< T, Cloud_T >::InvalidIndex = invalidIndex<Index>() [static]

the invalid index

Definition at line 285 of file nabo.h.

template<typename T, typename Cloud_T = Eigen::Matrix<T, Eigen::Dynamic, Eigen::Dynamic>>
constexpr T Nabo::NearestNeighbourSearch< T, Cloud_T >::InvalidValue = invalidValue<T>() [static]

the invalid value

Definition at line 287 of file nabo.h.

template<typename T, typename Cloud_T = Eigen::Matrix<T, Eigen::Dynamic, Eigen::Dynamic>>
const Vector Nabo::NearestNeighbourSearch< T, Cloud_T >::maxBound

the high bound of the search space (axis-aligned bounding box)

Definition at line 282 of file nabo.h.

template<typename T, typename Cloud_T = Eigen::Matrix<T, Eigen::Dynamic, Eigen::Dynamic>>
const Vector Nabo::NearestNeighbourSearch< T, Cloud_T >::minBound

the low bound of the search space (axis-aligned bounding box)

Definition at line 280 of file nabo.h.


The documentation for this struct was generated from the following files:


libnabo
Author(s): Stéphane Magnenat
autogenerated on Sun Feb 10 2019 03:52:20