brute_force_cpu.cpp
Go to the documentation of this file.
1 /*
2 
3 Copyright (c) 2010--2011, Stephane Magnenat, ASL, ETHZ, Switzerland
4 You can contact the author at <stephane at magnenat dot net>
5 
6 All rights reserved.
7 
8 Redistribution and use in source and binary forms, with or without
9 modification, are permitted provided that the following conditions are met:
10  * Redistributions of source code must retain the above copyright
11  notice, this list of conditions and the following disclaimer.
12  * Redistributions in binary form must reproduce the above copyright
13  notice, this list of conditions and the following disclaimer in the
14  documentation and/or other materials provided with the distribution.
15  * Neither the name of the <organization> nor the
16  names of its contributors may be used to endorse or promote products
17  derived from this software without specific prior written permission.
18 
19 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
20 ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
21 WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
22 DISCLAIMED. IN NO EVENT SHALL ETH-ASL BE LIABLE FOR ANY
23 DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
24 (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
25 LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
26 ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
27 (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
28 SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
29 
30 */
31 
32 #include "nabo_private.h"
33 #include "index_heap.h"
34 
40 namespace Nabo
41 {
42  using namespace std;
43 
44  template<typename T, typename CloudType>
45  BruteForceSearch<T, CloudType>::BruteForceSearch(const CloudType& cloud, const Index dim, const unsigned creationOptionFlags):
46  NearestNeighbourSearch<T, CloudType>::NearestNeighbourSearch(cloud, dim, creationOptionFlags)
47  {
48 #ifdef EIGEN3_API
49  const_cast<Vector&>(this->minBound) = cloud.topRows(this->dim).rowwise().minCoeff();
50  const_cast<Vector&>(this->maxBound) = cloud.topRows(this->dim).rowwise().maxCoeff();
51 #else // EIGEN3_API
52  // compute bounds
53  for (int i = 0; i < cloud.cols(); ++i)
54  {
55  const Vector& v(cloud.block(0,i,this->dim,1));
56  const_cast<Vector&>(this->minBound) = this->minBound.cwise().min(v);
57  const_cast<Vector&>(this->maxBound) = this->maxBound.cwise().max(v);
58  }
59 #endif // EIGEN3_API
60  }
61 
62 
63  template<typename T, typename CloudType>
64  unsigned long BruteForceSearch<T, CloudType>::knn(const Matrix& query, IndexMatrix& indices, Matrix& dists2, const Index k, const T epsilon, const unsigned optionFlags, const T maxRadius) const
65  {
66  const Vector maxRadii(Vector::Constant(query.cols(), maxRadius));
67  return knn(query, indices, dists2, maxRadii, k, epsilon, optionFlags);
68  }
69 
70  template<typename T, typename CloudType>
71  unsigned long BruteForceSearch<T, CloudType>::knn(const Matrix& query, IndexMatrix& indices, Matrix& dists2, const Vector& maxRadii, const Index k, const T /*epsilon*/, const unsigned optionFlags) const
72  {
73  checkSizesKnn(query, indices, dists2, k, optionFlags, &maxRadii);
74 
75  const bool allowSelfMatch(optionFlags & NearestNeighbourSearch<T>::ALLOW_SELF_MATCH);
76  const bool sortResults(optionFlags & NearestNeighbourSearch<T>::SORT_RESULTS);
78 
79  IndexHeapSTL<Index, T> heap(k);
80 
81  for (int c = 0; c < query.cols(); ++c)
82  {
83  const T maxRadius(maxRadii[c]);
84  const T maxRadius2(maxRadius * maxRadius);
85  const Vector& q(query.block(0,c,dim,1));
86  heap.reset();
87  for (int i = 0; i < this->cloud.cols(); ++i)
88  {
89  const T dist(dist2<T>(this->cloud.block(0,i,dim,1), q));
90  if ((dist <= maxRadius2) &&
91  (dist < heap.headValue()) &&
92  (allowSelfMatch || (dist > numeric_limits<T>::epsilon())))
93  heap.replaceHead(i, dist);
94  }
95  if (sortResults)
96  heap.sort();
97  heap.getData(indices.col(c), dists2.col(c));
98  }
99  if (collectStatistics)
100  return (unsigned long)query.cols() * (unsigned long)this->cloud.cols();
101  else
102  return 0;
103  }
104 
105  template struct BruteForceSearch<float>;
106  template struct BruteForceSearch<double>;
111 }
const unsigned creationOptionFlags
creation options
Definition: nabo.h:278
NearestNeighbourSearch< T, CloudType >::IndexMatrix IndexMatrix
Definition: nabo_private.h:78
void sort()
sort the entries, from the smallest to the largest
Definition: index_heap.h:123
void getData(const Eigen::MatrixBase< DI > &indices, const Eigen::MatrixBase< DV > &values) const
get the data from the heap
Definition: index_heap.h:132
implementation of index heaps
void checkSizesKnn(const Matrix &query, const IndexMatrix &indices, const Matrix &dists2, const Index k, const unsigned optionFlags, const Vector *maxRadii=0) const
Make sure that the output matrices have the right sizes. Throw an exception otherwise.
Definition: nabo/nabo.cpp:103
Nearest neighbour search interface, templatized on scalar type.
Definition: nabo.h:258
const VT & headValue() const
get the largest value of the heap
Definition: index_heap.h:101
NearestNeighbourSearch< T, CloudType >::Vector Vector
Definition: nabo_private.h:74
const CloudType & cloud
the reference to the data-point cloud, which must remain valid during the lifetime of the NearestNeig...
Definition: nabo.h:274
void reset()
reset to the empty heap
Definition: index_heap.h:93
Brute-force nearest neighbour.
Definition: nabo_private.h:72
void replaceHead(const Index index, const Value value)
put value into heap, replace the largest value if full
Definition: index_heap.h:106
const Vector maxBound
the high bound of the search space (axis-aligned bounding box)
Definition: nabo.h:282
NearestNeighbourSearch< T, CloudType >::Matrix Matrix
Definition: nabo_private.h:75
balanced-tree implementation of heap
Definition: index_heap.h:52
const Vector minBound
the low bound of the search space (axis-aligned bounding box)
Definition: nabo.h:280
Namespace for Nabo.
const Index dim
the dimensionality of the data-point cloud
Definition: nabo.h:276
virtual unsigned long knn(const Matrix &query, IndexMatrix &indices, Matrix &dists2, const Index k, const T epsilon, const unsigned optionFlags, const T maxRadius) const
BruteForceSearch(const CloudType &cloud, const Index dim, const unsigned creationOptionFlags)
constructor, calls NearestNeighbourSearch<T>(cloud)
NearestNeighbourSearch< T, CloudType >::Index Index
Definition: nabo_private.h:76
header for implementation
q
Definition: test.py:8


mrpt_local_obstacles
Author(s): Jose-Luis Blanco-Claraco
autogenerated on Thu Jun 1 2023 03:05:09