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