Public Types | Public Member Functions | Public Attributes | List of all members
nanoflann::KDTreeSingleIndexDynamicAdaptor_< Distance, DatasetAdaptor, DIM, IndexType > Class Template Reference

#include <nanoflann.hpp>

Inheritance diagram for nanoflann::KDTreeSingleIndexDynamicAdaptor_< Distance, DatasetAdaptor, DIM, IndexType >:
Inheritance graph
[legend]

Public Types

typedef nanoflann::KDTreeBaseClass< nanoflann::KDTreeSingleIndexDynamicAdaptor_< Distance, DatasetAdaptor, DIM, IndexType >, Distance, DatasetAdaptor, DIM, IndexType > BaseClassRef
 
typedef BaseClassRef::BoundingBox BoundingBox
 
typedef BaseClassRef::distance_vector_t distance_vector_t
 
typedef BaseClassRef::DistanceType DistanceType
 
typedef BaseClassRef::ElementType ElementType
 
typedef BaseClassRef::Interval Interval
 
typedef BaseClassRef::Node Node
 
typedef NodeNodePtr
 
- Public Types inherited from nanoflann::KDTreeBaseClass< KDTreeSingleIndexDynamicAdaptor_< Distance, DatasetAdaptor, -1, size_t >, Distance, DatasetAdaptor, -1, size_t >
typedef array_or_vector_selector< DIM, Interval >::container_t BoundingBox
 
typedef array_or_vector_selector< DIM, DistanceType >::container_t distance_vector_t
 
typedef Distance::DistanceType DistanceType
 
typedef Distance::ElementType ElementType
 
typedef Node * NodePtr
 

Public Member Functions

void buildIndex ()
 
void computeBoundingBox (BoundingBox &bbox)
 
 KDTreeSingleIndexDynamicAdaptor_ (const int dimensionality, const DatasetAdaptor &inputData, std::vector< int > &treeIndex_, const KDTreeSingleIndexAdaptorParams &params=KDTreeSingleIndexAdaptorParams())
 
void loadIndex (FILE *stream)
 
KDTreeSingleIndexDynamicAdaptor_ operator= (const KDTreeSingleIndexDynamicAdaptor_ &rhs)
 
void saveIndex (FILE *stream)
 
template<class RESULTSET >
void searchLevel (RESULTSET &result_set, const ElementType *vec, const NodePtr node, DistanceType mindistsq, distance_vector_t &dists, const float epsError) const
 
Query methods
template<typename RESULTSET >
bool findNeighbors (RESULTSET &result, const ElementType *vec, const SearchParams &searchParams) const
 
size_t knnSearch (const ElementType *query_point, const size_t num_closest, IndexType *out_indices, DistanceType *out_distances_sq, const int=10) const
 
size_t radiusSearch (const ElementType *query_point, const DistanceType &radius, std::vector< std::pair< IndexType, DistanceType >> &IndicesDists, const SearchParams &searchParams) const
 
template<class SEARCH_CALLBACK >
size_t radiusSearchCustomCallback (const ElementType *query_point, SEARCH_CALLBACK &resultSet, const SearchParams &searchParams=SearchParams()) const
 
- Public Member Functions inherited from nanoflann::KDTreeBaseClass< KDTreeSingleIndexDynamicAdaptor_< Distance, DatasetAdaptor, -1, size_t >, Distance, DatasetAdaptor, -1, size_t >
DistanceType computeInitialDistances (const KDTreeSingleIndexDynamicAdaptor_< Distance, DatasetAdaptor, -1, size_t > &obj, const ElementType *vec, distance_vector_t &dists) const
 
void computeMinMax (const KDTreeSingleIndexDynamicAdaptor_< Distance, DatasetAdaptor, -1, size_t > &obj, size_t *ind, size_t count, int element, ElementType &min_elem, ElementType &max_elem)
 
ElementType dataset_get (const KDTreeSingleIndexDynamicAdaptor_< Distance, DatasetAdaptor, -1, size_t > &obj, size_t idx, int component) const
 Helper accessor to the dataset points: More...
 
NodePtr divideTree (KDTreeSingleIndexDynamicAdaptor_< Distance, DatasetAdaptor, -1, size_t > &obj, const size_t left, const size_t right, BoundingBox &bbox)
 
void freeIndex (KDTreeSingleIndexDynamicAdaptor_< Distance, DatasetAdaptor, -1, size_t > &obj)
 
void load_tree (KDTreeSingleIndexDynamicAdaptor_< Distance, DatasetAdaptor, -1, size_t > &obj, FILE *stream, NodePtr &tree)
 
void loadIndex_ (KDTreeSingleIndexDynamicAdaptor_< Distance, DatasetAdaptor, -1, size_t > &obj, FILE *stream)
 
void middleSplit_ (KDTreeSingleIndexDynamicAdaptor_< Distance, DatasetAdaptor, -1, size_t > &obj, size_t *ind, size_t count, size_t &index, int &cutfeat, DistanceType &cutval, const BoundingBox &bbox)
 
void planeSplit (KDTreeSingleIndexDynamicAdaptor_< Distance, DatasetAdaptor, -1, size_t > &obj, size_t *ind, const size_t count, int cutfeat, DistanceType &cutval, size_t &lim1, size_t &lim2)
 
void save_tree (KDTreeSingleIndexDynamicAdaptor_< Distance, DatasetAdaptor, -1, size_t > &obj, FILE *stream, NodePtr tree)
 
void saveIndex_ (KDTreeSingleIndexDynamicAdaptor_< Distance, DatasetAdaptor, -1, size_t > &obj, FILE *stream)
 
size_t size (const KDTreeSingleIndexDynamicAdaptor_< Distance, DatasetAdaptor, -1, size_t > &obj) const
 
size_t usedMemory (KDTreeSingleIndexDynamicAdaptor_< Distance, DatasetAdaptor, -1, size_t > &obj)
 
size_t veclen (const KDTreeSingleIndexDynamicAdaptor_< Distance, DatasetAdaptor, -1, size_t > &obj)
 

Public Attributes

const DatasetAdaptor & dataset
 The source of our data. More...
 
Distance distance
 
KDTreeSingleIndexAdaptorParams index_params
 
std::vector< int > & treeIndex
 
- Public Attributes inherited from nanoflann::KDTreeBaseClass< KDTreeSingleIndexDynamicAdaptor_< Distance, DatasetAdaptor, -1, size_t >, Distance, DatasetAdaptor, -1, size_t >
int dim
 Dimensionality of each data point. More...
 
size_t m_leaf_max_size
 
size_t m_size
 Number of current points in the dataset. More...
 
size_t m_size_at_index_build
 
PooledAllocator pool
 
BoundingBox root_bbox
 
NodePtr root_node
 
std::vector< size_t > vind
 

Detailed Description

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

kd-tree dynamic 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 poins
inline size_t kdtree_get_point_count() const { ... }
// Must return the dim'th component of the idx'th point in the class:
inline T kdtree_get_pt(const size_t idx, const size_t 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
DatasetAdaptorThe user-provided adaptor (see comments above).
DistanceThe distance metric to use: nanoflann::metric_L1, nanoflann::metric_L2, nanoflann::metric_L2_Simple, etc.
DIMDimensionality of data points (e.g. 3 for 3D points)
IndexTypeWill be typically size_t or int

Definition at line 1466 of file nanoflann.hpp.

Member Typedef Documentation

◆ BaseClassRef

template<typename Distance , class DatasetAdaptor , int DIM = -1, typename IndexType = size_t>
typedef nanoflann::KDTreeBaseClass< nanoflann::KDTreeSingleIndexDynamicAdaptor_<Distance, DatasetAdaptor, DIM, IndexType>, Distance, DatasetAdaptor, DIM, IndexType> nanoflann::KDTreeSingleIndexDynamicAdaptor_< Distance, DatasetAdaptor, DIM, IndexType >::BaseClassRef

Definition at line 1486 of file nanoflann.hpp.

◆ BoundingBox

template<typename Distance , class DatasetAdaptor , int DIM = -1, typename IndexType = size_t>
typedef BaseClassRef::BoundingBox nanoflann::KDTreeSingleIndexDynamicAdaptor_< Distance, DatasetAdaptor, DIM, IndexType >::BoundingBox

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

Definition at line 1497 of file nanoflann.hpp.

◆ distance_vector_t

template<typename Distance , class DatasetAdaptor , int DIM = -1, typename IndexType = size_t>
typedef BaseClassRef::distance_vector_t nanoflann::KDTreeSingleIndexDynamicAdaptor_< Distance, DatasetAdaptor, DIM, IndexType >::distance_vector_t

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

Definition at line 1501 of file nanoflann.hpp.

◆ DistanceType

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

Definition at line 1489 of file nanoflann.hpp.

◆ ElementType

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

Definition at line 1488 of file nanoflann.hpp.

◆ Interval

template<typename Distance , class DatasetAdaptor , int DIM = -1, typename IndexType = size_t>
typedef BaseClassRef::Interval nanoflann::KDTreeSingleIndexDynamicAdaptor_< Distance, DatasetAdaptor, DIM, IndexType >::Interval

Definition at line 1494 of file nanoflann.hpp.

◆ Node

template<typename Distance , class DatasetAdaptor , int DIM = -1, typename IndexType = size_t>
typedef BaseClassRef::Node nanoflann::KDTreeSingleIndexDynamicAdaptor_< Distance, DatasetAdaptor, DIM, IndexType >::Node

Definition at line 1491 of file nanoflann.hpp.

◆ NodePtr

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

Definition at line 1492 of file nanoflann.hpp.

Constructor & Destructor Documentation

◆ KDTreeSingleIndexDynamicAdaptor_()

template<typename Distance , class DatasetAdaptor , int DIM = -1, typename IndexType = size_t>
nanoflann::KDTreeSingleIndexDynamicAdaptor_< Distance, DatasetAdaptor, DIM, IndexType >::KDTreeSingleIndexDynamicAdaptor_ ( const int  dimensionality,
const DatasetAdaptor &  inputData,
std::vector< int > &  treeIndex_,
const KDTreeSingleIndexAdaptorParams params = KDTreeSingleIndexAdaptorParams() 
)
inline

KDTree constructor

Refer to docs in README.md or online in https://github.com/jlblancoc/nanoflann

The KD-Tree point dimension (the length of each point in the datase, e.g. 3 for 3D points) is determined by means of:

  • The DIM template parameter if >0 (highest priority)
  • Otherwise, the dimensionality parameter of this constructor.
Parameters
inputDataDataset with the input features
paramsBasically, the maximum leaf node size

Definition at line 1517 of file nanoflann.hpp.

Member Function Documentation

◆ buildIndex()

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

Builds the index

Definition at line 1553 of file nanoflann.hpp.

◆ computeBoundingBox()

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

Definition at line 1665 of file nanoflann.hpp.

◆ findNeighbors()

template<typename Distance , class DatasetAdaptor , int DIM = -1, typename IndexType = size_t>
template<typename RESULTSET >
bool nanoflann::KDTreeSingleIndexDynamicAdaptor_< 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>
Returns
True if the requested neighbors could be found.
See also
knnSearch, radiusSearch

Definition at line 1582 of file nanoflann.hpp.

◆ knnSearch()

template<typename Distance , class DatasetAdaptor , int DIM = -1, typename IndexType = size_t>
size_t nanoflann::KDTreeSingleIndexDynamicAdaptor_< Distance, DatasetAdaptor, DIM, IndexType >::knnSearch ( const ElementType query_point,
const size_t  num_closest,
IndexType *  out_indices,
DistanceType out_distances_sq,
const int  = 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.
Returns
Number N of valid points in the result set. Only the first N entries in out_indices and out_distances_sq will be valid. Return may be less than num_closest only if the number of elements in the tree is less than num_closest.

Definition at line 1612 of file nanoflann.hpp.

◆ loadIndex()

template<typename Distance , class DatasetAdaptor , int DIM = -1, typename IndexType = size_t>
void nanoflann::KDTreeSingleIndexDynamicAdaptor_< 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 1768 of file nanoflann.hpp.

◆ operator=()

template<typename Distance , class DatasetAdaptor , int DIM = -1, typename IndexType = size_t>
KDTreeSingleIndexDynamicAdaptor_ nanoflann::KDTreeSingleIndexDynamicAdaptor_< Distance, DatasetAdaptor, DIM, IndexType >::operator= ( const KDTreeSingleIndexDynamicAdaptor_< Distance, DatasetAdaptor, DIM, IndexType > &  rhs)
inline

Assignment operator definiton

Definition at line 1535 of file nanoflann.hpp.

◆ radiusSearch()

template<typename Distance , class DatasetAdaptor , int DIM = -1, typename IndexType = size_t>
size_t nanoflann::KDTreeSingleIndexDynamicAdaptor_< 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, radiusSearchCustomCallback
Returns
The number of points within the given radius (i.e. indices.size() or dists.size() )

Definition at line 1638 of file nanoflann.hpp.

◆ radiusSearchCustomCallback()

template<typename Distance , class DatasetAdaptor , int DIM = -1, typename IndexType = size_t>
template<class SEARCH_CALLBACK >
size_t nanoflann::KDTreeSingleIndexDynamicAdaptor_< Distance, DatasetAdaptor, DIM, IndexType >::radiusSearchCustomCallback ( const ElementType query_point,
SEARCH_CALLBACK &  resultSet,
const SearchParams searchParams = SearchParams() 
) const
inline

Just like radiusSearch() but with a custom callback class for each point found in the radius of the query. See the source of RadiusResultSet<> as a start point for your own classes.

See also
radiusSearch

Definition at line 1655 of file nanoflann.hpp.

◆ saveIndex()

template<typename Distance , class DatasetAdaptor , int DIM = -1, typename IndexType = size_t>
void nanoflann::KDTreeSingleIndexDynamicAdaptor_< 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 1761 of file nanoflann.hpp.

◆ searchLevel()

template<typename Distance , class DatasetAdaptor , int DIM = -1, typename IndexType = size_t>
template<class RESULTSET >
void nanoflann::KDTreeSingleIndexDynamicAdaptor_< 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

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

Template Parameters
RESULTSETShould be any ResultSet<DistanceType>

Definition at line 1695 of file nanoflann.hpp.

Member Data Documentation

◆ dataset

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

The source of our data.

The dataset used by this index

Definition at line 1474 of file nanoflann.hpp.

◆ distance

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

Definition at line 1480 of file nanoflann.hpp.

◆ index_params

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

Definition at line 1476 of file nanoflann.hpp.

◆ treeIndex

template<typename Distance , class DatasetAdaptor , int DIM = -1, typename IndexType = size_t>
std::vector<int>& nanoflann::KDTreeSingleIndexDynamicAdaptor_< Distance, DatasetAdaptor, DIM, IndexType >::treeIndex

Definition at line 1478 of file nanoflann.hpp.


The documentation for this class was generated from the following file:
nanoflann::KDTreeBaseClass< KDTreeSingleIndexDynamicAdaptor_< Distance, DatasetAdaptor, -1, size_t >, Distance, DatasetAdaptor, -1, size_t >::dim
int dim
Dimensionality of each data point.
Definition: nanoflann.hpp:787


slam_toolbox
Author(s): Steve Macenski
autogenerated on Mon Mar 11 2024 02:36:25