KDTree, unbalanced, points in leaves, stack, implicit bounds, ANN_KD_SL_MIDPT, optimised implementation.  
 More...
|  | 
| typedef NearestNeighbourSearch< T, CloudType >::Index | Index | 
|  | 
| typedef NearestNeighbourSearch< T, CloudType >::IndexMatrix | IndexMatrix | 
|  | 
| typedef NearestNeighbourSearch< T, CloudType >::IndexVector | IndexVector | 
|  | 
| typedef NearestNeighbourSearch< T, CloudType >::Matrix | Matrix | 
|  | 
| typedef NearestNeighbourSearch< T, CloudType >::Vector | Vector | 
|  | 
| typedef Eigen::Matrix< T, Eigen::Dynamic, Eigen::Dynamic > | CloudType | 
|  | a column-major Eigen matrix in which each column is a point; this matrix has dim rows  More... 
 | 
|  | 
| enum | CreationOptionFlags | 
|  | 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 | 
|  | search option  More... 
 | 
|  | 
| enum | SearchType | 
|  | 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... 
 | 
|  | 
|  | 
|  | KDTreeUnbalancedPtInLeavesImplicitBoundsStackOpt (const CloudType &cloud, const Index dim, const unsigned creationOptionFlags, const Parameters &additionalParameters) | 
|  | constructor, calls NearestNeighbourSearch<T>(cloud)  More... 
 | 
|  | 
| 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 | 
|  | 
| 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... 
 | 
|  | 
|  | 
| 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]  More... 
 | 
|  | 
| 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  More... 
 | 
|  | 
| 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  More... 
 | 
|  | 
| uint32_t | getChildBucketSize (const uint32_t dimChildBucketSize) const | 
|  | get the child index or the bucket size out of the coumpount index  More... 
 | 
|  | 
| uint32_t | getDim (const uint32_t dimChildBucketSize) const | 
|  | get the dimension out of the compound index  More... 
 | 
|  | 
| 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  More... 
 | 
|  | 
| 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]  More... 
 | 
|  | 
| 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... 
 | 
|  | 
|  | 
| 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... 
 | 
|  | 
| 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... 
 | 
|  | 
| 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... 
 | 
|  | 
| 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... 
 | 
|  | 
| 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... 
 | 
|  | 
| 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 constexpr Index | InvalidIndex | 
|  | the invalid index  More... 
 | 
|  | 
| static constexpr T | InvalidValue | 
|  | the invalid value  More... 
 | 
|  | 
template<typename T, typename Heap, typename CloudType = Eigen::Matrix<T, Eigen::Dynamic, Eigen::Dynamic>>
struct Nabo::KDTreeUnbalancedPtInLeavesImplicitBoundsStackOpt< T, Heap, CloudType >
KDTree, unbalanced, points in leaves, stack, implicit bounds, ANN_KD_SL_MIDPT, optimised implementation. 
Definition at line 94 of file nabo_private.h.
template<typename T , typename Heap , typename CloudType > 
template<bool allowSelfMatch, bool collectStatistics> 
 
recursive search, strongly inspired by ANN and [Arya & Mount, Algorithms for fast vector quantization, 1993] 
- Parameters
- 
  
    | 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 368 of file nabo/kdtree_cpu.cpp.