Classes | Public Types | Public Member Functions | Public Attributes | Protected Types | Protected Attributes | Private Member Functions
nanoflann::KDTreeSingleIndexAdaptor< Distance, DatasetAdaptor, DIM, IndexType > Class Template Reference

#include <nanoflann.hpp>

List of all members.

Classes

struct  BranchStruct
struct  Interval
struct  Node

Public Types

typedef Distance::DistanceType DistanceType
typedef Distance::ElementType ElementType

Public Member Functions

void buildIndex ()
void freeIndex ()
 KDTreeSingleIndexAdaptor (const int dimensionality, const DatasetAdaptor &inputData, const KDTreeSingleIndexAdaptorParams &params=KDTreeSingleIndexAdaptorParams())
void loadIndex (FILE *stream)
void saveIndex (FILE *stream)
size_t size () const
size_t usedMemory () const
size_t veclen () const
 ~KDTreeSingleIndexAdaptor ()
Query methods
template<typename RESULTSET >
void findNeighbors (RESULTSET &result, const ElementType *vec, const SearchParams &searchParams) const
void knnSearch (const ElementType *query_point, const size_t num_closest, IndexType *out_indices, DistanceType *out_distances_sq, const int nChecks_IGNORED=10) const
size_t radiusSearch (const ElementType *query_point, const DistanceType radius, std::vector< std::pair< IndexType, DistanceType > > &IndicesDists, const SearchParams &searchParams) const

Public Attributes

Distance distance

Protected Types

typedef
array_or_vector_selector< DIM,
Interval >::container_t 
BoundingBox
typedef BranchStBranch
typedef BranchStruct< NodePtr,
DistanceType
BranchSt
typedef
array_or_vector_selector< DIM,
DistanceType >::container_t 
distance_vector_t
typedef NodeNodePtr

Protected Attributes

const DatasetAdaptor & dataset
 The source of our data.
int dim
 Dimensionality of each data point.
const
KDTreeSingleIndexAdaptorParams 
index_params
size_t m_leaf_max_size
size_t m_size
PooledAllocator pool
BoundingBox root_bbox
NodePtr root_node
std::vector< IndexType > vind

Private Member Functions

void computeBoundingBox (BoundingBox &bbox)
DistanceType computeInitialDistances (const ElementType *vec, distance_vector_t &dists) const
void computeMinMax (IndexType *ind, IndexType count, int element, ElementType &min_elem, ElementType &max_elem)
ElementType dataset_get (size_t idx, int component) const
 Helper accessor to the dataset points:
NodePtr divideTree (const IndexType left, const IndexType right, BoundingBox &bbox)
void init_vind ()
 KDTreeSingleIndexAdaptor (const KDTreeSingleIndexAdaptor< Distance, DatasetAdaptor, DIM, IndexType > &)
void load_tree (FILE *stream, NodePtr &tree)
void middleSplit (IndexType *ind, IndexType count, IndexType &index, int &cutfeat, DistanceType &cutval, const BoundingBox &bbox)
void middleSplit_ (IndexType *ind, IndexType count, IndexType &index, int &cutfeat, DistanceType &cutval, const BoundingBox &bbox)
void planeSplit (IndexType *ind, const IndexType count, int cutfeat, DistanceType cutval, IndexType &lim1, IndexType &lim2)
void save_tree (FILE *stream, NodePtr tree)
template<class RESULTSET >
void searchLevel (RESULTSET &result_set, const ElementType *vec, const NodePtr node, DistanceType mindistsq, distance_vector_t &dists, const float epsError) const

Detailed Description

template<typename Distance, class DatasetAdaptor, int DIM = -1, typename IndexType = size_t>
class nanoflann::KDTreeSingleIndexAdaptor< Distance, DatasetAdaptor, DIM, IndexType >

kd-tree index

Contains the k-d trees and other information for indexing a set of points for nearest-neighbor matching.

The class "DatasetAdaptor" must provide the following interface (can be non-virtual, inlined methods):

   // Must return the number of data points
   inline size_t kdtree_get_point_count() const { ... }

   // Must return the Euclidean (L2) distance between the vector "p1[0:size-1]" and the data point with index "idx_p2" stored in the class:
   inline DistanceType kdtree_distance(const T *p1, const size_t idx_p2,size_t size) const { ... }

   // Must return the dim'th component of the idx'th point in the class:
   inline T kdtree_get_pt(const size_t idx, int dim) const { ... }

   // Optional bounding-box computation: return false to default to a standard bbox computation loop.
   //   Return true if the BBOX was already computed by the class and returned in "bb" so it can be avoided to redo it again.
   //   Look at bb.size() to find out the expected dimensionality (e.g. 2 or 3 for point clouds)
   template <class BBOX>
   bool kdtree_get_bbox(BBOX &bb) const
   {
      bb[0].low = ...; bb[0].high = ...;  // 0th dimension limits
      bb[1].low = ...; bb[1].high = ...;  // 1st dimension limits
      ...
      return true;
   }
Template Parameters:
IndexTypeWill be typically size_t or int

Definition at line 733 of file nanoflann.hpp.


Member Typedef Documentation

template<typename Distance , class DatasetAdaptor , int DIM = -1, typename IndexType = size_t>
typedef array_or_vector_selector<DIM,Interval>::container_t nanoflann::KDTreeSingleIndexAdaptor< Distance, DatasetAdaptor, DIM, IndexType >::BoundingBox [protected]

Define "BoundingBox" as a fixed-size or variable-size container depending on "DIM"

Definition at line 799 of file nanoflann.hpp.

template<typename Distance , class DatasetAdaptor , int DIM = -1, typename IndexType = size_t>
typedef BranchSt* nanoflann::KDTreeSingleIndexAdaptor< Distance, DatasetAdaptor, DIM, IndexType >::Branch [protected]

Definition at line 828 of file nanoflann.hpp.

template<typename Distance , class DatasetAdaptor , int DIM = -1, typename IndexType = size_t>
typedef BranchStruct<NodePtr, DistanceType> nanoflann::KDTreeSingleIndexAdaptor< Distance, DatasetAdaptor, DIM, IndexType >::BranchSt [protected]

Definition at line 827 of file nanoflann.hpp.

template<typename Distance , class DatasetAdaptor , int DIM = -1, typename IndexType = size_t>
typedef array_or_vector_selector<DIM,DistanceType>::container_t nanoflann::KDTreeSingleIndexAdaptor< Distance, DatasetAdaptor, DIM, IndexType >::distance_vector_t [protected]

Define "distance_vector_t" as a fixed-size or variable-size container depending on "DIM"

Definition at line 802 of file nanoflann.hpp.

template<typename Distance , class DatasetAdaptor , int DIM = -1, typename IndexType = size_t>
typedef Distance::DistanceType nanoflann::KDTreeSingleIndexAdaptor< Distance, DatasetAdaptor, DIM, IndexType >::DistanceType

Definition at line 740 of file nanoflann.hpp.

template<typename Distance , class DatasetAdaptor , int DIM = -1, typename IndexType = size_t>
typedef Distance::ElementType nanoflann::KDTreeSingleIndexAdaptor< Distance, DatasetAdaptor, DIM, IndexType >::ElementType

Definition at line 739 of file nanoflann.hpp.

template<typename Distance , class DatasetAdaptor , int DIM = -1, typename IndexType = size_t>
typedef Node* nanoflann::KDTreeSingleIndexAdaptor< Distance, DatasetAdaptor, DIM, IndexType >::NodePtr [protected]

Definition at line 790 of file nanoflann.hpp.


Constructor & Destructor Documentation

template<typename Distance , class DatasetAdaptor , int DIM = -1, typename IndexType = size_t>
nanoflann::KDTreeSingleIndexAdaptor< Distance, DatasetAdaptor, DIM, IndexType >::KDTreeSingleIndexAdaptor ( const KDTreeSingleIndexAdaptor< Distance, DatasetAdaptor, DIM, IndexType > &  ) [private]

Hidden copy constructor, to disallow copying indices (Not implemented)

template<typename Distance , class DatasetAdaptor , int DIM = -1, typename IndexType = size_t>
nanoflann::KDTreeSingleIndexAdaptor< Distance, DatasetAdaptor, DIM, IndexType >::KDTreeSingleIndexAdaptor ( const int  dimensionality,
const DatasetAdaptor &  inputData,
const KDTreeSingleIndexAdaptorParams params = KDTreeSingleIndexAdaptorParams() 
) [inline]

KDTree constructor

Params: inputData = dataset with the input features params = parameters passed to the kdtree algorithm (see http://code.google.com/p/nanoflann/ for help choosing the parameters)

Definition at line 852 of file nanoflann.hpp.

template<typename Distance , class DatasetAdaptor , int DIM = -1, typename IndexType = size_t>
nanoflann::KDTreeSingleIndexAdaptor< Distance, DatasetAdaptor, DIM, IndexType >::~KDTreeSingleIndexAdaptor ( ) [inline]

Standard destructor

Definition at line 870 of file nanoflann.hpp.


Member Function Documentation

template<typename Distance , class DatasetAdaptor , int DIM = -1, typename IndexType = size_t>
void nanoflann::KDTreeSingleIndexAdaptor< Distance, DatasetAdaptor, DIM, IndexType >::buildIndex ( ) [inline]

Builds the index

Definition at line 884 of file nanoflann.hpp.

template<typename Distance , class DatasetAdaptor , int DIM = -1, typename IndexType = size_t>
void nanoflann::KDTreeSingleIndexAdaptor< Distance, DatasetAdaptor, DIM, IndexType >::computeBoundingBox ( BoundingBox bbox) [inline, private]

Definition at line 1024 of file nanoflann.hpp.

template<typename Distance , class DatasetAdaptor , int DIM = -1, typename IndexType = size_t>
DistanceType nanoflann::KDTreeSingleIndexAdaptor< Distance, DatasetAdaptor, DIM, IndexType >::computeInitialDistances ( const ElementType vec,
distance_vector_t dists 
) const [inline, private]

Definition at line 1244 of file nanoflann.hpp.

template<typename Distance , class DatasetAdaptor , int DIM = -1, typename IndexType = size_t>
void nanoflann::KDTreeSingleIndexAdaptor< Distance, DatasetAdaptor, DIM, IndexType >::computeMinMax ( IndexType *  ind,
IndexType  count,
int  element,
ElementType min_elem,
ElementType max_elem 
) [inline, private]

Definition at line 1108 of file nanoflann.hpp.

template<typename Distance , class DatasetAdaptor , int DIM = -1, typename IndexType = size_t>
ElementType nanoflann::KDTreeSingleIndexAdaptor< Distance, DatasetAdaptor, DIM, IndexType >::dataset_get ( size_t  idx,
int  component 
) const [inline, private]

Helper accessor to the dataset points:

Definition at line 994 of file nanoflann.hpp.

template<typename Distance , class DatasetAdaptor , int DIM = -1, typename IndexType = size_t>
NodePtr nanoflann::KDTreeSingleIndexAdaptor< Distance, DatasetAdaptor, DIM, IndexType >::divideTree ( const IndexType  left,
const IndexType  right,
BoundingBox bbox 
) [inline, private]

Create a tree node that subdivides the list of vecs from vind[first] to vind[last]. The routine is called recursively on each sublist. Place a pointer to this new tree node in the location pTree.

Params: pTree = the new node to create first = index of the first vector last = index of the last vector

Definition at line 1058 of file nanoflann.hpp.

template<typename Distance , class DatasetAdaptor , int DIM = -1, typename IndexType = size_t>
template<typename RESULTSET >
void nanoflann::KDTreeSingleIndexAdaptor< Distance, DatasetAdaptor, DIM, IndexType >::findNeighbors ( RESULTSET &  result,
const ElementType vec,
const SearchParams searchParams 
) const [inline]

Find set of nearest neighbors to vec[0:dim-1]. Their indices are stored inside the result object.

Params: result = the result object in which the indices of the nearest-neighbors are stored vec = the vector for which to search the nearest neighbors

Template Parameters:
RESULTSETShould be any ResultSet<DistanceType>
See also:
knnSearch, radiusSearch

Definition at line 933 of file nanoflann.hpp.

template<typename Distance , class DatasetAdaptor , int DIM = -1, typename IndexType = size_t>
void nanoflann::KDTreeSingleIndexAdaptor< Distance, DatasetAdaptor, DIM, IndexType >::freeIndex ( ) [inline]

Frees the previously-built index. Automatically called within buildIndex().

Definition at line 875 of file nanoflann.hpp.

template<typename Distance , class DatasetAdaptor , int DIM = -1, typename IndexType = size_t>
void nanoflann::KDTreeSingleIndexAdaptor< Distance, DatasetAdaptor, DIM, IndexType >::init_vind ( ) [inline, private]

Make sure the auxiliary list vind has the same size than the current dataset, and re-generate if size has changed.

Definition at line 985 of file nanoflann.hpp.

template<typename Distance , class DatasetAdaptor , int DIM = -1, typename IndexType = size_t>
void nanoflann::KDTreeSingleIndexAdaptor< Distance, DatasetAdaptor, DIM, IndexType >::knnSearch ( const ElementType query_point,
const size_t  num_closest,
IndexType *  out_indices,
DistanceType out_distances_sq,
const int  nChecks_IGNORED = 10 
) const [inline]

Find the "num_closest" nearest neighbors to the query_point[0:dim-1]. Their indices are stored inside the result object.

See also:
radiusSearch, findNeighbors
Note:
nChecks_IGNORED is ignored but kept for compatibility with the original FLANN interface.

Definition at line 951 of file nanoflann.hpp.

template<typename Distance , class DatasetAdaptor , int DIM = -1, typename IndexType = size_t>
void nanoflann::KDTreeSingleIndexAdaptor< Distance, DatasetAdaptor, DIM, IndexType >::load_tree ( FILE *  stream,
NodePtr tree 
) [inline, private]

Definition at line 1011 of file nanoflann.hpp.

template<typename Distance , class DatasetAdaptor , int DIM = -1, typename IndexType = size_t>
void nanoflann::KDTreeSingleIndexAdaptor< Distance, DatasetAdaptor, DIM, IndexType >::loadIndex ( FILE *  stream) [inline]

Loads a previous index from a binary file. IMPORTANT NOTE: The set of data points is NOT stored in the file, so the index object must be constructed associated to the same source of data points used while building the index. See the example: examples/saveload_example.cpp

See also:
loadIndex

Definition at line 1336 of file nanoflann.hpp.

template<typename Distance , class DatasetAdaptor , int DIM = -1, typename IndexType = size_t>
void nanoflann::KDTreeSingleIndexAdaptor< Distance, DatasetAdaptor, DIM, IndexType >::middleSplit ( IndexType *  ind,
IndexType  count,
IndexType &  index,
int &  cutfeat,
DistanceType cutval,
const BoundingBox bbox 
) [inline, private]

Definition at line 1119 of file nanoflann.hpp.

template<typename Distance , class DatasetAdaptor , int DIM = -1, typename IndexType = size_t>
void nanoflann::KDTreeSingleIndexAdaptor< Distance, DatasetAdaptor, DIM, IndexType >::middleSplit_ ( IndexType *  ind,
IndexType  count,
IndexType &  index,
int &  cutfeat,
DistanceType cutval,
const BoundingBox bbox 
) [inline, private]

Definition at line 1164 of file nanoflann.hpp.

template<typename Distance , class DatasetAdaptor , int DIM = -1, typename IndexType = size_t>
void nanoflann::KDTreeSingleIndexAdaptor< Distance, DatasetAdaptor, DIM, IndexType >::planeSplit ( IndexType *  ind,
const IndexType  count,
int  cutfeat,
DistanceType  cutval,
IndexType &  lim1,
IndexType &  lim2 
) [inline, private]

Subdivide the list of points by a plane perpendicular on axe corresponding to the 'cutfeat' dimension at 'cutval' position.

On return: dataset[ind[0..lim1-1]][cutfeat]<cutval dataset[ind[lim1..lim2-1]][cutfeat]==cutval dataset[ind[lim2..count]][cutfeat]>cutval

Definition at line 1215 of file nanoflann.hpp.

template<typename Distance , class DatasetAdaptor , int DIM = -1, typename IndexType = size_t>
size_t nanoflann::KDTreeSingleIndexAdaptor< Distance, DatasetAdaptor, DIM, IndexType >::radiusSearch ( const ElementType query_point,
const DistanceType  radius,
std::vector< std::pair< IndexType, DistanceType > > &  IndicesDists,
const SearchParams searchParams 
) const [inline]

Find all the neighbors to query_point[0:dim-1] within a maximum radius. The output is given as a vector of pairs, of which the first element is a point index and the second the corresponding distance. Previous contents of IndicesDists are cleared.

If searchParams.sorted==true, the output list is sorted by ascending distances.

For a better performance, it is advisable to do a .reserve() on the vector if you have any wild guess about the number of expected matches.

See also:
knnSearch, findNeighbors
Returns:
The number of points within the given radius (i.e. indices.size() or dists.size() )

Definition at line 970 of file nanoflann.hpp.

template<typename Distance , class DatasetAdaptor , int DIM = -1, typename IndexType = size_t>
void nanoflann::KDTreeSingleIndexAdaptor< Distance, DatasetAdaptor, DIM, IndexType >::save_tree ( FILE *  stream,
NodePtr  tree 
) [inline, private]

Definition at line 999 of file nanoflann.hpp.

template<typename Distance , class DatasetAdaptor , int DIM = -1, typename IndexType = size_t>
void nanoflann::KDTreeSingleIndexAdaptor< Distance, DatasetAdaptor, DIM, IndexType >::saveIndex ( FILE *  stream) [inline]

Stores the index in a binary file. IMPORTANT NOTE: The set of data points is NOT stored in the file, so when loading the index object it must be constructed associated to the same source of data points used while building it. See the example: examples/saveload_example.cpp

See also:
loadIndex

Definition at line 1322 of file nanoflann.hpp.

template<typename Distance , class DatasetAdaptor , int DIM = -1, typename IndexType = size_t>
template<class RESULTSET >
void nanoflann::KDTreeSingleIndexAdaptor< Distance, DatasetAdaptor, DIM, IndexType >::searchLevel ( RESULTSET &  result_set,
const ElementType vec,
const NodePtr  node,
DistanceType  mindistsq,
distance_vector_t dists,
const float  epsError 
) const [inline, private]

Performs an exact search in the tree starting from a node.

Template Parameters:
RESULTSETShould be any ResultSet<DistanceType>

Definition at line 1268 of file nanoflann.hpp.

template<typename Distance , class DatasetAdaptor , int DIM = -1, typename IndexType = size_t>
size_t nanoflann::KDTreeSingleIndexAdaptor< Distance, DatasetAdaptor, DIM, IndexType >::size ( ) const [inline]

Returns size of index.

Definition at line 896 of file nanoflann.hpp.

template<typename Distance , class DatasetAdaptor , int DIM = -1, typename IndexType = size_t>
size_t nanoflann::KDTreeSingleIndexAdaptor< Distance, DatasetAdaptor, DIM, IndexType >::usedMemory ( ) const [inline]

Computes the inde memory usage Returns: memory used by the index

Definition at line 913 of file nanoflann.hpp.

template<typename Distance , class DatasetAdaptor , int DIM = -1, typename IndexType = size_t>
size_t nanoflann::KDTreeSingleIndexAdaptor< Distance, DatasetAdaptor, DIM, IndexType >::veclen ( ) const [inline]

Returns the length of an index feature.

Definition at line 904 of file nanoflann.hpp.


Member Data Documentation

template<typename Distance , class DatasetAdaptor , int DIM = -1, typename IndexType = size_t>
const DatasetAdaptor& nanoflann::KDTreeSingleIndexAdaptor< Distance, DatasetAdaptor, DIM, IndexType >::dataset [protected]

The source of our data.

The dataset used by this index

Definition at line 754 of file nanoflann.hpp.

template<typename Distance , class DatasetAdaptor , int DIM = -1, typename IndexType = size_t>
int nanoflann::KDTreeSingleIndexAdaptor< Distance, DatasetAdaptor, DIM, IndexType >::dim [protected]

Dimensionality of each data point.

Definition at line 759 of file nanoflann.hpp.

template<typename Distance , class DatasetAdaptor , int DIM = -1, typename IndexType = size_t>
Distance nanoflann::KDTreeSingleIndexAdaptor< Distance, DatasetAdaptor, DIM, IndexType >::distance

Definition at line 843 of file nanoflann.hpp.

template<typename Distance , class DatasetAdaptor , int DIM = -1, typename IndexType = size_t>
const KDTreeSingleIndexAdaptorParams nanoflann::KDTreeSingleIndexAdaptor< Distance, DatasetAdaptor, DIM, IndexType >::index_params [protected]

Definition at line 756 of file nanoflann.hpp.

template<typename Distance , class DatasetAdaptor , int DIM = -1, typename IndexType = size_t>
size_t nanoflann::KDTreeSingleIndexAdaptor< Distance, DatasetAdaptor, DIM, IndexType >::m_leaf_max_size [protected]

Definition at line 748 of file nanoflann.hpp.

template<typename Distance , class DatasetAdaptor , int DIM = -1, typename IndexType = size_t>
size_t nanoflann::KDTreeSingleIndexAdaptor< Distance, DatasetAdaptor, DIM, IndexType >::m_size [protected]

Definition at line 758 of file nanoflann.hpp.

template<typename Distance , class DatasetAdaptor , int DIM = -1, typename IndexType = size_t>
PooledAllocator nanoflann::KDTreeSingleIndexAdaptor< Distance, DatasetAdaptor, DIM, IndexType >::pool [protected]

Pooled memory allocator.

Using a pooled memory allocator is more efficient than allocating memory directly when there is a large number small of memory allocations.

Definition at line 839 of file nanoflann.hpp.

template<typename Distance , class DatasetAdaptor , int DIM = -1, typename IndexType = size_t>
BoundingBox nanoflann::KDTreeSingleIndexAdaptor< Distance, DatasetAdaptor, DIM, IndexType >::root_bbox [protected]

Definition at line 830 of file nanoflann.hpp.

template<typename Distance , class DatasetAdaptor , int DIM = -1, typename IndexType = size_t>
NodePtr nanoflann::KDTreeSingleIndexAdaptor< Distance, DatasetAdaptor, DIM, IndexType >::root_node [protected]

Array of k-d trees used to find neighbours.

Definition at line 826 of file nanoflann.hpp.

template<typename Distance , class DatasetAdaptor , int DIM = -1, typename IndexType = size_t>
std::vector<IndexType> nanoflann::KDTreeSingleIndexAdaptor< Distance, DatasetAdaptor, DIM, IndexType >::vind [protected]

Array of indices to vectors in the dataset.

Definition at line 746 of file nanoflann.hpp.


The documentation for this class was generated from the following file:


shape_reconstruction
Author(s): Roberto Martín-Martín
autogenerated on Sat Jun 8 2019 18:41:08