NearestNeighborsGNAT.h
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2011, Rice University
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of the Rice University nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *********************************************************************/
34 
35 /* Author: Mark Moll, Bryant Gipson */
36 
37 // This file is a slightly modified version of <ompl/datastructures/NearestNeighborsGNAT.h>
38 
39 #pragma once
40 
41 #include "NearestNeighbors.h"
42 #include "GreedyKCenters.h"
44 #include <unordered_set>
45 #include <queue>
46 #include <algorithm>
47 #include <utility>
48 
50 {
67 template <typename _T>
68 class NearestNeighborsGNAT : public NearestNeighbors<_T>
69 {
70 protected:
71  // \cond IGNORE
72  // internally, we use a priority queue for nearest neighbors, paired
73  // with their distance to the query point
74  using DataDist = std::pair<const _T*, double>;
75  struct DataDistCompare
76  {
77  bool operator()(const DataDist& d0, const DataDist& d1)
78  {
79  return d0.second < d1.second;
80  }
81  };
82  using NearQueue = std::priority_queue<DataDist, std::vector<DataDist>, DataDistCompare>;
83 
84  // another internal data structure is a priority queue of nodes to
85  // check next for possible nearest neighbors
86  class Node;
87  using NodeDist = std::pair<Node*, double>;
88  struct NodeDistCompare
89  {
90  bool operator()(const NodeDist& n0, const NodeDist& n1) const
91  {
92  return (n0.second - n0.first->maxRadius_) > (n1.second - n1.first->maxRadius_);
93  }
94  };
95  using NodeQueue = std::priority_queue<NodeDist, std::vector<NodeDist>, NodeDistCompare>;
96  // \endcond
97 
98 public:
99  NearestNeighborsGNAT(unsigned int degree = 8, unsigned int minDegree = 4, unsigned int maxDegree = 12,
100  unsigned int maxNumPtsPerLeaf = 50, unsigned int removedCacheSize = 500,
101  bool rebalancing = false)
102  : NearestNeighbors<_T>()
103  , degree_(degree)
104  , minDegree_(std::min(degree, minDegree))
105  , maxDegree_(std::max(maxDegree, degree))
106  , maxNumPtsPerLeaf_(maxNumPtsPerLeaf)
107  , rebuildSize_(rebalancing ? maxNumPtsPerLeaf * degree : std::numeric_limits<std::size_t>::max())
108  , removedCacheSize_(removedCacheSize)
109  {
110  }
111 
112  ~NearestNeighborsGNAT() override
113  {
114  if (tree_)
115  delete tree_;
116  }
117  // \brief Set the distance function to use
118  void setDistanceFunction(const typename NearestNeighbors<_T>::DistanceFunction& distFun) override
119  {
121  pivotSelector_.setDistanceFunction(distFun);
122  if (tree_)
124  }
125 
126  void clear() override
127  {
128  if (tree_)
129  {
130  delete tree_;
131  tree_ = nullptr;
132  }
133  size_ = 0;
134  removed_.clear();
135  if (rebuildSize_ != std::numeric_limits<std::size_t>::max())
137  }
138 
139  bool reportsSortedResults() const override
140  {
141  return true;
142  }
143 
144  void add(const _T& data) override
145  {
146  if (tree_)
147  {
148  if (isRemoved(data))
150  tree_->add(*this, data);
151  }
152  else
153  {
154  tree_ = new Node(degree_, maxNumPtsPerLeaf_, data);
155  size_ = 1;
156  }
157  }
158  void add(const std::vector<_T>& data) override
159  {
160  if (tree_)
162  else if (!data.empty())
163  {
164  tree_ = new Node(degree_, maxNumPtsPerLeaf_, data[0]);
165  for (unsigned int i = 1; i < data.size(); ++i)
166  tree_->data_.push_back(data[i]);
167  size_ += data.size();
168  if (tree_->needToSplit(*this))
169  tree_->split(*this);
170  }
171  }
172  // \brief Rebuild the internal data structure.
173  void rebuildDataStructure()
174  {
175  std::vector<_T> lst;
176  list(lst);
177  clear();
178  add(lst);
179  }
180  // \brief Remove data from the tree.
181  // The element won't actually be removed immediately, but just marked
182  // for removal in the removed_ cache. When the cache is full, the tree
183  // will be rebuilt and the elements marked for removal will actually
184  // be removed.
185  bool remove(const _T& data) override
186  {
187  if (size_ == 0u)
188  return false;
189  NearQueue nbh_queue;
190  // find data in tree
191  bool is_pivot = nearestKInternal(data, 1, nbh_queue);
192  const _T* d = nbh_queue.top().first;
193  if (*d != data)
194  return false;
195  removed_.insert(d);
196  size_--;
197  // if we removed a pivot or if the capacity of removed elements
198  // has been reached, we rebuild the entire GNAT
199  if (is_pivot || removed_.size() >= removedCacheSize_)
201  return true;
202  }
203 
204  _T nearest(const _T& data) const override
205  {
206  if (size_)
207  {
208  NearQueue nbh_queue;
209  nearestKInternal(data, 1, nbh_queue);
210  if (!nbh_queue.empty())
211  return *nbh_queue.top().first;
212  }
213  throw moveit::Exception("No elements found in nearest neighbors data structure");
214  }
215 
216  // Return the k nearest neighbors in sorted order
217  void nearestK(const _T& data, std::size_t k, std::vector<_T>& nbh) const override
218  {
219  nbh.clear();
220  if (k == 0)
221  return;
222  if (size_)
223  {
224  NearQueue nbh_queue;
225  nearestKInternal(data, k, nbh_queue);
226  postprocessNearest(nbh_queue, nbh);
227  }
228  }
229 
230  // Return the nearest neighbors within distance \c radius in sorted order
231  void nearestR(const _T& data, double radius, std::vector<_T>& nbh) const override
232  {
233  nbh.clear();
234  if (size_)
235  {
236  NearQueue nbh_queue;
237  nearestRInternal(data, radius, nbh_queue);
238  postprocessNearest(nbh_queue, nbh);
239  }
240  }
241 
242  std::size_t size() const override
243  {
244  return size_;
245  }
246 
247  void list(std::vector<_T>& data) const override
248  {
249  data.clear();
250  data.reserve(size());
251  if (tree_)
252  tree_->list(*this, data);
253  }
254 
255  // \brief Print a GNAT structure (mostly useful for debugging purposes).
256  friend std::ostream& operator<<(std::ostream& out, const NearestNeighborsGNAT<_T>& gnat)
257  {
258  if (gnat.tree_)
259  {
260  out << *gnat.tree_;
261  if (!gnat.removed_.empty())
262  {
263  out << "Elements marked for removal:\n";
264  for (typename std::unordered_set<const _T*>::const_iterator it = gnat.removed_.begin();
265  it != gnat.removed_.end(); it++)
266  out << **it << '\t';
267  out << std::endl;
268  }
269  }
270  return out;
271  }
272 
273  // for debugging purposes
274  void integrityCheck()
275  {
276  std::vector<_T> lst;
277  std::unordered_set<const _T*> tmp;
278  // get all elements, including those marked for removal
279  removed_.swap(tmp);
280  list(lst);
281  // check if every element marked for removal is also in the tree
282  for (typename std::unordered_set<const _T*>::iterator it = tmp.begin(); it != tmp.end(); it++)
283  {
284  unsigned int i;
285  for (i = 0; i < lst.size(); ++i)
286  if (lst[i] == **it)
287  break;
288  if (i == lst.size())
289  {
290  // an element marked for removal is not actually in the tree
291  std::cout << "***** FAIL!! ******\n" << *this << '\n';
292  for (unsigned int j = 0; j < lst.size(); ++j)
293  std::cout << lst[j] << '\t';
294  std::cout << std::endl;
295  }
296  assert(i != lst.size());
297  }
298  // restore
299  removed_.swap(tmp);
300  // get elements in the tree with elements marked for removal purged from the list
301  list(lst);
302  if (lst.size() != size_)
303  std::cout << "#########################################\n" << *this << std::endl;
304  assert(lst.size() == size_);
305  }
306 
307 protected:
309 
310  // Return true iff data has been marked for removal.
311  bool isRemoved(const _T& data) const
312  {
313  return !removed_.empty() && removed_.find(&data) != removed_.end();
314  }
315 
316  // \brief Return in nbhQueue the k nearest neighbors of data.
317  // For k=1, return true if the nearest neighbor is a pivot.
318  // (which is important during removal; removing pivots is a
319  // special case).
320  bool nearestKInternal(const _T& data, std::size_t k, NearQueue& nbhQueue) const
321  {
322  bool is_pivot;
323  double dist;
324  NodeDist node_dist;
325  NodeQueue node_queue;
326 
328  is_pivot = tree_->insertNeighborK(nbhQueue, k, tree_->pivot_, data, dist);
329  tree_->nearestK(*this, data, k, nbhQueue, node_queue, is_pivot);
330  while (!node_queue.empty())
331  {
332  dist = nbhQueue.top().second; // note the difference with nearestRInternal
333  node_dist = node_queue.top();
334  node_queue.pop();
335  if (nbhQueue.size() == k && (node_dist.second > node_dist.first->maxRadius_ + dist ||
336  node_dist.second < node_dist.first->minRadius_ - dist))
337  continue;
338  node_dist.first->nearestK(*this, data, k, nbhQueue, node_queue, is_pivot);
339  }
340  return is_pivot;
341  }
342  // \brief Return in nbhQueue the elements that are within distance radius of data.
343  void nearestRInternal(const _T& data, double radius, NearQueue& nbhQueue) const
344  {
345  double dist = radius; // note the difference with nearestKInternal
346  NodeQueue node_queue;
347  NodeDist node_dist;
348 
350  tree_->nearestR(*this, data, radius, nbhQueue, node_queue);
351  while (!node_queue.empty())
352  {
353  node_dist = node_queue.top();
354  node_queue.pop();
355  if (node_dist.second > node_dist.first->maxRadius_ + dist || node_dist.second < node_dist.first->minRadius_ - dist)
356  continue;
357  node_dist.first->nearestR(*this, data, radius, nbhQueue, node_queue);
358  }
359  }
360  // \brief Convert the internal data structure used for storing neighbors
361  // to the vector that NearestNeighbor API requires.
362  void postprocessNearest(NearQueue& nbhQueue, std::vector<_T>& nbh) const
363  {
364  typename std::vector<_T>::reverse_iterator it;
365  nbh.resize(nbhQueue.size());
366  for (it = nbh.rbegin(); it != nbh.rend(); it++, nbhQueue.pop())
367  *it = *nbhQueue.top().first;
368  }
369 
370  // The class used internally to define the GNAT.
371  class Node
372  {
373  public:
374  // \brief Construct a node of given degree with at most
375  // \e capacity data elements and with given pivot.
376  Node(int degree, int capacity, _T pivot)
377  : degree_(degree)
378  , pivot_(std::move(pivot))
379  , minRadius_(std::numeric_limits<double>::infinity())
381  , minRange_(degree, minRadius_)
382  , maxRange_(degree, maxRadius_)
383  {
384  // The "+1" is needed because we add an element before we check whether to split
385  data_.reserve(capacity + 1);
386  }
387 
388  ~Node()
389  {
390  for (unsigned int i = 0; i < children_.size(); ++i)
391  delete children_[i];
392  }
393 
394  // \brief Update minRadius_ and maxRadius_, given that an element
395  // was added with distance dist to the pivot.
396  void updateRadius(double dist)
397  {
398  if (minRadius_ > dist)
399  minRadius_ = dist;
400 #ifndef GNAT_SAMPLER
401  if (maxRadius_ < dist)
402  maxRadius_ = dist;
403 #else
404  if (maxRadius_ < dist)
405  {
406  maxRadius_ = dist;
407  activity_ = 0;
408  }
409  else
410  activity_ = std::max(-32, activity_ - 1);
411 #endif
412  }
413  // \brief Update minRange_[i] and maxRange_[i], given that an
414  // element was added to the i-th child of the parent that has
415  // distance dist to this Node's pivot.
416  void updateRange(unsigned int i, double dist)
417  {
418  if (minRange_[i] > dist)
419  minRange_[i] = dist;
420  if (maxRange_[i] < dist)
421  maxRange_[i] = dist;
422  }
423  // Add an element to the tree rooted at this node.
424  void add(GNAT& gnat, const _T& data)
425  {
426  if (children_.empty())
427  {
428  data_.push_back(data);
429  gnat.size_++;
430  if (needToSplit(gnat))
431  {
432  if (!gnat.removed_.empty())
433  gnat.rebuildDataStructure();
434  else if (gnat.size_ >= gnat.rebuildSize_)
435  {
436  gnat.rebuildSize_ <<= 1;
437  gnat.rebuildDataStructure();
438  }
439  else
440  split(gnat);
441  }
442  }
443  else
444  {
445  std::vector<double> dist(children_.size());
446  double min_dist = dist[0] = gnat.distFun_(data, children_[0]->pivot_);
447  int min_ind = 0;
448 
449  for (unsigned int i = 1; i < children_.size(); ++i)
450  if ((dist[i] = gnat.distFun_(data, children_[i]->pivot_)) < min_dist)
451  {
452  min_dist = dist[i];
453  min_ind = i;
454  }
455  for (unsigned int i = 0; i < children_.size(); ++i)
456  children_[i]->updateRange(min_ind, dist[i]);
457  children_[min_ind]->updateRadius(min_dist);
458  children_[min_ind]->add(gnat, data);
459  }
460  }
461  // Return true iff the node needs to be split into child nodes.
462  bool needToSplit(const GNAT& gnat) const
463  {
464  unsigned int sz = data_.size();
465  return sz > gnat.maxNumPtsPerLeaf_ && sz > degree_;
466  }
467  // \brief The split operation finds pivot elements for the child
468  // nodes and moves each data element of this node to the appropriate
469  // child node.
470  void split(GNAT& gnat)
471  {
472  typename GreedyKCenters<_T>::Matrix dists(data_.size(), degree_);
473  std::vector<unsigned int> pivots;
474 
475  children_.reserve(degree_);
476  gnat.pivotSelector_.kcenters(data_, degree_, pivots, dists);
477  for (unsigned int& pivot : pivots)
478  children_.push_back(new Node(degree_, gnat.maxNumPtsPerLeaf_, data_[pivot]));
479  degree_ = pivots.size(); // in case fewer than degree_ pivots were found
480  for (unsigned int j = 0; j < data_.size(); ++j)
481  {
482  unsigned int k = 0;
483  for (unsigned int i = 1; i < degree_; ++i)
484  if (dists(j, i) < dists(j, k))
485  k = i;
486  Node* child = children_[k];
487  if (j != pivots[k])
488  {
489  child->data_.push_back(data_[j]);
490  child->updateRadius(dists(j, k));
491  }
492  for (unsigned int i = 0; i < degree_; ++i)
493  children_[i]->updateRange(k, dists(j, i));
494  }
495 
496  for (unsigned int i = 0; i < degree_; ++i)
497  {
498  // make sure degree lies between minDegree_ and maxDegree_
499  children_[i]->degree_ =
500  std::min(std::max((unsigned int)((degree_ * children_[i]->data_.size()) / data_.size()), gnat.minDegree_),
501  gnat.maxDegree_);
502  // singleton
503  if (children_[i]->minRadius_ >= std::numeric_limits<double>::infinity())
504  children_[i]->minRadius_ = children_[i]->maxRadius_ = 0.;
505  }
506  // this does more than clear(); it also sets capacity to 0 and frees the memory
507  std::vector<_T> tmp;
508  data_.swap(tmp);
509  // check if new leaves need to be split
510  for (unsigned int i = 0; i < degree_; ++i)
511  if (children_[i]->needToSplit(gnat))
512  children_[i]->split(gnat);
513  }
514 
515  // Insert data in nbh if it is a near neighbor. Return true iff data was added to nbh.
516  bool insertNeighborK(NearQueue& nbh, std::size_t k, const _T& data, const _T& key, double dist) const
517  {
518  if (nbh.size() < k)
519  {
520  nbh.push(std::make_pair(&data, dist));
521  return true;
522  }
523  if (dist < nbh.top().second || (dist < std::numeric_limits<double>::epsilon() && data == key))
524  {
525  nbh.pop();
526  nbh.push(std::make_pair(&data, dist));
527  return true;
528  }
529  return false;
530  }
531 
532  // \brief Compute the k nearest neighbors of data in the tree.
533  // For k=1, isPivot is true if the nearest neighbor is a pivot
534  // (which is important during removal; removing pivots is a
535  // special case). The nodeQueue, which contains other Nodes
536  // that need to be checked for nearest neighbors, is updated.
537  void nearestK(const GNAT& gnat, const _T& data, std::size_t k, NearQueue& nbh, NodeQueue& nodeQueue,
538  bool& isPivot) const
539  {
540  for (unsigned int i = 0; i < data_.size(); ++i)
541  if (!gnat.isRemoved(data_[i]))
542  {
543  if (insertNeighborK(nbh, k, data_[i], data, gnat.distFun_(data, data_[i])))
544  isPivot = false;
545  }
546  if (!children_.empty())
547  {
548  double dist;
549  Node* child;
550  std::vector<double> dist_to_pivot(children_.size());
551  std::vector<int> permutation(children_.size());
552  for (unsigned int i = 0; i < permutation.size(); ++i)
553  permutation[i] = i;
554  std::shuffle(permutation.begin(), permutation.end(), std::default_random_engine{});
555 
556  for (unsigned int i = 0; i < children_.size(); ++i)
557  if (permutation[i] >= 0)
558  {
559  child = children_[permutation[i]];
560  dist_to_pivot[permutation[i]] = gnat.distFun_(data, child->pivot_);
561  if (insertNeighborK(nbh, k, child->pivot_, data, dist_to_pivot[permutation[i]]))
562  isPivot = true;
563  if (nbh.size() == k)
564  {
565  dist = nbh.top().second; // note difference with nearestR
566  for (unsigned int j = 0; j < children_.size(); ++j)
567  if (permutation[j] >= 0 && i != j &&
568  (dist_to_pivot[permutation[i]] - dist > child->maxRange_[permutation[j]] ||
569  dist_to_pivot[permutation[i]] + dist < child->minRange_[permutation[j]]))
570  permutation[j] = -1;
571  }
572  }
573 
574  dist = nbh.top().second;
575  for (unsigned int i = 0; i < children_.size(); ++i)
576  if (permutation[i] >= 0)
577  {
578  child = children_[permutation[i]];
579  if (nbh.size() < k || (dist_to_pivot[permutation[i]] - dist <= child->maxRadius_ &&
580  dist_to_pivot[permutation[i]] + dist >= child->minRadius_))
581  nodeQueue.push(std::make_pair(child, dist_to_pivot[permutation[i]]));
582  }
583  }
584  }
585  // Insert data in nbh if it is a near neighbor.
586  void insertNeighborR(NearQueue& nbh, double r, const _T& data, double dist) const
587  {
588  if (dist <= r)
589  nbh.push(std::make_pair(&data, dist));
590  }
591  // \brief Return all elements that are within distance r in nbh.
592  // The nodeQueue, which contains other Nodes that need to
593  // be checked for nearest neighbors, is updated.
594  void nearestR(const GNAT& gnat, const _T& data, double r, NearQueue& nbh, NodeQueue& nodeQueue) const
595  {
596  double dist = r; // note difference with nearestK
597 
598  for (unsigned int i = 0; i < data_.size(); ++i)
599  if (!gnat.isRemoved(data_[i]))
600  insertNeighborR(nbh, r, data_[i], gnat.distFun_(data, data_[i]));
601  if (!children_.empty())
602  {
603  Node* child;
604  std::vector<double> dist_to_pivot(children_.size());
605  std::vector<int> permutation(children_.size());
606  for (unsigned int i = 0; i < permutation.size(); ++i)
607  permutation[i] = i;
608  std::shuffle(permutation.begin(), permutation.end(), std::default_random_engine{});
609 
610  for (unsigned int i = 0; i < children_.size(); ++i)
611  if (permutation[i] >= 0)
612  {
613  child = children_[permutation[i]];
614  dist_to_pivot[i] = gnat.distFun_(data, child->pivot_);
615  insertNeighborR(nbh, r, child->pivot_, dist_to_pivot[i]);
616  for (unsigned int j = 0; j < children_.size(); ++j)
617  if (permutation[j] >= 0 && i != j &&
618  (dist_to_pivot[i] - dist > child->maxRange_[permutation[j]] ||
619  dist_to_pivot[i] + dist < child->minRange_[permutation[j]]))
620  permutation[j] = -1;
621  }
622 
623  for (unsigned int i = 0; i < children_.size(); ++i)
624  if (permutation[i] >= 0)
625  {
626  child = children_[permutation[i]];
627  if (dist_to_pivot[i] - dist <= child->maxRadius_ && dist_to_pivot[i] + dist >= child->minRadius_)
628  nodeQueue.push(std::make_pair(child, dist_to_pivot[i]));
629  }
630  }
631  }
632 
633  void list(const GNAT& gnat, std::vector<_T>& data) const
634  {
635  if (!gnat.isRemoved(pivot_))
636  data.push_back(pivot_);
637  for (unsigned int i = 0; i < data_.size(); ++i)
638  if (!gnat.isRemoved(data_[i]))
639  data.push_back(data_[i]);
640  for (unsigned int i = 0; i < children_.size(); ++i)
641  children_[i]->list(gnat, data);
642  }
643 
644  friend std::ostream& operator<<(std::ostream& out, const Node& node)
645  {
646  out << "\ndegree:\t" << node.degree_;
647  out << "\nminRadius:\t" << node.minRadius_;
648  out << "\nmaxRadius:\t" << node.maxRadius_;
649  out << "\nminRange:\t";
650  for (unsigned int i = 0; i < node.minRange_.size(); ++i)
651  out << node.minRange_[i] << '\t';
652  out << "\nmaxRange: ";
653  for (unsigned int i = 0; i < node.maxRange_.size(); ++i)
654  out << node.maxRange_[i] << '\t';
655  out << "\npivot:\t" << node.pivot_;
656  out << "\ndata: ";
657  for (unsigned int i = 0; i < node.data_.size(); ++i)
658  out << node.data_[i] << '\t';
659  out << "\nthis:\t" << &node;
660  out << "\nchildren:\n";
661  for (unsigned int i = 0; i < node.children_.size(); ++i)
662  out << node.children_[i] << '\t';
663  out << '\n';
664  for (unsigned int i = 0; i < node.children_.size(); ++i)
665  out << *node.children_[i] << '\n';
666  return out;
667  }
668 
669  // Number of child nodes
670  unsigned int degree_;
671  // Data element stored in this Node
672  const _T pivot_;
673  // Minimum distance between the pivot element and the elements stored in data_
674  double minRadius_;
675  // Maximum distance between the pivot element and the elements stored in data_
676  double maxRadius_;
677  // \brief The i-th element in minRange_ is the minimum distance between the
678  // pivot and any data_ element in the i-th child node of this node's parent.
679  std::vector<double> minRange_;
680  // \brief The i-th element in maxRange_ is the maximum distance between the
681  // pivot and any data_ element in the i-th child node of this node's parent.
682  std::vector<double> maxRange_;
683  // \brief The data elements stored in this node (in addition to the pivot
684  // element). An internal node has no elements stored in data_.
685  std::vector<_T> data_;
686  // \brief The child nodes of this node. By definition, only internal nodes
687  // have child nodes.
688  std::vector<Node*> children_;
689  };
690 
691  // \brief The data structure containing the elements stored in this structure.
692  Node* tree_{ nullptr };
693  // The desired degree of each node.
694  unsigned int degree_;
695  // \brief After splitting a Node, each child Node has degree equal to
696  // the default degree times the fraction of data elements from the
697  // original node that got assigned to that child Node. However, its
698  // degree can be no less than minDegree_.
699  unsigned int minDegree_;
700  // \brief After splitting a Node, each child Node has degree equal to
701  // the default degree times the fraction of data elements from the
702  // original node that got assigned to that child Node. However, its
703  // degree can be no larger than maxDegree_.
704  unsigned int maxDegree_;
705  // \brief Maximum number of elements allowed to be stored in a Node before
706  // it needs to be split into several nodes.
707  unsigned int maxNumPtsPerLeaf_;
708  // \brief Number of elements stored in the tree.
709  std::size_t size_{ 0 };
710  // \brief If size_ exceeds rebuildSize_, the tree will be rebuilt (and
711  // automatically rebalanced), and rebuildSize_ will be doubled.
712  std::size_t rebuildSize_;
713  // \brief Maximum number of removed elements that can be stored in the
714  // removed_ cache. If the cache is full, the tree will be rebuilt with
715  // the elements in removed_ actually removed from the tree.
716  std::size_t removedCacheSize_;
717  // \brief The data structure used to split data into subtrees.
719  // \brief Cache of removed elements.
720  std::unordered_set<const _T*> removed_;
721 };
722 } // namespace cached_ik_kinematics_plugin
GreedyKCenters.h
cached_ik_kinematics_plugin::NearestNeighborsGNAT::rebuildSize_
std::size_t rebuildSize_
Definition: NearestNeighborsGNAT.h:776
cached_ik_kinematics_plugin
Definition: cached_ik_kinematics_plugin-inl.h:40
cached_ik_kinematics_plugin::NearestNeighborsGNAT::add
void add(const _T &data) override
Add an element to the datastructure.
Definition: NearestNeighborsGNAT.h:208
cached_ik_kinematics_plugin::NearestNeighborsGNAT::Node::updateRadius
void updateRadius(double dist)
Definition: NearestNeighborsGNAT.h:460
cached_ik_kinematics_plugin::NearestNeighborsGNAT::Node::nearestK
void nearestK(const GNAT &gnat, const _T &data, std::size_t k, NearQueue &nbh, NodeQueue &nodeQueue, bool &isPivot) const
Definition: NearestNeighborsGNAT.h:601
cached_ik_kinematics_plugin::NearestNeighborsGNAT::nearestRInternal
void nearestRInternal(const _T &data, double radius, NearQueue &nbhQueue) const
Definition: NearestNeighborsGNAT.h:407
cached_ik_kinematics_plugin::NearestNeighbors::DistanceFunction
std::function< double(const _T &, const _T &)> DistanceFunction
The definition of a distance function.
Definition: NearestNeighbors.h:116
cached_ik_kinematics_plugin::NearestNeighborsGNAT::nearestKInternal
bool nearestKInternal(const _T &data, std::size_t k, NearQueue &nbhQueue) const
Definition: NearestNeighborsGNAT.h:384
cached_ik_kinematics_plugin::NearestNeighborsGNAT::~NearestNeighborsGNAT
~NearestNeighborsGNAT() override
Definition: NearestNeighborsGNAT.h:176
cached_ik_kinematics_plugin::NearestNeighborsGNAT::pivotSelector_
GreedyKCenters< _T > pivotSelector_
Definition: NearestNeighborsGNAT.h:782
cached_ik_kinematics_plugin::NearestNeighborsGNAT::Node::insertNeighborR
void insertNeighborR(NearQueue &nbh, double r, const _T &data, double dist) const
Definition: NearestNeighborsGNAT.h:650
cached_ik_kinematics_plugin::NearestNeighborsGNAT::rebuildDataStructure
void rebuildDataStructure()
Definition: NearestNeighborsGNAT.h:237
cached_ik_kinematics_plugin::NearestNeighborsGNAT::Node::degree_
unsigned int degree_
Definition: NearestNeighborsGNAT.h:734
cached_ik_kinematics_plugin::NearestNeighborsGNAT::setDistanceFunction
void setDistanceFunction(const typename NearestNeighbors< _T >::DistanceFunction &distFun) override
Definition: NearestNeighborsGNAT.h:182
cached_ik_kinematics_plugin::NearestNeighborsGNAT::Node::nearestR
void nearestR(const GNAT &gnat, const _T &data, double r, NearQueue &nbh, NodeQueue &nodeQueue) const
Definition: NearestNeighborsGNAT.h:658
cached_ik_kinematics_plugin::NearestNeighborsGNAT::Node::data_
std::vector< _T > data_
Definition: NearestNeighborsGNAT.h:749
cached_ik_kinematics_plugin::NearestNeighborsGNAT::Node
Definition: NearestNeighborsGNAT.h:435
cached_ik_kinematics_plugin::NearestNeighborsGNAT::GNAT
NearestNeighborsGNAT< _T > GNAT
Definition: NearestNeighborsGNAT.h:372
cached_ik_kinematics_plugin::NearestNeighbors::setDistanceFunction
virtual void setDistanceFunction(const DistanceFunction &distFun)
Set the distance function to use.
Definition: NearestNeighbors.h:123
cached_ik_kinematics_plugin::NearestNeighborsGNAT::clear
void clear() override
Clear the datastructure.
Definition: NearestNeighborsGNAT.h:190
cached_ik_kinematics_plugin::NearestNeighborsGNAT::size
std::size_t size() const override
Get the number of elements in the datastructure.
Definition: NearestNeighborsGNAT.h:306
cached_ik_kinematics_plugin::NearestNeighborsGNAT::list
void list(std::vector< _T > &data) const override
Get all the elements in the datastructure.
Definition: NearestNeighborsGNAT.h:311
NearestNeighbors.h
cached_ik_kinematics_plugin::NearestNeighborsGNAT::tree_
Node * tree_
Definition: NearestNeighborsGNAT.h:756
cached_ik_kinematics_plugin::NearestNeighborsGNAT::degree_
unsigned int degree_
Definition: NearestNeighborsGNAT.h:758
cached_ik_kinematics_plugin::NearestNeighborsGNAT::nearest
_T nearest(const _T &data) const override
Get the nearest neighbor of a point.
Definition: NearestNeighborsGNAT.h:268
cached_ik_kinematics_plugin::NearestNeighborsGNAT::isRemoved
bool isRemoved(const _T &data) const
Definition: NearestNeighborsGNAT.h:375
cached_ik_kinematics_plugin::GreedyKCenters
An instance of this class can be used to greedily select a given number of representatives from a set...
Definition: GreedyKCenters.h:83
cached_ik_kinematics_plugin::NearestNeighborsGNAT::postprocessNearest
void postprocessNearest(NearQueue &nbhQueue, std::vector< _T > &nbh) const
Definition: NearestNeighborsGNAT.h:426
cached_ik_kinematics_plugin::NearestNeighbors
Abstract representation of a container that can perform nearest neighbors queries.
Definition: NearestNeighbors.h:80
cached_ik_kinematics_plugin::NearestNeighborsGNAT
Geometric Near-neighbor Access Tree (GNAT), a data structure for nearest neighbor search.
Definition: NearestNeighborsGNAT.h:100
cached_ik_kinematics_plugin::NearestNeighborsGNAT::Node::pivot_
const _T pivot_
Definition: NearestNeighborsGNAT.h:736
d
d
cached_ik_kinematics_plugin::GreedyKCenters::Matrix
boost::numeric::ublas::matrix< double > Matrix
A matrix type for storing distances between points and centers.
Definition: GreedyKCenters.h:121
cached_ik_kinematics_plugin::NearestNeighborsGNAT::NearestNeighborsGNAT
NearestNeighborsGNAT(unsigned int degree=8, unsigned int minDegree=4, unsigned int maxDegree=12, unsigned int maxNumPtsPerLeaf=50, unsigned int removedCacheSize=500, bool rebalancing=false)
Definition: NearestNeighborsGNAT.h:163
cached_ik_kinematics_plugin::NearestNeighborsGNAT::remove
bool remove(const _T &data) override
Remove an element from the datastructure.
Definition: NearestNeighborsGNAT.h:249
r
S r
cached_ik_kinematics_plugin::NearestNeighborsGNAT::Node::maxRange_
std::vector< double > maxRange_
Definition: NearestNeighborsGNAT.h:746
cached_ik_kinematics_plugin::NearestNeighborsGNAT::Node::children_
std::vector< Node * > children_
Definition: NearestNeighborsGNAT.h:752
exceptions.h
cached_ik_kinematics_plugin::NearestNeighbors::add
virtual void add(const _T &data)=0
Add an element to the datastructure.
cached_ik_kinematics_plugin::NearestNeighborsGNAT::minDegree_
unsigned int minDegree_
Definition: NearestNeighborsGNAT.h:763
cached_ik_kinematics_plugin::NearestNeighborsGNAT::size_
std::size_t size_
Definition: NearestNeighborsGNAT.h:773
cached_ik_kinematics_plugin::NearestNeighborsGNAT::Node::split
void split(GNAT &gnat)
Definition: NearestNeighborsGNAT.h:534
cached_ik_kinematics_plugin::NearestNeighborsGNAT::Node::insertNeighborK
bool insertNeighborK(NearQueue &nbh, std::size_t k, const _T &data, const _T &key, double dist) const
Definition: NearestNeighborsGNAT.h:580
cached_ik_kinematics_plugin::NearestNeighborsGNAT::Node::Node
Node(int degree, int capacity, _T pivot)
Definition: NearestNeighborsGNAT.h:440
cached_ik_kinematics_plugin::NearestNeighborsGNAT::Node::maxRadius_
double maxRadius_
Definition: NearestNeighborsGNAT.h:740
cached_ik_kinematics_plugin::NearestNeighborsGNAT::removedCacheSize_
std::size_t removedCacheSize_
Definition: NearestNeighborsGNAT.h:780
cached_ik_kinematics_plugin::NearestNeighborsGNAT::removed_
std::unordered_set< const _T * > removed_
Definition: NearestNeighborsGNAT.h:784
cached_ik_kinematics_plugin::NearestNeighborsGNAT::Node::minRadius_
double minRadius_
Definition: NearestNeighborsGNAT.h:738
std
cached_ik_kinematics_plugin::NearestNeighborsGNAT::maxNumPtsPerLeaf_
unsigned int maxNumPtsPerLeaf_
Definition: NearestNeighborsGNAT.h:771
cached_ik_kinematics_plugin::NearestNeighborsGNAT::nearestK
void nearestK(const _T &data, std::size_t k, std::vector< _T > &nbh) const override
Get the k-nearest neighbors of a point.
Definition: NearestNeighborsGNAT.h:281
cached_ik_kinematics_plugin::NearestNeighborsGNAT::Node::list
void list(const GNAT &gnat, std::vector< _T > &data) const
Definition: NearestNeighborsGNAT.h:697
cached_ik_kinematics_plugin::NearestNeighbors::distFun_
DistanceFunction distFun_
The used distance function.
Definition: NearestNeighbors.h:179
cached_ik_kinematics_plugin::NearestNeighborsGNAT::Node::updateRange
void updateRange(unsigned int i, double dist)
Definition: NearestNeighborsGNAT.h:480
cached_ik_kinematics_plugin::NearestNeighborsGNAT::Node::minRange_
std::vector< double > minRange_
Definition: NearestNeighborsGNAT.h:743
moveit::Exception
cached_ik_kinematics_plugin::NearestNeighborsGNAT::Node::needToSplit
bool needToSplit(const GNAT &gnat) const
Definition: NearestNeighborsGNAT.h:526
cached_ik_kinematics_plugin::NearestNeighborsGNAT::Node::operator<<
friend std::ostream & operator<<(std::ostream &out, const Node &node)
Definition: NearestNeighborsGNAT.h:708
cached_ik_kinematics_plugin::NearestNeighborsGNAT::Node::~Node
~Node()
Definition: NearestNeighborsGNAT.h:452
cached_ik_kinematics_plugin::NearestNeighborsGNAT::maxDegree_
unsigned int maxDegree_
Definition: NearestNeighborsGNAT.h:768
cached_ik_kinematics_plugin::NearestNeighborsGNAT::reportsSortedResults
bool reportsSortedResults() const override
Return true if the solutions reported by this data structure are sorted, when calling nearestK / near...
Definition: NearestNeighborsGNAT.h:203
cached_ik_kinematics_plugin::NearestNeighborsGNAT::integrityCheck
void integrityCheck()
Definition: NearestNeighborsGNAT.h:338
cached_ik_kinematics_plugin::NearestNeighborsGNAT::Node::add
void add(GNAT &gnat, const _T &data)
Definition: NearestNeighborsGNAT.h:488
cached_ik_kinematics_plugin::NearestNeighborsGNAT::operator<<
friend std::ostream & operator<<(std::ostream &out, const NearestNeighborsGNAT< _T > &gnat)
Definition: NearestNeighborsGNAT.h:320
cached_ik_kinematics_plugin::NearestNeighborsGNAT::nearestR
void nearestR(const _T &data, double radius, std::vector< _T > &nbh) const override
Get the nearest neighbors of a point, within a specified radius.
Definition: NearestNeighborsGNAT.h:295


moveit_kinematics
Author(s): Dave Coleman , Ioan Sucan , Sachin Chitta
autogenerated on Fri May 3 2024 02:29:33