Brute-force nearest neighbour. More...
#include <nabo_private.h>

| 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 | |
| BruteForceSearch (const CloudType &cloud, const Index dim, const unsigned creationOptionFlags) | |
| 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... | |
| Additional Inherited Members | |
|  Static Public Member Functions inherited from Nabo::NearestNeighbourSearch< T, Eigen::Matrix< T, Eigen::Dynamic, Eigen::Dynamic > > | |
| 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... | |
|  Public Attributes inherited from Nabo::NearestNeighbourSearch< T, Eigen::Matrix< T, Eigen::Dynamic, Eigen::Dynamic > > | |
| 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 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... | |
|  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... | |
Brute-force nearest neighbour.
Definition at line 72 of file nabo_private.h.
| typedef NearestNeighbourSearch<T, CloudType>::Index Nabo::BruteForceSearch< T, CloudType >::Index | 
Definition at line 76 of file nabo_private.h.
| typedef NearestNeighbourSearch<T, CloudType>::IndexMatrix Nabo::BruteForceSearch< T, CloudType >::IndexMatrix | 
Definition at line 78 of file nabo_private.h.
| typedef NearestNeighbourSearch<T, CloudType>::IndexVector Nabo::BruteForceSearch< T, CloudType >::IndexVector | 
Definition at line 77 of file nabo_private.h.
| typedef NearestNeighbourSearch<T, CloudType>::Matrix Nabo::BruteForceSearch< T, CloudType >::Matrix | 
Definition at line 75 of file nabo_private.h.
| typedef NearestNeighbourSearch<T, CloudType>::Vector Nabo::BruteForceSearch< T, CloudType >::Vector | 
Definition at line 74 of file nabo_private.h.
| Nabo::BruteForceSearch< T, CloudType >::BruteForceSearch | ( | const CloudType & | cloud, | 
| const Index | dim, | ||
| const unsigned | creationOptionFlags | ||
| ) | 
constructor, calls NearestNeighbourSearch<T>(cloud)
Definition at line 45 of file brute_force_cpu.cpp.
| 
 | virtual | 
Definition at line 64 of file brute_force_cpu.cpp.
| 
 | virtual | 
Definition at line 71 of file brute_force_cpu.cpp.