Classes | Public Types | Protected Types | Protected Member Functions | Protected Attributes
Nabo::KDTreeUnbalancedPtInLeavesImplicitBoundsStackOpt< T, Heap > Struct Template Reference

KDTree, unbalanced, points in leaves, stack, implicit bounds, ANN_KD_SL_MIDPT, optimised implementation. More...

#include <nabo_private.h>

Inheritance diagram for Nabo::KDTreeUnbalancedPtInLeavesImplicitBoundsStackOpt< T, Heap >:
Inheritance graph
[legend]

List of all members.

Classes

struct  BucketEntry
 entry in a bucket More...
struct  Node
 search node More...

Public Types

typedef NearestNeighbourSearch
< T >::Index 
Index
 an index to a Vector or a Matrix, for refering to data points
typedef NearestNeighbourSearch
< T >::IndexMatrix 
IndexMatrix
 a matrix of indices to data points
typedef NearestNeighbourSearch
< T >::IndexVector 
IndexVector
 a vector of indices to data points
typedef NearestNeighbourSearch
< T >::Matrix 
Matrix
 a column-major Eigen matrix in which each column is a point; this matrix has dim rows
typedef NearestNeighbourSearch
< T >::Vector 
Vector
 an Eigen vector of type T, to hold the coordinates of a point

Protected Types

typedef std::vector< BucketEntryBuckets
 bucket data
typedef std::vector< IndexBuildPoints
 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< NodeNodes
 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 Matrix &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
 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
 Find the k nearest neighbours for each point of query.

Detailed Description

template<typename T, typename Heap>
struct Nabo::KDTreeUnbalancedPtInLeavesImplicitBoundsStackOpt< T, Heap >

KDTree, unbalanced, points in leaves, stack, implicit bounds, ANN_KD_SL_MIDPT, optimised implementation.

Definition at line 98 of file nabo_private.h.


Member Typedef Documentation

template<typename T, typename Heap>
typedef std::vector<BucketEntry> Nabo::KDTreeUnbalancedPtInLeavesImplicitBoundsStackOpt< T, Heap >::Buckets [protected]

bucket data

Definition at line 175 of file nabo_private.h.

template<typename T, typename Heap>
typedef std::vector<Index> Nabo::KDTreeUnbalancedPtInLeavesImplicitBoundsStackOpt< T, Heap >::BuildPoints [protected]

indices of points during kd-tree construction

Definition at line 115 of file nabo_private.h.

template<typename T, typename Heap>
typedef BuildPoints::const_iterator Nabo::KDTreeUnbalancedPtInLeavesImplicitBoundsStackOpt< T, Heap >::BuildPointsCstIt [protected]

const-iterator to indices of points during kd-tree construction

Definition at line 119 of file nabo_private.h.

template<typename T, typename Heap>
typedef BuildPoints::iterator Nabo::KDTreeUnbalancedPtInLeavesImplicitBoundsStackOpt< T, Heap >::BuildPointsIt [protected]

iterator to indices of points during kd-tree construction

Definition at line 117 of file nabo_private.h.

template<typename T, typename Heap>
typedef NearestNeighbourSearch<T>::Index Nabo::KDTreeUnbalancedPtInLeavesImplicitBoundsStackOpt< T, Heap >::Index

an index to a Vector or a Matrix, for refering to data points

Reimplemented from Nabo::NearestNeighbourSearch< T >.

Definition at line 102 of file nabo_private.h.

a matrix of indices to data points

Reimplemented from Nabo::NearestNeighbourSearch< T >.

Definition at line 104 of file nabo_private.h.

a vector of indices to data points

Reimplemented from Nabo::NearestNeighbourSearch< T >.

Definition at line 103 of file nabo_private.h.

template<typename T, typename Heap>
typedef NearestNeighbourSearch<T>::Matrix Nabo::KDTreeUnbalancedPtInLeavesImplicitBoundsStackOpt< T, Heap >::Matrix

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

Reimplemented from Nabo::NearestNeighbourSearch< T >.

Definition at line 101 of file nabo_private.h.

template<typename T, typename Heap>
typedef std::vector<Node> Nabo::KDTreeUnbalancedPtInLeavesImplicitBoundsStackOpt< T, Heap >::Nodes [protected]

dense vector of search nodes, provides better memory performances than many small objects

Definition at line 159 of file nabo_private.h.

template<typename T, typename Heap>
typedef NearestNeighbourSearch<T>::Vector Nabo::KDTreeUnbalancedPtInLeavesImplicitBoundsStackOpt< T, Heap >::Vector

an Eigen vector of type T, to hold the coordinates of a point

Reimplemented from Nabo::NearestNeighbourSearch< T >.

Definition at line 100 of file nabo_private.h.


Constructor & Destructor Documentation

template<typename T , typename Heap >
Nabo::KDTreeUnbalancedPtInLeavesImplicitBoundsStackOpt< T, Heap >::KDTreeUnbalancedPtInLeavesImplicitBoundsStackOpt ( const Matrix cloud,
const Index  dim,
const unsigned  creationOptionFlags,
const Parameters additionalParameters 
)

constructor, calls NearestNeighbourSearch<T>(cloud)

Definition at line 228 of file kdtree_cpu.cpp.


Member Function Documentation

template<typename T , typename Heap >
unsigned Nabo::KDTreeUnbalancedPtInLeavesImplicitBoundsStackOpt< T, Heap >::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 110 of file kdtree_cpu.cpp.

template<typename T, typename Heap>
uint32_t Nabo::KDTreeUnbalancedPtInLeavesImplicitBoundsStackOpt< T, Heap >::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.

template<typename T , typename Heap >
pair< T, T > Nabo::KDTreeUnbalancedPtInLeavesImplicitBoundsStackOpt< T, Heap >::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 94 of file kdtree_cpu.cpp.

template<typename T, typename Heap>
uint32_t Nabo::KDTreeUnbalancedPtInLeavesImplicitBoundsStackOpt< T, Heap >::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.

template<typename T, typename Heap>
uint32_t Nabo::KDTreeUnbalancedPtInLeavesImplicitBoundsStackOpt< T, Heap >::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.

template<typename T , typename Heap >
unsigned long Nabo::KDTreeUnbalancedPtInLeavesImplicitBoundsStackOpt< T, Heap >::knn ( const Matrix query,
IndexMatrix indices,
Matrix dists2,
const Index  k,
const T  epsilon,
const unsigned  optionFlags,
const T  maxRadius 
) const [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.

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 percentage of error for approximate search, 0 for exact search
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

Implements Nabo::NearestNeighbourSearch< T >.

Definition at line 274 of file kdtree_cpu.cpp.

template<typename T , typename Heap >
unsigned long Nabo::KDTreeUnbalancedPtInLeavesImplicitBoundsStackOpt< T, Heap >::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]

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.

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 percentage of error for approximate search, 0 for exact search
optionFlagssearch options, a bitwise OR of elements of SearchOptionFlags
Returns:
if creationOptionFlags contains TOUCH_STATISTICS, return the number of point touched, otherwise return 0

Implements Nabo::NearestNeighbourSearch< T >.

Definition at line 299 of file kdtree_cpu.cpp.

template<typename T , typename Heap >
unsigned long Nabo::KDTreeUnbalancedPtInLeavesImplicitBoundsStackOpt< T, Heap >::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

Parameters:
querypointer to query coordinates
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()
iindex of point to search
heapreference to heap
offreference to array of offsets
maxErrorerror factor (1 + epsilon)
maxRadius2square of maximum radius
allowSelfMatchwhether to allow self match
collectStatisticswhether to collect statistics
sortResultswether to sort results

Definition at line 325 of file kdtree_cpu.cpp.

template<typename T , typename Heap >
template<bool allowSelfMatch, bool collectStatistics>
unsigned long Nabo::KDTreeUnbalancedPtInLeavesImplicitBoundsStackOpt< T, Heap >::recurseKnn ( const T *  query,
const unsigned  n,
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]

Parameters:
querypointer to query coordinates
nindex of node to visit
rdsquared dist to this rect
heapreference to heap
offreference to array of offsets
maxErrorerror factor (1 + epsilon)
maxRadius2square of maximum radius

Definition at line 354 of file kdtree_cpu.cpp.


Member Data Documentation

template<typename T, typename Heap>
Buckets Nabo::KDTreeUnbalancedPtInLeavesImplicitBoundsStackOpt< T, Heap >::buckets [protected]

buckets

Definition at line 181 of file nabo_private.h.

template<typename T, typename Heap>
const unsigned Nabo::KDTreeUnbalancedPtInLeavesImplicitBoundsStackOpt< T, Heap >::bucketSize [protected]

size of bucket

Definition at line 122 of file nabo_private.h.

template<typename T, typename Heap>
const uint32_t Nabo::KDTreeUnbalancedPtInLeavesImplicitBoundsStackOpt< T, Heap >::dimBitCount [protected]

number of bits required to store dimension index + number of dimensions

Definition at line 125 of file nabo_private.h.

template<typename T, typename Heap>
const uint32_t Nabo::KDTreeUnbalancedPtInLeavesImplicitBoundsStackOpt< T, Heap >::dimMask [protected]

mask to access dim

Definition at line 127 of file nabo_private.h.

template<typename T, typename Heap>
Nodes Nabo::KDTreeUnbalancedPtInLeavesImplicitBoundsStackOpt< T, Heap >::nodes [protected]

search nodes

Definition at line 178 of file nabo_private.h.


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


libnabo
Author(s): Stéphane Magnenat
autogenerated on Thu Jan 2 2014 11:15:54