Template Class NearestNeighborsGNATNoThreadSafety
Defined in File NearestNeighborsGNATNoThreadSafety.h
Nested Relationships
Nested Types
Inheritance Relationships
Base Type
public ompl::NearestNeighbors< _T >
(Template Class NearestNeighbors)
Class Documentation
-
template<typename _T>
class NearestNeighborsGNATNoThreadSafety : public ompl::NearestNeighbors<_T> Geometric Near-neighbor Access Tree (GNAT), a data structure for nearest neighbor search.
If GNAT_SAMPLER is defined, then extra code will be enabled to sample elements from the GNAT with probability inversely proportial to their local density.
B. Gipson, M. Moll, and L.E. Kavraki, Resolution independent density estimation for motion planning in high-dimensional spaces, in IEEE Intl. Conf. on Robotics and Automation, 2013. [PDF]
- External documentation
S. Brin, Near neighbor search in large metric spaces, in Proc. 21st Conf. on Very Large Databases (VLDB), pp. 574–584, 1995.
Internal scratch space
Internal data structure to store nearest neighbors
-
mutable NearQueue nearQueue_
-
mutable NodeQueue nodeQueue_
Nodes yet to be processed for possible nearest neighbors.
-
mutable Permutation permutation_
Permutation of indices to process children of a node in random order.
-
mutable std::vector<unsigned int> pivots_
Pivot indices within a vector of elements as selected by GreedyKCenters.
-
mutable GreedyKCenters<_T>::Matrix distances_
Matrix of distances to pivots.
Public Functions
-
inline NearestNeighborsGNATNoThreadSafety(unsigned int degree = 8, unsigned int minDegree = 4, unsigned int maxDegree = 12, unsigned int maxNumPtsPerLeaf = 50, unsigned int removedCacheSize = 500, bool rebalancing = false)
-
inline ~NearestNeighborsGNATNoThreadSafety() override
-
inline void setDistanceFunction(const typename NearestNeighbors<_T>::DistanceFunction &distFun) override
Set the distance function to use.
-
inline virtual void clear() override
Clear the datastructure.
-
inline virtual bool reportsSortedResults() const override
Return true if the solutions reported by this data structure are sorted, when calling nearestK / nearestR.
-
inline void rebuildDataStructure()
Rebuild the internal data structure.
-
inline virtual bool remove(const _T &data) override
Remove data from the tree. The element won’t actually be removed immediately, but just marked for removal in the removed_ cache. When the cache is full, the tree will be rebuilt and the elements marked for removal will actually be removed.
-
inline virtual void nearestK(const _T &data, std::size_t k, std::vector<_T> &nbh) const override
Return the k nearest neighbors in sorted order.
-
inline virtual void nearestR(const _T &data, double radius, std::vector<_T> &nbh) const override
Return the nearest neighbors within distance
radius
in sorted order.
-
inline virtual std::size_t size() const override
Get the number of elements in the datastructure.
-
inline virtual void list(std::vector<_T> &data) const override
Get all the elements in the datastructure.
-
inline void integrityCheck()
Protected Types
-
using GNAT = NearestNeighborsGNATNoThreadSafety<_T>
Protected Functions
-
inline bool nearestKInternal(const _T &data, std::size_t k) const
Return in nearQueue_ the k nearest neighbors of data. For k=1, return true if the nearest neighbor is a pivot. (which is important during removal; removing pivots is a special case).
Protected Attributes
-
unsigned int degree_
The desired degree of each node.
-
unsigned int minDegree_
After splitting a Node, each child Node has degree equal to the default degree times the fraction of data elements from the original node that got assigned to that child Node. However, its degree can be no less than minDegree_.
-
unsigned int maxDegree_
After splitting a Node, each child Node has degree equal to the default degree times the fraction of data elements from the original node that got assigned to that child Node. However, its degree can be no larger than maxDegree_.
-
unsigned int maxNumPtsPerLeaf_
Maximum number of elements allowed to be stored in a Node before it needs to be split into several nodes.
-
std::size_t size_ = {0}
Number of elements stored in the tree.
-
std::size_t rebuildSize_
If size_ exceeds rebuildSize_, the tree will be rebuilt (and automatically rebalanced), and rebuildSize_ will be doubled.
-
std::size_t removedCacheSize_
Maximum number of removed elements that can be stored in the removed_ cache. If the cache is full, the tree will be rebuilt with the elements in removed_ actually removed from the tree.
-
GreedyKCenters<_T> pivotSelector_
The data structure used to split data into subtrees.
Friends
-
inline friend std::ostream &operator<<(std::ostream &out, const NearestNeighborsGNATNoThreadSafety<_T> &gnat)
Print a GNAT structure (mostly useful for debugging purposes).
-
class Node
The class used internally to define the GNAT.
Public Functions
-
inline Node(int degree, int capacity, _T pivot)
Construct a node of given degree with at most capacity data elements and with given pivot.
-
inline ~Node()
-
inline void updateRadius(double dist)
Update minRadius_ and maxRadius_, given that an element was added with distance dist to the pivot.
-
inline void updateRange(unsigned int i, double dist)
Update minRange_[i] and maxRange_[i], given that an element was added to the i-th child of the parent that has distance dist to this Node’s pivot.
-
inline bool needToSplit(const GNAT &gnat) const
Return true iff the node needs to be split into child nodes.
-
inline void split(GNAT &gnat)
The split operation finds pivot elements for the child nodes and moves each data element of this node to the appropriate child node.
-
inline bool insertNeighborK(NearQueue &nbh, std::size_t k, const _T &data, const _T &key, double dist) const
Insert data in nbh if it is a near neighbor. Return true iff data was added to nbh.
-
inline void nearestK(const GNAT &gnat, const _T &data, std::size_t k, bool &isPivot) const
Compute the k nearest neighbors of data in the tree. For k=1, isPivot is true if the nearest neighbor is a pivot (which is important during removal; removing pivots is a special case).
-
inline void insertNeighborR(NearQueue &nbh, double r, const _T &data, double dist) const
Insert data in nbh if it is a near neighbor.
Public Members
-
unsigned int degree_
Number of child nodes.
-
double minRadius_
Minimum distance between the pivot element and the elements stored in data_.
-
double maxRadius_
Maximum distance between the pivot element and the elements stored in data_.
-
std::vector<double> minRange_
The i-th element in minRange_ is the minimum distance between the pivot and any data_ element in the i-th child node of this node’s parent.
-
std::vector<double> maxRange_
The i-th element in maxRange_ is the maximum distance between the pivot and any data_ element in the i-th child node of this node’s parent.
-
std::vector<_T> data_
The data elements stored in this node (in addition to the pivot element). An internal node has no elements stored in data_.
-
std::vector<Node*> children_
The child nodes of this node. By definition, only internal nodes have child nodes.
-
mutable double distToPivot_
Scratch space to store distance to pivot during nearest neighbor queries.
-
inline Node(int degree, int capacity, _T pivot)