Classes | Public Types | Public Member Functions | Protected Member Functions | Protected Attributes
vcg::KdTree< _Scalar > Class Template Reference

#include <kdtree.h>

List of all members.

Classes

struct  Node
struct  QueryNode

Public Types

typedef vcg::Box3< ScalarAxisAlignedBoxType
typedef std::vector< NodeNodeList
typedef HeapMaxPriorityQueue
< int, Scalar
PriorityQueue
typedef _Scalar Scalar
typedef vcg::Point3< ScalarVectorType

Public Member Functions

const NodeList_getNodes (void)
const std::vector< VectorType > & _getPoints (void)
void doQueryClosest (const VectorType &queryPoint, unsigned int &index, Scalar &dist)
void doQueryDist (const VectorType &queryPoint, float dist, std::vector< unsigned int > &points, std::vector< Scalar > &sqrareDists)
void doQueryK (const VectorType &queryPoint, int k, PriorityQueue &mNeighborQueue)
 KdTree (const ConstDataWrapper< VectorType > &points, unsigned int nofPointsPerCell=16, unsigned int maxDepth=64)
 ~KdTree ()

Protected Member Functions

int createTree (unsigned int nodeId, unsigned int start, unsigned int end, unsigned int level, unsigned int targetCellsize, unsigned int targetMaxDepth)
unsigned int split (int start, int end, unsigned int dim, float splitValue)

Protected Attributes

AxisAlignedBoxType mAABB
std::vector< unsigned int > mIndices
NodeList mNodes
std::vector< VectorTypemPoints

Detailed Description

template<typename _Scalar>
class vcg::KdTree< _Scalar >

This class allows to create a Kd-Tree thought to perform the neighbour query (radius search, knn-nearest serach and closest search). The class implemetantion is thread-safe.

Definition at line 83 of file kdtree.h.


Member Typedef Documentation

template<typename _Scalar>
typedef vcg::Box3<Scalar> vcg::KdTree< _Scalar >::AxisAlignedBoxType

Definition at line 89 of file kdtree.h.

template<typename _Scalar>
typedef std::vector<Node> vcg::KdTree< _Scalar >::NodeList

Definition at line 110 of file kdtree.h.

template<typename _Scalar>
typedef HeapMaxPriorityQueue<int, Scalar> vcg::KdTree< _Scalar >::PriorityQueue

Definition at line 91 of file kdtree.h.

template<typename _Scalar>
typedef _Scalar vcg::KdTree< _Scalar >::Scalar

Definition at line 87 of file kdtree.h.

template<typename _Scalar>
typedef vcg::Point3<Scalar> vcg::KdTree< _Scalar >::VectorType

Definition at line 88 of file kdtree.h.


Constructor & Destructor Documentation

template<typename Scalar >
vcg::KdTree< Scalar >::KdTree ( const ConstDataWrapper< VectorType > &  points,
unsigned int  nofPointsPerCell = 16,
unsigned int  maxDepth = 64 
)

Definition at line 154 of file kdtree.h.

template<typename Scalar >
vcg::KdTree< Scalar >::~KdTree ( )

Definition at line 176 of file kdtree.h.


Member Function Documentation

template<typename _Scalar>
const NodeList& vcg::KdTree< _Scalar >::_getNodes ( void  ) [inline]

Definition at line 113 of file kdtree.h.

template<typename _Scalar>
const std::vector<VectorType>& vcg::KdTree< _Scalar >::_getPoints ( void  ) [inline]

Definition at line 114 of file kdtree.h.

template<typename Scalar >
int vcg::KdTree< Scalar >::createTree ( unsigned int  nodeId,
unsigned int  start,
unsigned int  end,
unsigned int  level,
unsigned int  targetCellSize,
unsigned int  targetMaxDepth 
) [protected]

recursively builds the kdtree

The heuristic is the following:

  • if the number of points in the node is lower than targetCellsize then make a leaf
  • else compute the AABB of the points of the node and split it at the middle of the largest AABB dimension.

This strategy might look not optimal because it does not explicitly prune empty space, unlike more advanced SAH-like techniques used for RT. On the other hand it leads to a shorter tree, faster to traverse and our experience shown that in the special case of kNN queries, this strategy is indeed more efficient (and much faster to build). Moreover, for volume data (e.g., fluid simulation) pruning the empty space is useless.

Actually, storing at each node the exact AABB (we therefore have a binary BVH) allows to prune only about 10% of the leaves, but the overhead of this pruning (ball/ABBB intersection) is more expensive than the gain it provides and the memory consumption is x4 higher !

Definition at line 441 of file kdtree.h.

template<typename Scalar >
void vcg::KdTree< Scalar >::doQueryClosest ( const VectorType queryPoint,
unsigned int &  index,
Scalar dist 
)

Searchs the closest point.

The result of the query, the closest point to the query point, is the index of the point and and the squared distance from the query point.

Definition at line 336 of file kdtree.h.

template<typename Scalar >
void vcg::KdTree< Scalar >::doQueryDist ( const VectorType queryPoint,
float  dist,
std::vector< unsigned int > &  points,
std::vector< Scalar > &  sqrareDists 
)

Performs the distance query.

The result of the query, all the points within the distance dist form the query point, is the vector of the indeces and the vector of the squared distances from the query point.

Definition at line 273 of file kdtree.h.

template<typename Scalar >
void vcg::KdTree< Scalar >::doQueryK ( const VectorType queryPoint,
int  k,
PriorityQueue mNeighborQueue 
)

Performs the kNN query.

This algorithm uses the simple distance to the split plane to prune nodes. A more elaborated approach consists to track the closest corner of the cell relatively to the current query point. This strategy allows to save about 5% of the leaves. However, in practice the slight overhead due to this tracking reduces the overall performance.

This algorithm also use a simple stack while a priority queue using the squared distances to the cells as a priority values allows to save about 10% of the leaves. But, again, priority queue insertions and deletions are quite involved, and therefore a simple stack is by far much faster.

The result of the query, the k-nearest neighbors, are stored into the stack mNeighborQueue, where the topmost element [0] is NOT the nearest but the farthest!! (they are not sorted but arranged into a heap).

Definition at line 198 of file kdtree.h.

template<typename Scalar >
unsigned int vcg::KdTree< Scalar >::split ( int  start,
int  end,
unsigned int  dim,
float  splitValue 
) [protected]

Split the subarray between start and end in two part, one with the elements less than splitValue, the other with the elements greater or equal than splitValue. The elements are compared using the "dim" coordinate [0 = x, 1 = y, 2 = z].

Definition at line 405 of file kdtree.h.


Member Data Documentation

template<typename _Scalar>
AxisAlignedBoxType vcg::KdTree< _Scalar >::mAABB [protected]

Definition at line 147 of file kdtree.h.

template<typename _Scalar>
std::vector<unsigned int> vcg::KdTree< _Scalar >::mIndices [protected]

Definition at line 150 of file kdtree.h.

template<typename _Scalar>
NodeList vcg::KdTree< _Scalar >::mNodes [protected]

Definition at line 148 of file kdtree.h.

template<typename _Scalar>
std::vector<VectorType> vcg::KdTree< _Scalar >::mPoints [protected]

Definition at line 149 of file kdtree.h.


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:18