Public Types | Public Member Functions | Protected Member Functions | List of all members
Nabo::KDTreeBalancedPtInNodesStack< T, CloudType > Struct Template Reference

#include <nabo_experimental.h>

Inheritance diagram for Nabo::KDTreeBalancedPtInNodesStack< T, CloudType >:
Inheritance graph
[legend]

Public Types

typedef IndexHeapSTL< Index, T > Heap
 
typedef NearestNeighbourSearch< T, CloudType >::Index Index
 
typedef NearestNeighbourSearch< T, CloudType >::IndexVector IndexVector
 
typedef NearestNeighbourSearch< T, CloudType >::Matrix Matrix
 
typedef KDTreeBalancedPtInNodes< T, CloudType >::Node Node
 
typedef KDTreeBalancedPtInNodes< T, CloudType >::Nodes Nodes
 
typedef NearestNeighbourSearch< T, CloudType >::Vector Vector
 
- Public Types inherited from Nabo::KDTreeBalancedPtInNodes< T, CloudType >
typedef NearestNeighbourSearch< T, CloudType >::Index Index
 
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, CloudType >
typedef CloudType 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

 KDTreeBalancedPtInNodesStack (const CloudType &cloud)
 
virtual IndexVector knn (const Vector &query, const Index k, const T epsilon, const unsigned optionFlags)
 
- Public Member Functions inherited from Nabo::NearestNeighbourSearch< T, CloudType >
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 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...
 
virtual ~NearestNeighbourSearch ()
 virtual destructor More...
 

Protected Member Functions

void recurseKnn (const Vector &query, const size_t n, T rd, Heap &heap, Vector &off, const T maxError, const bool allowSelfMatch)
 
- Protected Member Functions inherited from Nabo::KDTreeBalancedPtInNodes< T, CloudType >
void buildNodes (const BuildPointsIt first, const BuildPointsIt last, const size_t pos)
 
size_t childLeft (size_t pos) const
 
size_t childRight (size_t pos) const
 
IndexVector cloudIndexesFromNodesIndexes (const IndexVector &indexes) const
 
void dump (const Vector minValues, const Vector maxValues, const size_t pos) const
 
size_t getTreeSize (size_t size) const
 
 KDTreeBalancedPtInNodes (const CloudType &cloud)
 
size_t parent (size_t pos) const
 
- Protected Member Functions inherited from Nabo::NearestNeighbourSearch< T, CloudType >
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...
 

Additional Inherited Members

- Static Public Member Functions inherited from Nabo::NearestNeighbourSearch< T, CloudType >
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, CloudType >
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, CloudType >
static constexpr Index InvalidIndex
 the invalid index More...
 
static constexpr T InvalidValue
 the invalid value More...
 
- Protected Types inherited from Nabo::KDTreeBalancedPtInNodes< T, CloudType >
typedef std::vector< BuildPointBuildPoints
 
typedef BuildPoints::const_iterator BuildPointsCstIt
 
typedef BuildPoints::iterator BuildPointsIt
 
typedef std::vector< NodeNodes
 
- Protected Attributes inherited from Nabo::KDTreeBalancedPtInNodes< T, CloudType >
Nodes nodes
 

Detailed Description

template<typename T, typename CloudType>
struct Nabo::KDTreeBalancedPtInNodesStack< T, CloudType >

Definition at line 124 of file nabo_experimental.h.

Member Typedef Documentation

◆ Heap

template<typename T, typename CloudType>
typedef IndexHeapSTL<Index, T> Nabo::KDTreeBalancedPtInNodesStack< T, CloudType >::Heap

Definition at line 138 of file nabo_experimental.h.

◆ Index

template<typename T, typename CloudType>
typedef NearestNeighbourSearch<T, CloudType>::Index Nabo::KDTreeBalancedPtInNodesStack< T, CloudType >::Index

Definition at line 128 of file nabo_experimental.h.

◆ IndexVector

template<typename T, typename CloudType>
typedef NearestNeighbourSearch<T, CloudType>::IndexVector Nabo::KDTreeBalancedPtInNodesStack< T, CloudType >::IndexVector

Definition at line 129 of file nabo_experimental.h.

◆ Matrix

template<typename T, typename CloudType>
typedef NearestNeighbourSearch<T, CloudType>::Matrix Nabo::KDTreeBalancedPtInNodesStack< T, CloudType >::Matrix

Definition at line 127 of file nabo_experimental.h.

◆ Node

template<typename T, typename CloudType>
typedef KDTreeBalancedPtInNodes<T, CloudType>::Node Nabo::KDTreeBalancedPtInNodesStack< T, CloudType >::Node

Definition at line 130 of file nabo_experimental.h.

◆ Nodes

template<typename T, typename CloudType>
typedef KDTreeBalancedPtInNodes<T, CloudType>::Nodes Nabo::KDTreeBalancedPtInNodesStack< T, CloudType >::Nodes

Definition at line 131 of file nabo_experimental.h.

◆ Vector

template<typename T, typename CloudType>
typedef NearestNeighbourSearch<T, CloudType>::Vector Nabo::KDTreeBalancedPtInNodesStack< T, CloudType >::Vector

Definition at line 126 of file nabo_experimental.h.

Constructor & Destructor Documentation

◆ KDTreeBalancedPtInNodesStack()

template<typename T , typename CloudType>
Nabo::KDTreeBalancedPtInNodesStack< T, CloudType >::KDTreeBalancedPtInNodesStack ( const CloudType cloud)

Definition at line 285 of file experimental/kdtree_cpu.cpp.

Member Function Documentation

◆ knn()

template<typename T, typename CloudType >
KDTreeBalancedPtInNodesStack< T, CloudType >::IndexVector Nabo::KDTreeBalancedPtInNodesStack< T, CloudType >::knn ( const Vector query,
const Index  k,
const T  epsilon,
const unsigned  optionFlags 
)
virtual

Definition at line 291 of file experimental/kdtree_cpu.cpp.

◆ recurseKnn()

template<typename T, typename CloudType >
void Nabo::KDTreeBalancedPtInNodesStack< T, CloudType >::recurseKnn ( const Vector query,
const size_t  n,
rd,
Heap heap,
Vector off,
const T  maxError,
const bool  allowSelfMatch 
)
protected

Definition at line 313 of file experimental/kdtree_cpu.cpp.


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


libnabo
Author(s): Stéphane Magnenat
autogenerated on Mon Feb 28 2022 22:41:38