42#include <rsl/random.hpp>
45#include <unordered_set>
76 using DataDist = std::pair<const _T*, double>;
77 struct DataDistCompare
79 bool operator()(
const DataDist& d0,
const DataDist& d1)
81 return d0.second < d1.second;
84 using NearQueue = std::priority_queue<DataDist, std::vector<DataDist>, DataDistCompare>;
89 using NodeDist = std::pair<Node*, double>;
90 struct NodeDistCompare
92 bool operator()(
const NodeDist& n0,
const NodeDist& n1)
const
94 return (n0.second - n0.first->maxRadius_) > (n1.second - n1.first->maxRadius_);
97 using NodeQueue = std::priority_queue<NodeDist, std::vector<NodeDist>, NodeDistCompare>;
102 unsigned int maxNumPtsPerLeaf = 50,
unsigned int removedCacheSize = 500,
103 bool rebalancing =
false)
109 ,
rebuildSize_(rebalancing ? maxNumPtsPerLeaf * degree : std::numeric_limits<std::size_t>::max())
137 if (
rebuildSize_ != std::numeric_limits<std::size_t>::max())
146 void add(
const _T& data)
override
160 void add(
const std::vector<_T>& data)
override
166 else if (!data.empty())
169 for (
unsigned int i = 1; i < data.size(); ++i)
171 size_ += data.size();
196 const _T* d = nbh_queue.top().first;
214 if (!nbh_queue.empty())
215 return *nbh_queue.top().first;
217 throw moveit::Exception(
"No elements found in nearest neighbors data structure");
221 void nearestK(
const _T& data, std::size_t k, std::vector<_T>& nbh)
const override
235 void nearestR(
const _T& data,
double radius, std::vector<_T>& nbh)
const override
246 std::size_t
size()
const override
251 void list(std::vector<_T>& data)
const override
254 data.reserve(
size());
267 out <<
"Elements marked for removal:\n";
268 for (
typename std::unordered_set<const _T*>::const_iterator it = gnat.
removed_.begin();
281 std::unordered_set<const _T*> tmp;
286 for (
typename std::unordered_set<const _T*>::iterator it = tmp.begin(); it != tmp.end(); ++it)
289 for (i = 0; i < lst.size(); ++i)
297 std::cout <<
"***** FAIL!! ******\n" << *
this <<
'\n';
298 for (
unsigned int j = 0; j < lst.size(); ++j)
299 std::cout << lst[j] <<
'\t';
302 assert(i != lst.size());
308 if (lst.size() !=
size_)
309 std::cout <<
"#########################################\n" << *
this <<
'\n';
310 assert(lst.size() ==
size_);
331 NodeQueue node_queue;
335 tree_->
nearestK(*
this, data, k, nbhQueue, node_queue, is_pivot);
336 while (!node_queue.empty())
338 dist = nbhQueue.top().second;
339 node_dist = node_queue.top();
341 if (nbhQueue.size() == k && (node_dist.second > node_dist.first->maxRadius_ + dist ||
342 node_dist.second < node_dist.first->minRadius_ - dist))
344 node_dist.first->nearestK(*
this, data, k, nbhQueue, node_queue, is_pivot);
351 double dist = radius;
352 NodeQueue node_queue;
357 while (!node_queue.empty())
359 node_dist = node_queue.top();
361 if (node_dist.second > node_dist.first->maxRadius_ + dist || node_dist.second < node_dist.first->minRadius_ - dist)
363 node_dist.first->nearestR(*
this, data, radius, nbhQueue, node_queue);
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;
382 Node(
int degree,
int capacity, _T pivot)
384 ,
pivot_(std::move(pivot))
385 ,
minRadius_(std::numeric_limits<double>::infinity())
391 data_.reserve(capacity + 1);
396 for (
unsigned int i = 0; i <
children_.size(); ++i)
416 activity_ = std::max(-32, activity_ - 1);
434 data_.push_back(data);
453 std::vector<double> dist(
children_.size());
457 for (
unsigned int i = 1; i <
children_.size(); ++i)
465 for (
unsigned int i = 0; i <
children_.size(); ++i)
467 children_[min_ind]->updateRadius(min_dist);
474 unsigned int sz =
data_.size();
483 std::vector<unsigned int> pivots;
487 for (
unsigned int& pivot : pivots)
490 for (
unsigned int j = 0; j <
data_.size(); ++j)
493 for (
unsigned int i = 1; i <
degree_; ++i)
495 if (dists(j, i) < dists(j, k))
504 for (
unsigned int i = 0; i <
degree_; ++i)
508 for (
unsigned int i = 0; i <
degree_; ++i)
523 for (
unsigned int i = 0; i <
degree_; ++i)
531 bool insertNeighborK(NearQueue& nbh, std::size_t k,
const _T& data,
const _T& key,
double dist)
const
535 nbh.push(std::make_pair(&data, dist));
538 if (dist < nbh.top().second || (dist < std::numeric_limits<double>::epsilon() && data == key))
541 nbh.push(std::make_pair(&data, dist));
552 void nearestK(
const GNAT& gnat,
const _T& data, std::size_t k, NearQueue& nbh, NodeQueue& nodeQueue,
555 for (
unsigned int i = 0; i <
data_.size(); ++i)
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)
571 std::shuffle(permutation.begin(), permutation.end(), rsl::rng());
573 for (
unsigned int i = 0; i <
children_.size(); ++i)
575 if (permutation[i] >= 0)
578 dist_to_pivot[permutation[i]] = gnat.
distFun_(data, child->
pivot_);
583 dist = nbh.top().second;
584 for (
unsigned int j = 0; j <
children_.size(); ++j)
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]]))
595 dist = nbh.top().second;
596 for (
unsigned int i = 0; i <
children_.size(); ++i)
598 if (permutation[i] >= 0)
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]]));
612 nbh.push(std::make_pair(&data, dist));
617 void nearestR(
const GNAT& gnat,
const _T& data,
double r, NearQueue& nbh, NodeQueue& nodeQueue)
const
621 for (
unsigned int i = 0; i <
data_.size(); ++i)
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)
633 std::shuffle(permutation.begin(), permutation.end(), rsl::rng());
635 for (
unsigned int i = 0; i <
children_.size(); ++i)
637 if (permutation[i] >= 0)
642 for (
unsigned int j = 0; j <
children_.size(); ++j)
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]]))
652 for (
unsigned int i = 0; i <
children_.size(); ++i)
654 if (permutation[i] >= 0)
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]));
664 void list(
const GNAT& gnat, std::vector<_T>& data)
const
668 for (
unsigned int i = 0; i <
data_.size(); ++i)
671 data.push_back(
data_[i]);
673 for (
unsigned int i = 0; i <
children_.size(); ++i)
679 out <<
"\ndegree:\t" << node.
degree_;
682 out <<
"\nminRange:\t";
683 for (
unsigned int i = 0; i < node.
minRange_.size(); ++i)
685 out <<
"\nmaxRange: ";
686 for (
unsigned int i = 0; i < node.
maxRange_.size(); ++i)
688 out <<
"\npivot:\t" << node.
pivot_;
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)
697 for (
unsigned int i = 0; i < node.
children_.size(); ++i)
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
std::vector< double > maxRange_
void nearestR(const GNAT &gnat, const _T &data, double r, NearQueue &nbh, NodeQueue &nodeQueue) const
void updateRadius(double dist)
void list(const GNAT &gnat, std::vector< _T > &data) const
void updateRange(unsigned int i, double dist)
Node(int degree, int capacity, _T pivot)
std::vector< Node * > children_
bool needToSplit(const GNAT &gnat) const
std::vector< double > minRange_
void insertNeighborR(NearQueue &nbh, double r, const _T &data, double dist) const
friend std::ostream & operator<<(std::ostream &out, const Node &node)
void add(GNAT &gnat, const _T &data)
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 removedCacheSize_
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.
~NearestNeighborsGNAT() override
void setDistanceFunction(const typename NearestNeighbors< _T >::DistanceFunction &distFun) override
void rebuildDataStructure()
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
unsigned int maxNumPtsPerLeaf_
void nearestRInternal(const _T &data, double radius, NearQueue &nbhQueue) const
std::unordered_set< const _T * > removed_
GreedyKCenters< _T > pivotSelector_
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.
bool isRemoved(const _T &data) const
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.