Classes | Public Member Functions | Protected Types | Protected Member Functions | Protected Attributes | Friends | List of all members
cached_ik_kinematics_plugin::NearestNeighborsGNAT< _T > Class Template Reference

Geometric Near-neighbor Access Tree (GNAT), a data structure for nearest neighbor search. More...

#include <NearestNeighborsGNAT.h>

Inheritance diagram for cached_ik_kinematics_plugin::NearestNeighborsGNAT< _T >:
Inheritance graph
[legend]

Classes

class  Node
 

Public Member Functions

void add (const _T &data) override
 Add an element to the datastructure. More...
 
void add (const std::vector< _T > &data) override
 Add a vector of points. More...
 
void clear () override
 Clear the datastructure. More...
 
void integrityCheck ()
 
void list (std::vector< _T > &data) const override
 Get all the elements in the datastructure. More...
 
_T nearest (const _T &data) const override
 Get the nearest neighbor of a point. More...
 
void nearestK (const _T &data, std::size_t k, std::vector< _T > &nbh) const override
 Get the k-nearest neighbors of a point. More...
 
 NearestNeighborsGNAT (unsigned int degree=8, unsigned int minDegree=4, unsigned int maxDegree=12, unsigned int maxNumPtsPerLeaf=50, unsigned int removedCacheSize=500, bool rebalancing=false)
 
void nearestR (const _T &data, double radius, std::vector< _T > &nbh) const override
 Get the nearest neighbors of a point, within a specified radius. More...
 
void rebuildDataStructure ()
 
bool remove (const _T &data) override
 Remove an element from the datastructure. More...
 
bool reportsSortedResults () const override
 Return true if the solutions reported by this data structure are sorted, when calling nearestK / nearestR. More...
 
void setDistanceFunction (const typename NearestNeighbors< _T >::DistanceFunction &distFun) override
 
std::size_t size () const override
 Get the number of elements in the datastructure. More...
 
 ~NearestNeighborsGNAT () override
 
- Public Member Functions inherited from cached_ik_kinematics_plugin::NearestNeighbors< _T >
const DistanceFunctiongetDistanceFunction () const
 Get the distance function used. More...
 
 NearestNeighbors ()=default
 
virtual void setDistanceFunction (const DistanceFunction &distFun)
 Set the distance function to use. More...
 
virtual ~NearestNeighbors ()=default
 

Protected Types

using GNAT = NearestNeighborsGNAT< _T >
 

Protected Member Functions

bool isRemoved (const _T &data) const
 
bool nearestKInternal (const _T &data, std::size_t k, NearQueue &nbhQueue) const
 
void nearestRInternal (const _T &data, double radius, NearQueue &nbhQueue) const
 
void postprocessNearest (NearQueue &nbhQueue, std::vector< _T > &nbh) const
 

Protected Attributes

unsigned int degree_
 
unsigned int maxDegree_
 
unsigned int maxNumPtsPerLeaf_
 
unsigned int minDegree_
 
GreedyKCenters< _T > pivotSelector_
 
std::size_t rebuildSize_
 
std::unordered_set< const _T * > removed_
 
std::size_t removedCacheSize_
 
std::size_t size_ { 0 }
 
Nodetree_ { nullptr }
 
- Protected Attributes inherited from cached_ik_kinematics_plugin::NearestNeighbors< _T >
DistanceFunction distFun_
 The used distance function. More...
 

Friends

std::ostream & operator<< (std::ostream &out, const NearestNeighborsGNAT< _T > &gnat)
 

Additional Inherited Members

- Public Types inherited from cached_ik_kinematics_plugin::NearestNeighbors< _T >
typedef std::function< double(const _T &, const _T &)> DistanceFunction
 The definition of a distance function. More...
 

Detailed Description

template<typename _T>
class cached_ik_kinematics_plugin::NearestNeighborsGNAT< _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.

External documentation
S. Brin, Near neighbor search in large metric spaces, in Proc. 21st Conf. on Very Large Databases (VLDB), pp. 574–584, 1995.

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]

Definition at line 100 of file NearestNeighborsGNAT.h.

Member Typedef Documentation

◆ GNAT

template<typename _T >
using cached_ik_kinematics_plugin::NearestNeighborsGNAT< _T >::GNAT = NearestNeighborsGNAT<_T>
protected

Definition at line 372 of file NearestNeighborsGNAT.h.

Constructor & Destructor Documentation

◆ NearestNeighborsGNAT()

template<typename _T >
cached_ik_kinematics_plugin::NearestNeighborsGNAT< _T >::NearestNeighborsGNAT ( unsigned int  degree = 8,
unsigned int  minDegree = 4,
unsigned int  maxDegree = 12,
unsigned int  maxNumPtsPerLeaf = 50,
unsigned int  removedCacheSize = 500,
bool  rebalancing = false 
)
inline

Definition at line 163 of file NearestNeighborsGNAT.h.

◆ ~NearestNeighborsGNAT()

template<typename _T >
cached_ik_kinematics_plugin::NearestNeighborsGNAT< _T >::~NearestNeighborsGNAT ( )
inlineoverride

Definition at line 176 of file NearestNeighborsGNAT.h.

Member Function Documentation

◆ add() [1/2]

template<typename _T >
void cached_ik_kinematics_plugin::NearestNeighborsGNAT< _T >::add ( const _T &  data)
inlineoverridevirtual

Add an element to the datastructure.

Implements cached_ik_kinematics_plugin::NearestNeighbors< _T >.

Definition at line 208 of file NearestNeighborsGNAT.h.

◆ add() [2/2]

template<typename _T >
void cached_ik_kinematics_plugin::NearestNeighborsGNAT< _T >::add ( const std::vector< _T > &  data)
inlineoverridevirtual

Add a vector of points.

Reimplemented from cached_ik_kinematics_plugin::NearestNeighbors< _T >.

Definition at line 222 of file NearestNeighborsGNAT.h.

◆ clear()

template<typename _T >
void cached_ik_kinematics_plugin::NearestNeighborsGNAT< _T >::clear ( )
inlineoverridevirtual

Clear the datastructure.

Implements cached_ik_kinematics_plugin::NearestNeighbors< _T >.

Definition at line 190 of file NearestNeighborsGNAT.h.

◆ integrityCheck()

template<typename _T >
void cached_ik_kinematics_plugin::NearestNeighborsGNAT< _T >::integrityCheck ( )
inline

Definition at line 338 of file NearestNeighborsGNAT.h.

◆ isRemoved()

template<typename _T >
bool cached_ik_kinematics_plugin::NearestNeighborsGNAT< _T >::isRemoved ( const _T &  data) const
inlineprotected

Definition at line 375 of file NearestNeighborsGNAT.h.

◆ list()

template<typename _T >
void cached_ik_kinematics_plugin::NearestNeighborsGNAT< _T >::list ( std::vector< _T > &  data) const
inlineoverridevirtual

Get all the elements in the datastructure.

Implements cached_ik_kinematics_plugin::NearestNeighbors< _T >.

Definition at line 311 of file NearestNeighborsGNAT.h.

◆ nearest()

template<typename _T >
_T cached_ik_kinematics_plugin::NearestNeighborsGNAT< _T >::nearest ( const _T &  data) const
inlineoverridevirtual

Get the nearest neighbor of a point.

Implements cached_ik_kinematics_plugin::NearestNeighbors< _T >.

Definition at line 268 of file NearestNeighborsGNAT.h.

◆ nearestK()

template<typename _T >
void cached_ik_kinematics_plugin::NearestNeighborsGNAT< _T >::nearestK ( const _T &  data,
std::size_t  k,
std::vector< _T > &  nbh 
) const
inlineoverridevirtual

Get the k-nearest neighbors of a point.

All the nearest neighbor structures currently return the neighbors in sorted order, but this is not required.

Implements cached_ik_kinematics_plugin::NearestNeighbors< _T >.

Definition at line 281 of file NearestNeighborsGNAT.h.

◆ nearestKInternal()

template<typename _T >
bool cached_ik_kinematics_plugin::NearestNeighborsGNAT< _T >::nearestKInternal ( const _T &  data,
std::size_t  k,
NearQueue &  nbhQueue 
) const
inlineprotected

Definition at line 384 of file NearestNeighborsGNAT.h.

◆ nearestR()

template<typename _T >
void cached_ik_kinematics_plugin::NearestNeighborsGNAT< _T >::nearestR ( const _T &  data,
double  radius,
std::vector< _T > &  nbh 
) const
inlineoverridevirtual

Get the nearest neighbors of a point, within a specified radius.

All the nearest neighbor structures currently return the neighbors in sorted order, but this is not required.

Implements cached_ik_kinematics_plugin::NearestNeighbors< _T >.

Definition at line 295 of file NearestNeighborsGNAT.h.

◆ nearestRInternal()

template<typename _T >
void cached_ik_kinematics_plugin::NearestNeighborsGNAT< _T >::nearestRInternal ( const _T &  data,
double  radius,
NearQueue &  nbhQueue 
) const
inlineprotected

Definition at line 407 of file NearestNeighborsGNAT.h.

◆ postprocessNearest()

template<typename _T >
void cached_ik_kinematics_plugin::NearestNeighborsGNAT< _T >::postprocessNearest ( NearQueue &  nbhQueue,
std::vector< _T > &  nbh 
) const
inlineprotected

Definition at line 426 of file NearestNeighborsGNAT.h.

◆ rebuildDataStructure()

template<typename _T >
void cached_ik_kinematics_plugin::NearestNeighborsGNAT< _T >::rebuildDataStructure ( )
inline

Definition at line 237 of file NearestNeighborsGNAT.h.

◆ remove()

template<typename _T >
bool cached_ik_kinematics_plugin::NearestNeighborsGNAT< _T >::remove ( const _T &  data)
inlineoverridevirtual

Remove an element from the datastructure.

Implements cached_ik_kinematics_plugin::NearestNeighbors< _T >.

Definition at line 249 of file NearestNeighborsGNAT.h.

◆ reportsSortedResults()

template<typename _T >
bool cached_ik_kinematics_plugin::NearestNeighborsGNAT< _T >::reportsSortedResults ( ) const
inlineoverridevirtual

Return true if the solutions reported by this data structure are sorted, when calling nearestK / nearestR.

Implements cached_ik_kinematics_plugin::NearestNeighbors< _T >.

Definition at line 203 of file NearestNeighborsGNAT.h.

◆ setDistanceFunction()

template<typename _T >
void cached_ik_kinematics_plugin::NearestNeighborsGNAT< _T >::setDistanceFunction ( const typename NearestNeighbors< _T >::DistanceFunction distFun)
inlineoverride

Definition at line 182 of file NearestNeighborsGNAT.h.

◆ size()

template<typename _T >
std::size_t cached_ik_kinematics_plugin::NearestNeighborsGNAT< _T >::size ( ) const
inlineoverridevirtual

Get the number of elements in the datastructure.

Implements cached_ik_kinematics_plugin::NearestNeighbors< _T >.

Definition at line 306 of file NearestNeighborsGNAT.h.

Friends And Related Function Documentation

◆ operator<<

template<typename _T >
std::ostream& operator<< ( std::ostream &  out,
const NearestNeighborsGNAT< _T > &  gnat 
)
friend

Definition at line 320 of file NearestNeighborsGNAT.h.

Member Data Documentation

◆ degree_

template<typename _T >
unsigned int cached_ik_kinematics_plugin::NearestNeighborsGNAT< _T >::degree_
protected

Definition at line 758 of file NearestNeighborsGNAT.h.

◆ maxDegree_

template<typename _T >
unsigned int cached_ik_kinematics_plugin::NearestNeighborsGNAT< _T >::maxDegree_
protected

Definition at line 768 of file NearestNeighborsGNAT.h.

◆ maxNumPtsPerLeaf_

template<typename _T >
unsigned int cached_ik_kinematics_plugin::NearestNeighborsGNAT< _T >::maxNumPtsPerLeaf_
protected

Definition at line 771 of file NearestNeighborsGNAT.h.

◆ minDegree_

template<typename _T >
unsigned int cached_ik_kinematics_plugin::NearestNeighborsGNAT< _T >::minDegree_
protected

Definition at line 763 of file NearestNeighborsGNAT.h.

◆ pivotSelector_

template<typename _T >
GreedyKCenters<_T> cached_ik_kinematics_plugin::NearestNeighborsGNAT< _T >::pivotSelector_
protected

Definition at line 782 of file NearestNeighborsGNAT.h.

◆ rebuildSize_

template<typename _T >
std::size_t cached_ik_kinematics_plugin::NearestNeighborsGNAT< _T >::rebuildSize_
protected

Definition at line 776 of file NearestNeighborsGNAT.h.

◆ removed_

template<typename _T >
std::unordered_set<const _T*> cached_ik_kinematics_plugin::NearestNeighborsGNAT< _T >::removed_
protected

Definition at line 784 of file NearestNeighborsGNAT.h.

◆ removedCacheSize_

template<typename _T >
std::size_t cached_ik_kinematics_plugin::NearestNeighborsGNAT< _T >::removedCacheSize_
protected

Definition at line 780 of file NearestNeighborsGNAT.h.

◆ size_

template<typename _T >
std::size_t cached_ik_kinematics_plugin::NearestNeighborsGNAT< _T >::size_ { 0 }
protected

Definition at line 773 of file NearestNeighborsGNAT.h.

◆ tree_

template<typename _T >
Node* cached_ik_kinematics_plugin::NearestNeighborsGNAT< _T >::tree_ { nullptr }
protected

Definition at line 756 of file NearestNeighborsGNAT.h.


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


moveit_kinematics
Author(s): Dave Coleman , Ioan Sucan , Sachin Chitta
autogenerated on Sat Apr 27 2024 02:26:15