moveit2
The MoveIt Motion Planning Framework for ROS 2.
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]
Collaboration diagram for cached_ik_kinematics_plugin::NearestNeighborsGNAT< _T >:
Collaboration graph
[legend]

Classes

class  Node
 

Public Member Functions

 NearestNeighborsGNAT (unsigned int degree=8, unsigned int minDegree=4, unsigned int maxDegree=12, unsigned int maxNumPtsPerLeaf=50, unsigned int removedCacheSize=500, bool rebalancing=false)
 
 ~NearestNeighborsGNAT () override
 
void setDistanceFunction (const typename NearestNeighbors< _T >::DistanceFunction &distFun) override
 
void clear () override
 Clear 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 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 rebuildDataStructure ()
 
bool remove (const _T &data) override
 Remove an element from 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...
 
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...
 
std::size_t size () const override
 Get the number of elements in the datastructure. More...
 
void list (std::vector< _T > &data) const override
 Get all the elements in the datastructure. More...
 
void integrityCheck ()
 
- Public Member Functions inherited from cached_ik_kinematics_plugin::NearestNeighbors< _T >
 NearestNeighbors ()=default
 
 NearestNeighbors (const NearestNeighbors &)=default
 
 NearestNeighbors (NearestNeighbors &&) noexcept=default
 
NearestNeighborsoperator= (const NearestNeighbors &)=default
 
NearestNeighborsoperator= (NearestNeighbors &&) noexcept=default
 
virtual ~NearestNeighbors ()=default
 
virtual void setDistanceFunction (const DistanceFunction &distFun)
 Set the distance function to use. More...
 
const DistanceFunctiongetDistanceFunction () const
 Get the distance function used. More...
 

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

Nodetree_ { nullptr }
 
unsigned int degree_
 
unsigned int minDegree_
 
unsigned int maxDegree_
 
unsigned int maxNumPtsPerLeaf_
 
std::size_t size_ { 0 }
 
std::size_t rebuildSize_
 
std::size_t removedCacheSize_
 
GreedyKCenters< _T > pivotSelector_
 
std::unordered_set< const _T * > removed_
 
- 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 70 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 314 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 101 of file NearestNeighborsGNAT.h.

◆ ~NearestNeighborsGNAT()

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

Definition at line 114 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 146 of file NearestNeighborsGNAT.h.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ 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 160 of file NearestNeighborsGNAT.h.

Here is the call graph for this function:

◆ 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 128 of file NearestNeighborsGNAT.h.

Here is the caller graph for this function:

◆ integrityCheck()

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

Definition at line 278 of file NearestNeighborsGNAT.h.

Here is the call graph for this function:

◆ isRemoved()

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

Definition at line 317 of file NearestNeighborsGNAT.h.

Here is the caller graph for this function:

◆ 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 251 of file NearestNeighborsGNAT.h.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ 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 208 of file NearestNeighborsGNAT.h.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ 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 221 of file NearestNeighborsGNAT.h.

Here is the call graph for this function:

◆ 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 326 of file NearestNeighborsGNAT.h.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ 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 235 of file NearestNeighborsGNAT.h.

Here is the call graph for this function:

◆ nearestRInternal()

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

Definition at line 349 of file NearestNeighborsGNAT.h.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ postprocessNearest()

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

Definition at line 368 of file NearestNeighborsGNAT.h.

Here is the caller graph for this function:

◆ rebuildDataStructure()

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

Definition at line 177 of file NearestNeighborsGNAT.h.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ 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 189 of file NearestNeighborsGNAT.h.

Here is the call graph for this function:

◆ 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 141 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 120 of file NearestNeighborsGNAT.h.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ 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 246 of file NearestNeighborsGNAT.h.

Here is the caller graph for this function:

Friends And Related Function Documentation

◆ operator<<

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

Definition at line 260 of file NearestNeighborsGNAT.h.

Member Data Documentation

◆ degree_

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

Definition at line 727 of file NearestNeighborsGNAT.h.

◆ maxDegree_

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

Definition at line 737 of file NearestNeighborsGNAT.h.

◆ maxNumPtsPerLeaf_

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

Definition at line 740 of file NearestNeighborsGNAT.h.

◆ minDegree_

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

Definition at line 732 of file NearestNeighborsGNAT.h.

◆ pivotSelector_

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

Definition at line 751 of file NearestNeighborsGNAT.h.

◆ rebuildSize_

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

Definition at line 745 of file NearestNeighborsGNAT.h.

◆ removed_

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

Definition at line 753 of file NearestNeighborsGNAT.h.

◆ removedCacheSize_

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

Definition at line 749 of file NearestNeighborsGNAT.h.

◆ size_

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

Definition at line 742 of file NearestNeighborsGNAT.h.

◆ tree_

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

Definition at line 725 of file NearestNeighborsGNAT.h.


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