KDTree.cpp
Go to the documentation of this file.
1 
36 
37 namespace lvr2
38 {
39 
40 class KDNode : public KDTree
41 {
42 public:
44  : axis(axis), split(split), lesser(move(lesser)), greater(move(greater))
45  { }
46 
47 protected:
48  virtual void nnInternal(const Point& point, Neighbor& neighbor, double& maxDist) const override
49  {
50  double val = point(this->axis);
51  if (val < this->split)
52  {
53  this->lesser->nnInternal(point, neighbor, maxDist);
54  if (val + maxDist >= this->split)
55  {
56  this->greater->nnInternal(point, neighbor, maxDist);
57  }
58  }
59  else
60  {
61  this->greater->nnInternal(point, neighbor, maxDist);
62  if (val - maxDist <= this->split)
63  {
64  this->lesser->nnInternal(point, neighbor, maxDist);
65  }
66  }
67  }
68 
69 private:
70  int axis;
71  double split;
74 };
75 
76 class KDLeaf : public KDTree
77 {
78 public:
81  { }
82 
83 protected:
84  virtual void nnInternal(const Point& point, Neighbor& neighbor, double& maxDist) const override
85  {
86  double maxDistSq = maxDist * maxDist;
87  bool changed = false;
88  for (int i = 0; i < this->count; i++)
89  {
90  double dist = (point - this->points[i]).squaredNorm();
91  if (dist < maxDistSq)
92  {
93  neighbor = &this->points[i];
94  maxDistSq = dist;
95  changed = true;
96  }
97  }
98  if (changed)
99  {
100  maxDist = sqrt(maxDistSq);
101  }
102  }
103 
104 private:
106  int count;
107 };
108 
109 KDTreePtr create_recursive(KDTree::Point* points, int n, int maxLeafSize)
110 {
111  if (n <= maxLeafSize)
112  {
113  return KDTreePtr(new KDLeaf(points, n));
114  }
115 
116  AABB<float> boundingBox(points, n);
117 
118  int splitAxis = boundingBox.longestAxis();
119  double splitValue = boundingBox.avg()(splitAxis);
120 
121  if (boundingBox.difference(splitAxis) == 0.0) // all points are exactly the same
122  {
123  // this case is rare, but would lead to an infinite recursion loop if not handled,
124  // since all Points would end up in the "lesser" branch every time
125 
126  // there is no need to check all of them later on, so just pretend like there is only one
127  return KDTreePtr(new KDLeaf(points, 1));
128  }
129 
130  int l = splitPoints(points, n, splitAxis, splitValue);
131 
132  KDTreePtr lesser, greater;
133 
134  if (n > 8 * maxLeafSize) // stop the omp task subdivision early to avoid spamming tasks
135  {
136  #pragma omp task shared(lesser)
137  lesser = create_recursive(points , l , maxLeafSize);
138 
139  #pragma omp task shared(greater)
140  greater = create_recursive(points + l, n - l, maxLeafSize);
141 
142  #pragma omp taskwait
143  }
144  else
145  {
146  lesser = create_recursive(points , l , maxLeafSize);
147  greater = create_recursive(points + l, n - l, maxLeafSize);
148  }
149 
150  return KDTreePtr(new KDNode(splitAxis, splitValue, lesser, greater));
151 }
152 
153 KDTreePtr KDTree::create(SLAMScanPtr scan, int maxLeafSize)
154 {
155  KDTreePtr ret;
156 
157  size_t n = scan->numPoints();
158  auto points = boost::shared_array<Point>(new Point[n]);
159 
160  #pragma omp parallel for schedule(static)
161  for (size_t i = 0; i < n; i++)
162  {
163  points[i] = scan->point(i).cast<PointT>();
164  }
165 
166  #pragma omp parallel // allows "pragma omp task"
167  #pragma omp single // only execute every task once
168  ret = create_recursive(points.get(), n, maxLeafSize);
169 
170  ret->points = points;
171 
172  return ret;
173 }
174 
175 
176 size_t KDTree::nearestNeighbors(KDTreePtr tree, SLAMScanPtr scan, KDTree::Neighbor* neighbors, double maxDistance, Vector3d& centroid_m, Vector3d& centroid_d)
177 {
178  size_t found = KDTree::nearestNeighbors(tree, scan, neighbors, maxDistance);
179 
180  centroid_m = Vector3d::Zero();
181  centroid_d = Vector3d::Zero();
182 
183  for (size_t i = 0; i < scan->numPoints(); i++)
184  {
185  if (neighbors[i] != nullptr)
186  {
187  centroid_m += neighbors[i]->cast<double>();
188  centroid_d += scan->point(i);
189  }
190  }
191 
192  centroid_m /= found;
193  centroid_d /= found;
194 
195  return found;
196 }
197 
198 size_t KDTree::nearestNeighbors(KDTreePtr tree, SLAMScanPtr scan, KDTree::Neighbor* neighbors, double maxDistance)
199 {
200  size_t found = 0;
201  double distance = 0.0;
202 
203  #pragma omp parallel for firstprivate(distance) reduction(+:found) schedule(dynamic,8)
204  for (size_t i = 0; i < scan->numPoints(); i++)
205  {
206  if (tree->nearestNeighbor(scan->point(i), neighbors[i], distance, maxDistance))
207  {
208  found++;
209  }
210  }
211 
212  return found;
213 }
214 
215 }
lvr2::KDNode::split
double split
Definition: KDTree.cpp:71
lvr2::KDLeaf
Definition: KDTree.cpp:76
lvr2::AABB::difference
T difference(int axis) const
Calculates the size of the Bounding Box along a certain axis.
lvr2::AABB
A struct to calculate the Axis Aligned Bounding Box and Average Point of a Point Cloud.
Definition: AABB.hpp:49
lvr2::KDLeaf::KDLeaf
KDLeaf(Point *points, int count)
Definition: KDTree.cpp:79
lvr2::AABB::longestAxis
int longestAxis() const
Calculates the axis that has the largest size of the Bounding Box.
lvr2::KDNode
Definition: KDTree.cpp:40
lvr2::KDNode::axis
int axis
Definition: KDTree.cpp:70
lvr2::KDLeaf::nnInternal
virtual void nnInternal(const Point &point, Neighbor &neighbor, double &maxDist) const override
Definition: KDTree.cpp:84
lvr2::KDTree::create
static std::shared_ptr< KDTree > create(SLAMScanPtr scan, int maxLeafSize=20)
Creates a new KDTree from the given Scan.
Definition: KDTree.cpp:153
lvr2::KDTree::points
boost::shared_array< Point > points
Definition: KDTree.hpp:132
lvr2::create_recursive
KDTreePtr create_recursive(KDTree::Point *points, int n, int maxLeafSize)
Definition: KDTree.cpp:109
lvr2::KDLeaf::count
int count
Definition: KDTree.cpp:106
lvr2::KDTreePtr
std::shared_ptr< KDTree > KDTreePtr
Definition: KDTree.hpp:135
lvr2::KDNode::nnInternal
virtual void nnInternal(const Point &point, Neighbor &neighbor, double &maxDist) const override
Definition: KDTree.cpp:48
KDTree.hpp
lvr2::KDTree::nearestNeighbors
static size_t nearestNeighbors(KDTreePtr tree, SLAMScanPtr scan, Neighbor *neighbors, double maxDistance, Vector3d &centroid_m, Vector3d &centroid_d)
Finds the nearest neighbors of all points in a Scan using a pre-generated KDTree.
Definition: KDTree.cpp:176
lvr2::KDNode::KDNode
KDNode(int axis, double split, KDTreePtr &lesser, KDTreePtr &greater)
Definition: KDTree.cpp:43
lvr2::KDTree::Point
Vector3< PointT > Point
Definition: KDTree.hpp:55
lvr2::SLAMScanPtr
std::shared_ptr< SLAMScanWrapper > SLAMScanPtr
Definition: SLAMScanWrapper.hpp:221
lvr2::KDNode::greater
KDTreePtr greater
Definition: KDTree.cpp:73
lvr2::Vector3d
Eigen::Vector3d Vector3d
Eigen 3D vector, double precision.
Definition: MatrixTypes.hpp:121
lvr2::splitPoints
int splitPoints(Vector3f *points, int n, int axis, double splitValue)
Sorts a Point array so that all Points smaller than splitValue are on the left.
Definition: TreeUtils.cpp:47
lvr2::AABB::avg
Vector3< T > avg() const
Returns the average of all the Points in the Point Cloud.
lvr2::KDNode::lesser
KDTreePtr lesser
Definition: KDTree.cpp:72
lvr2
Definition: BaseBufferManipulators.hpp:39
Point
Representation of a point in 3D space.
Definition: point.h:22
lvr2::KDTree::Neighbor
Point * Neighbor
Definition: KDTree.hpp:56
lvr2::KDTree::KDTreePtr
std::shared_ptr< KDTree > KDTreePtr
Definition: KDTree.hpp:57
AABB.hpp
lvr2::KDLeaf::points
Point * points
Definition: KDTree.cpp:105
lvr2::KDTree
a kd-Tree Implementation for nearest Neighbor searches
Definition: KDTree.hpp:51
lvr2::KDTree::PointT
float PointT
Definition: KDTree.hpp:54


lvr2
Author(s): Thomas Wiemann , Sebastian Pütz , Alexander Mock , Lars Kiesow , Lukas Kalbertodt , Tristan Igelbrink , Johan M. von Behren , Dominik Feldschnieders , Alexander Löhr
autogenerated on Wed Mar 2 2022 00:37:23