KDTree, unbalanced, points in leaves, stack, implicit bounds, ANN_KD_SL_MIDPT, optimised implementation. More...
#include <nabo_private.h>

Classes | |
| struct | BucketEntry |
| entry in a bucket More... | |
| struct | Node |
| search node More... | |
Public Types | |
| typedef NearestNeighbourSearch < T, CloudType >::Index | Index |
| an index to a Vector or a Matrix, for refering to data points | |
| typedef NearestNeighbourSearch < T, CloudType >::IndexMatrix | IndexMatrix |
| a matrix of indices to data points | |
| typedef NearestNeighbourSearch < T, CloudType >::IndexVector | IndexVector |
| a vector of indices to data points | |
| typedef NearestNeighbourSearch < T, CloudType >::Matrix | Matrix |
| a column-major Eigen matrix in which each column is a point; this matrix has dim rows | |
| typedef NearestNeighbourSearch < T, CloudType >::Vector | Vector |
| an Eigen vector of type T, to hold the coordinates of a point | |
Protected Types | |
| typedef std::vector< BucketEntry > | Buckets |
| bucket data | |
| typedef std::vector< Index > | BuildPoints |
| indices of points during kd-tree construction | |
| typedef BuildPoints::const_iterator | BuildPointsCstIt |
| const-iterator to indices of points during kd-tree construction | |
| typedef BuildPoints::iterator | BuildPointsIt |
| iterator to indices of points during kd-tree construction | |
| typedef std::vector< Node > | Nodes |
| dense vector of search nodes, provides better memory performances than many small objects | |
Protected Member Functions | |
| uint32_t | createDimChildBucketSize (const uint32_t dim, const uint32_t childIndex) const |
| create the compound index containing the dimension and the index of the child or the bucket size | |
| uint32_t | getChildBucketSize (const uint32_t dimChildBucketSize) const |
| get the child index or the bucket size out of the coumpount index | |
| uint32_t | getDim (const uint32_t dimChildBucketSize) const |
| get the dimension out of the compound index | |
Protected Attributes | |
| Buckets | buckets |
| buckets | |
| const unsigned | bucketSize |
| size of bucket | |
| const uint32_t | dimBitCount |
| number of bits required to store dimension index + number of dimensions | |
| const uint32_t | dimMask |
| mask to access dim | |
| Nodes | nodes |
| search nodes | |
| std::pair< T, T > | getBounds (const BuildPointsIt first, const BuildPointsIt last, const unsigned dim) |
| return the bounds of points from [first..last[ on dimension dim | |
| unsigned | buildNodes (const BuildPointsIt first, const BuildPointsIt last, const Vector minValues, const Vector maxValues) |
| construct nodes for points [first..last[ inside the hyperrectangle [minValues..maxValues] | |
| unsigned long | onePointKnn (const Matrix &query, IndexMatrix &indices, Matrix &dists2, int i, Heap &heap, std::vector< T > &off, const T maxError, const T maxRadius2, const bool allowSelfMatch, const bool collectStatistics, const bool sortResults) const |
| search one point, call recurseKnn with the correct template parameters | |
| template<bool allowSelfMatch, bool collectStatistics> | |
| unsigned long | recurseKnn (const T *query, const unsigned n, T rd, Heap &heap, std::vector< T > &off, const T maxError, const T maxRadius2) const |
| recursive search, strongly inspired by ANN and [Arya & Mount, Algorithms for fast vector quantization, 1993] | |
| KDTreeUnbalancedPtInLeavesImplicitBoundsStackOpt (const CloudType &cloud, const Index dim, const unsigned creationOptionFlags, const Parameters &additionalParameters) | |
| constructor, calls NearestNeighbourSearch<T>(cloud) | |
| virtual unsigned long | knn (const Matrix &query, IndexMatrix &indices, Matrix &dists2, const Index k, const T epsilon, const unsigned optionFlags, const T maxRadius) const |
| 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 |
KDTree, unbalanced, points in leaves, stack, implicit bounds, ANN_KD_SL_MIDPT, optimised implementation.
Definition at line 98 of file nabo_private.h.
typedef std::vector<BucketEntry> Nabo::KDTreeUnbalancedPtInLeavesImplicitBoundsStackOpt< T, Heap, CloudType >::Buckets [protected] |
bucket data
Definition at line 175 of file nabo_private.h.
typedef std::vector<Index> Nabo::KDTreeUnbalancedPtInLeavesImplicitBoundsStackOpt< T, Heap, CloudType >::BuildPoints [protected] |
indices of points during kd-tree construction
Definition at line 115 of file nabo_private.h.
typedef BuildPoints::const_iterator Nabo::KDTreeUnbalancedPtInLeavesImplicitBoundsStackOpt< T, Heap, CloudType >::BuildPointsCstIt [protected] |
const-iterator to indices of points during kd-tree construction
Definition at line 119 of file nabo_private.h.
typedef BuildPoints::iterator Nabo::KDTreeUnbalancedPtInLeavesImplicitBoundsStackOpt< T, Heap, CloudType >::BuildPointsIt [protected] |
iterator to indices of points during kd-tree construction
Definition at line 117 of file nabo_private.h.
| typedef NearestNeighbourSearch<T, CloudType>::Index Nabo::KDTreeUnbalancedPtInLeavesImplicitBoundsStackOpt< T, Heap, CloudType >::Index |
an index to a Vector or a Matrix, for refering to data points
Reimplemented from Nabo::NearestNeighbourSearch< T, CloudType >.
Definition at line 102 of file nabo_private.h.
| typedef NearestNeighbourSearch<T, CloudType>::IndexMatrix Nabo::KDTreeUnbalancedPtInLeavesImplicitBoundsStackOpt< T, Heap, CloudType >::IndexMatrix |
a matrix of indices to data points
Reimplemented from Nabo::NearestNeighbourSearch< T, CloudType >.
Definition at line 104 of file nabo_private.h.
| typedef NearestNeighbourSearch<T, CloudType>::IndexVector Nabo::KDTreeUnbalancedPtInLeavesImplicitBoundsStackOpt< T, Heap, CloudType >::IndexVector |
a vector of indices to data points
Reimplemented from Nabo::NearestNeighbourSearch< T, CloudType >.
Definition at line 103 of file nabo_private.h.
| typedef NearestNeighbourSearch<T, CloudType>::Matrix Nabo::KDTreeUnbalancedPtInLeavesImplicitBoundsStackOpt< T, Heap, CloudType >::Matrix |
a column-major Eigen matrix in which each column is a point; this matrix has dim rows
Reimplemented from Nabo::NearestNeighbourSearch< T, CloudType >.
Definition at line 101 of file nabo_private.h.
typedef std::vector<Node> Nabo::KDTreeUnbalancedPtInLeavesImplicitBoundsStackOpt< T, Heap, CloudType >::Nodes [protected] |
dense vector of search nodes, provides better memory performances than many small objects
Definition at line 159 of file nabo_private.h.
| typedef NearestNeighbourSearch<T, CloudType>::Vector Nabo::KDTreeUnbalancedPtInLeavesImplicitBoundsStackOpt< T, Heap, CloudType >::Vector |
an Eigen vector of type T, to hold the coordinates of a point
Reimplemented from Nabo::NearestNeighbourSearch< T, CloudType >.
Definition at line 100 of file nabo_private.h.
| Nabo::KDTreeUnbalancedPtInLeavesImplicitBoundsStackOpt< T, Heap, CloudType >::KDTreeUnbalancedPtInLeavesImplicitBoundsStackOpt | ( | const CloudType & | cloud, |
| const Index | dim, | ||
| const unsigned | creationOptionFlags, | ||
| const Parameters & | additionalParameters | ||
| ) |
constructor, calls NearestNeighbourSearch<T>(cloud)
Definition at line 231 of file nabo/kdtree_cpu.cpp.
| unsigned Nabo::KDTreeUnbalancedPtInLeavesImplicitBoundsStackOpt< T, Heap, CloudType >::buildNodes | ( | const BuildPointsIt | first, |
| const BuildPointsIt | last, | ||
| const Vector | minValues, | ||
| const Vector | maxValues | ||
| ) | [protected] |
construct nodes for points [first..last[ inside the hyperrectangle [minValues..maxValues]
Definition at line 113 of file nabo/kdtree_cpu.cpp.
| uint32_t Nabo::KDTreeUnbalancedPtInLeavesImplicitBoundsStackOpt< T, Heap, CloudType >::createDimChildBucketSize | ( | const uint32_t | dim, |
| const uint32_t | childIndex | ||
| ) | const [inline, protected] |
create the compound index containing the dimension and the index of the child or the bucket size
Definition at line 130 of file nabo_private.h.
| pair< T, T > Nabo::KDTreeUnbalancedPtInLeavesImplicitBoundsStackOpt< T, Heap, CloudType >::getBounds | ( | const BuildPointsIt | first, |
| const BuildPointsIt | last, | ||
| const unsigned | dim | ||
| ) | [protected] |
return the bounds of points from [first..last[ on dimension dim
Definition at line 97 of file nabo/kdtree_cpu.cpp.
| uint32_t Nabo::KDTreeUnbalancedPtInLeavesImplicitBoundsStackOpt< T, Heap, CloudType >::getChildBucketSize | ( | const uint32_t | dimChildBucketSize | ) | const [inline, protected] |
get the child index or the bucket size out of the coumpount index
Definition at line 136 of file nabo_private.h.
| uint32_t Nabo::KDTreeUnbalancedPtInLeavesImplicitBoundsStackOpt< T, Heap, CloudType >::getDim | ( | const uint32_t | dimChildBucketSize | ) | const [inline, protected] |
get the dimension out of the compound index
Definition at line 133 of file nabo_private.h.
| unsigned long Nabo::KDTreeUnbalancedPtInLeavesImplicitBoundsStackOpt< T, Heap, CloudType >::knn | ( | const Matrix & | query, |
| IndexMatrix & | indices, | ||
| Matrix & | dists2, | ||
| const Index | k, | ||
| const T | epsilon, | ||
| const unsigned | optionFlags, | ||
| const T | maxRadius | ||
| ) | const [virtual] |
Definition at line 277 of file nabo/kdtree_cpu.cpp.
| unsigned long Nabo::KDTreeUnbalancedPtInLeavesImplicitBoundsStackOpt< T, Heap, CloudType >::knn | ( | const Matrix & | query, |
| IndexMatrix & | indices, | ||
| Matrix & | dists2, | ||
| const Vector & | maxRadii, | ||
| const Index | k = 1, |
||
| const T | epsilon = 0, |
||
| const unsigned | optionFlags = 0 |
||
| ) | const [virtual] |
Definition at line 309 of file nabo/kdtree_cpu.cpp.
| unsigned long Nabo::KDTreeUnbalancedPtInLeavesImplicitBoundsStackOpt< T, Heap, CloudType >::onePointKnn | ( | const Matrix & | query, |
| IndexMatrix & | indices, | ||
| Matrix & | dists2, | ||
| int | i, | ||
| Heap & | heap, | ||
| std::vector< T > & | off, | ||
| const T | maxError, | ||
| const T | maxRadius2, | ||
| const bool | allowSelfMatch, | ||
| const bool | collectStatistics, | ||
| const bool | sortResults | ||
| ) | const [protected] |
search one point, call recurseKnn with the correct template parameters
| query | pointer to query coordinates |
| 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() |
| i | index of point to search |
| heap | reference to heap |
| off | reference to array of offsets |
| maxError | error factor (1 + epsilon) |
| maxRadius2 | square of maximum radius |
| allowSelfMatch | whether to allow self match |
| collectStatistics | whether to collect statistics |
| sortResults | wether to sort results |
Definition at line 341 of file nabo/kdtree_cpu.cpp.
| unsigned long Nabo::KDTreeUnbalancedPtInLeavesImplicitBoundsStackOpt< T, Heap, CloudType >::recurseKnn | ( | const T * | query, |
| const unsigned | n, | ||
| T | rd, | ||
| Heap & | heap, | ||
| std::vector< T > & | off, | ||
| const T | maxError, | ||
| const T | maxRadius2 | ||
| ) | const [protected] |
recursive search, strongly inspired by ANN and [Arya & Mount, Algorithms for fast vector quantization, 1993]
| query | pointer to query coordinates |
| n | index of node to visit |
| rd | squared dist to this rect |
| heap | reference to heap |
| off | reference to array of offsets |
| maxError | error factor (1 + epsilon) |
| maxRadius2 | square of maximum radius |
Definition at line 370 of file nabo/kdtree_cpu.cpp.
Buckets Nabo::KDTreeUnbalancedPtInLeavesImplicitBoundsStackOpt< T, Heap, CloudType >::buckets [protected] |
buckets
Definition at line 181 of file nabo_private.h.
const unsigned Nabo::KDTreeUnbalancedPtInLeavesImplicitBoundsStackOpt< T, Heap, CloudType >::bucketSize [protected] |
size of bucket
Definition at line 122 of file nabo_private.h.
const uint32_t Nabo::KDTreeUnbalancedPtInLeavesImplicitBoundsStackOpt< T, Heap, CloudType >::dimBitCount [protected] |
number of bits required to store dimension index + number of dimensions
Definition at line 125 of file nabo_private.h.
const uint32_t Nabo::KDTreeUnbalancedPtInLeavesImplicitBoundsStackOpt< T, Heap, CloudType >::dimMask [protected] |
mask to access dim
Definition at line 127 of file nabo_private.h.
Nodes Nabo::KDTreeUnbalancedPtInLeavesImplicitBoundsStackOpt< T, Heap, CloudType >::nodes [protected] |
search nodes
Definition at line 178 of file nabo_private.h.