Classes | Public Types | Public Member Functions | Protected Types | Protected Member Functions | Protected Attributes | List of all members
Nabo::KDTreeUnbalancedPtInLeavesImplicitBoundsStackOpt< T, Heap, CloudType > 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, CloudType >:
Inheritance graph
[legend]

Classes

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

Public Types

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
 
- Public Types inherited from Nabo::NearestNeighbourSearch< T, Eigen::Matrix< T, Eigen::Dynamic, Eigen::Dynamic > >
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...
 

Public Member Functions

 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
 
- Public Member Functions inherited from Nabo::NearestNeighbourSearch< T, Eigen::Matrix< T, Eigen::Dynamic, Eigen::Dynamic > >
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...
 

Protected Types

typedef std::vector< BucketEntryBuckets
 bucket data More...
 
typedef std::vector< IndexBuildPoints
 indices of points during kd-tree construction More...
 
typedef BuildPoints::const_iterator BuildPointsCstIt
 const-iterator to indices of points during kd-tree construction More...
 
typedef BuildPoints::iterator BuildPointsIt
 iterator to indices of points during kd-tree construction More...
 
typedef std::vector< NodeNodes
 dense vector of search nodes, provides better memory performances than many small objects More...
 

Protected Member Functions

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...
 
- Protected Member Functions inherited from Nabo::NearestNeighbourSearch< T, Eigen::Matrix< T, Eigen::Dynamic, Eigen::Dynamic > >
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...
 

Protected Attributes

Buckets buckets
 buckets More...
 
const unsigned bucketSize
 size of bucket More...
 
const uint32_t dimBitCount
 number of bits required to store dimension index + number of dimensions More...
 
const uint32_t dimMask
 mask to access dim More...
 
Nodes nodes
 search nodes More...
 

Additional Inherited Members

- Static Public Member Functions inherited from Nabo::NearestNeighbourSearch< T, Eigen::Matrix< T, Eigen::Dynamic, Eigen::Dynamic > >
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. More...
 
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. More...
 
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. More...
 
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. More...
 
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) More...
 
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. More...
 
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) More...
 
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. More...
 
- Public Attributes inherited from Nabo::NearestNeighbourSearch< T, Eigen::Matrix< T, Eigen::Dynamic, Eigen::Dynamic > >
const CloudTypecloud
 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 Public Attributes inherited from Nabo::NearestNeighbourSearch< T, Eigen::Matrix< T, Eigen::Dynamic, Eigen::Dynamic > >
static constexpr Index InvalidIndex
 the invalid index More...
 
static constexpr T InvalidValue
 the invalid value More...
 

Detailed Description

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.

Member Typedef Documentation

◆ Buckets

template<typename T , typename Heap , typename CloudType = Eigen::Matrix<T, Eigen::Dynamic, Eigen::Dynamic>>
typedef std::vector<BucketEntry> Nabo::KDTreeUnbalancedPtInLeavesImplicitBoundsStackOpt< T, Heap, CloudType >::Buckets
protected

bucket data

Definition at line 171 of file nabo_private.h.

◆ BuildPoints

template<typename T , typename Heap , typename CloudType = Eigen::Matrix<T, Eigen::Dynamic, Eigen::Dynamic>>
typedef std::vector<Index> Nabo::KDTreeUnbalancedPtInLeavesImplicitBoundsStackOpt< T, Heap, CloudType >::BuildPoints
protected

indices of points during kd-tree construction

Definition at line 111 of file nabo_private.h.

◆ BuildPointsCstIt

template<typename T , typename Heap , typename CloudType = Eigen::Matrix<T, Eigen::Dynamic, Eigen::Dynamic>>
typedef BuildPoints::const_iterator Nabo::KDTreeUnbalancedPtInLeavesImplicitBoundsStackOpt< T, Heap, CloudType >::BuildPointsCstIt
protected

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

Definition at line 115 of file nabo_private.h.

◆ BuildPointsIt

template<typename T , typename Heap , typename CloudType = Eigen::Matrix<T, Eigen::Dynamic, Eigen::Dynamic>>
typedef BuildPoints::iterator Nabo::KDTreeUnbalancedPtInLeavesImplicitBoundsStackOpt< T, Heap, CloudType >::BuildPointsIt
protected

iterator to indices of points during kd-tree construction

Definition at line 113 of file nabo_private.h.

◆ Index

template<typename T , typename Heap , typename CloudType = Eigen::Matrix<T, Eigen::Dynamic, Eigen::Dynamic>>
typedef NearestNeighbourSearch<T, CloudType>::Index Nabo::KDTreeUnbalancedPtInLeavesImplicitBoundsStackOpt< T, Heap, CloudType >::Index

Definition at line 98 of file nabo_private.h.

◆ IndexMatrix

template<typename T , typename Heap , typename CloudType = Eigen::Matrix<T, Eigen::Dynamic, Eigen::Dynamic>>
typedef NearestNeighbourSearch<T, CloudType>::IndexMatrix Nabo::KDTreeUnbalancedPtInLeavesImplicitBoundsStackOpt< T, Heap, CloudType >::IndexMatrix

Definition at line 100 of file nabo_private.h.

◆ IndexVector

template<typename T , typename Heap , typename CloudType = Eigen::Matrix<T, Eigen::Dynamic, Eigen::Dynamic>>
typedef NearestNeighbourSearch<T, CloudType>::IndexVector Nabo::KDTreeUnbalancedPtInLeavesImplicitBoundsStackOpt< T, Heap, CloudType >::IndexVector

Definition at line 99 of file nabo_private.h.

◆ Matrix

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

Definition at line 97 of file nabo_private.h.

◆ Nodes

template<typename T , typename Heap , typename CloudType = Eigen::Matrix<T, Eigen::Dynamic, Eigen::Dynamic>>
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 155 of file nabo_private.h.

◆ Vector

template<typename T , typename Heap , typename CloudType = Eigen::Matrix<T, Eigen::Dynamic, Eigen::Dynamic>>
typedef NearestNeighbourSearch<T, CloudType>::Vector Nabo::KDTreeUnbalancedPtInLeavesImplicitBoundsStackOpt< T, Heap, CloudType >::Vector

Definition at line 96 of file nabo_private.h.

Constructor & Destructor Documentation

◆ KDTreeUnbalancedPtInLeavesImplicitBoundsStackOpt()

template<typename T , typename Heap , typename CloudType >
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 228 of file nabo/kdtree_cpu.cpp.

Member Function Documentation

◆ buildNodes()

template<typename T , typename Heap , typename CloudType >
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 110 of file nabo/kdtree_cpu.cpp.

◆ createDimChildBucketSize()

template<typename T , typename Heap , typename CloudType = Eigen::Matrix<T, Eigen::Dynamic, Eigen::Dynamic>>
uint32_t Nabo::KDTreeUnbalancedPtInLeavesImplicitBoundsStackOpt< T, Heap, CloudType >::createDimChildBucketSize ( const uint32_t  dim,
const uint32_t  childIndex 
) const
inlineprotected

create the compound index containing the dimension and the index of the child or the bucket size

Definition at line 126 of file nabo_private.h.

◆ getBounds()

template<typename T , typename Heap , typename CloudType >
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 94 of file nabo/kdtree_cpu.cpp.

◆ getChildBucketSize()

template<typename T , typename Heap , typename CloudType = Eigen::Matrix<T, Eigen::Dynamic, Eigen::Dynamic>>
uint32_t Nabo::KDTreeUnbalancedPtInLeavesImplicitBoundsStackOpt< T, Heap, CloudType >::getChildBucketSize ( const uint32_t  dimChildBucketSize) const
inlineprotected

get the child index or the bucket size out of the coumpount index

Definition at line 132 of file nabo_private.h.

◆ getDim()

template<typename T , typename Heap , typename CloudType = Eigen::Matrix<T, Eigen::Dynamic, Eigen::Dynamic>>
uint32_t Nabo::KDTreeUnbalancedPtInLeavesImplicitBoundsStackOpt< T, Heap, CloudType >::getDim ( const uint32_t  dimChildBucketSize) const
inlineprotected

get the dimension out of the compound index

Definition at line 129 of file nabo_private.h.

◆ knn() [1/2]

template<typename T , typename Heap , typename CloudType >
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 275 of file nabo/kdtree_cpu.cpp.

◆ knn() [2/2]

template<typename T , typename Heap , typename CloudType >
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 307 of file nabo/kdtree_cpu.cpp.

◆ onePointKnn()

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

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 339 of file nabo/kdtree_cpu.cpp.

◆ recurseKnn()

template<typename T , typename Heap , typename CloudType >
template<bool allowSelfMatch, bool collectStatistics>
unsigned long Nabo::KDTreeUnbalancedPtInLeavesImplicitBoundsStackOpt< T, Heap, CloudType >::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 368 of file nabo/kdtree_cpu.cpp.

Member Data Documentation

◆ buckets

template<typename T , typename Heap , typename CloudType = Eigen::Matrix<T, Eigen::Dynamic, Eigen::Dynamic>>
Buckets Nabo::KDTreeUnbalancedPtInLeavesImplicitBoundsStackOpt< T, Heap, CloudType >::buckets
protected

buckets

Definition at line 177 of file nabo_private.h.

◆ bucketSize

template<typename T , typename Heap , typename CloudType = Eigen::Matrix<T, Eigen::Dynamic, Eigen::Dynamic>>
const unsigned Nabo::KDTreeUnbalancedPtInLeavesImplicitBoundsStackOpt< T, Heap, CloudType >::bucketSize
protected

size of bucket

Definition at line 118 of file nabo_private.h.

◆ dimBitCount

template<typename T , typename Heap , typename CloudType = Eigen::Matrix<T, Eigen::Dynamic, Eigen::Dynamic>>
const uint32_t Nabo::KDTreeUnbalancedPtInLeavesImplicitBoundsStackOpt< T, Heap, CloudType >::dimBitCount
protected

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

Definition at line 121 of file nabo_private.h.

◆ dimMask

template<typename T , typename Heap , typename CloudType = Eigen::Matrix<T, Eigen::Dynamic, Eigen::Dynamic>>
const uint32_t Nabo::KDTreeUnbalancedPtInLeavesImplicitBoundsStackOpt< T, Heap, CloudType >::dimMask
protected

mask to access dim

Definition at line 123 of file nabo_private.h.

◆ nodes

template<typename T , typename Heap , typename CloudType = Eigen::Matrix<T, Eigen::Dynamic, Eigen::Dynamic>>
Nodes Nabo::KDTreeUnbalancedPtInLeavesImplicitBoundsStackOpt< T, Heap, CloudType >::nodes
protected

search nodes

Definition at line 174 of file nabo_private.h.


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


libnabo
Author(s): Stéphane Magnenat
autogenerated on Sat Mar 23 2024 02:52:25