octree-inl.h
Go to the documentation of this file.
1 /*
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2011-2014, Willow Garage, Inc.
5  * Copyright (c) 2014-2016, Open Source Robotics Foundation
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
10  * are met:
11  *
12  * * Redistributions of source code must retain the above copyright
13  * notice, this list of conditions and the following disclaimer.
14  * * Redistributions in binary form must reproduce the above
15  * copyright notice, this list of conditions and the following
16  * disclaimer in the documentation and/or other materials provided
17  * with the distribution.
18  * * Neither the name of Open Source Robotics Foundation nor the names of its
19  * contributors may be used to endorse or promote products derived
20  * from this software without specific prior written permission.
21  *
22  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33  * POSSIBILITY OF SUCH DAMAGE.
34  */
35 
38 #ifndef FCL_OCTREE_INL_H
39 #define FCL_OCTREE_INL_H
40 
42 
43 #include "fcl/config.h"
44 
46 
47 #if FCL_HAVE_OCTOMAP
48 
49 namespace fcl
50 {
51 
52 //==============================================================================
53 extern template
54 class FCL_EXPORT OcTree<double>;
55 
56 //==============================================================================
57 extern template
58 void computeChildBV(const AABB<double>& root_bv, unsigned int i, AABB<double>& child_bv);
59 
60 //==============================================================================
61 template <typename S>
62 OcTree<S>::OcTree(S resolution)
63  : tree(std::shared_ptr<const octomap::OcTree>(new octomap::OcTree(resolution)))
64 {
65  default_occupancy = tree->getOccupancyThres();
66 
67  // default occupancy/free threshold is consistent with default setting from octomap
68  occupancy_threshold_log_odds = tree->getOccupancyThresLog();
69  free_threshold_log_odds = 0.0;
70 }
71 
72 //==============================================================================
73 template <typename S>
74 OcTree<S>::OcTree(const std::shared_ptr<const octomap::OcTree>& tree_)
75  : tree(tree_)
76 {
77  default_occupancy = tree->getOccupancyThres();
78 
79  // default occupancy/free threshold is consistent with default setting from octomap
80  occupancy_threshold_log_odds = tree->getOccupancyThresLog();
81  free_threshold_log_odds = 0;
82 }
83 
84 //==============================================================================
85 template <typename S>
86 void OcTree<S>::computeLocalAABB()
87 {
88  this->aabb_local = getRootBV();
89  this->aabb_center = this->aabb_local.center();
90  this->aabb_radius = (this->aabb_local.min_ - this->aabb_center).norm();
91 }
92 
93 //==============================================================================
94 template <typename S>
95 AABB<S> OcTree<S>::getRootBV() const
96 {
97  S delta = (1 << tree->getTreeDepth()) * tree->getResolution() / 2;
98 
99  // std::cout << "octree size " << delta << std::endl;
100  return AABB<S>(Vector3<S>(-delta, -delta, -delta), Vector3<S>(delta, delta, delta));
101 }
102 
103 //==============================================================================
104 template <typename S>
105 typename OcTree<S>::OcTreeNode* OcTree<S>::getRoot() const
106 {
107  return tree->getRoot();
108 }
109 
110 //==============================================================================
111 template <typename S>
112 bool OcTree<S>::isNodeOccupied(const typename OcTree<S>::OcTreeNode* node) const
113 {
114  // return tree->isNodeOccupied(node);
115  return node->getLogOdds() >= occupancy_threshold_log_odds;
116 }
117 
118 //==============================================================================
119 template <typename S>
120 bool OcTree<S>::isNodeFree(const typename OcTree<S>::OcTreeNode* node) const
121 {
122  // return false; // default no definitely free node
123  return node->getLogOdds() <= free_threshold_log_odds;
124 }
125 
126 //==============================================================================
127 template <typename S>
128 bool OcTree<S>::isNodeUncertain(const typename OcTree<S>::OcTreeNode* node) const
129 {
130  return (!isNodeOccupied(node)) && (!isNodeFree(node));
131 }
132 
133 //==============================================================================
134 template <typename S>
135 S OcTree<S>::getOccupancyThres() const
136 {
137  return octomap::probability(occupancy_threshold_log_odds);
138 }
139 
140 //==============================================================================
141 template <typename S>
142 S OcTree<S>::getFreeThres() const
143 {
144  return octomap::probability(free_threshold_log_odds);
145 }
146 
147 //==============================================================================
148 template <typename S>
149 S OcTree<S>::getDefaultOccupancy() const
150 {
151  return default_occupancy;
152 }
153 
154 //==============================================================================
155 template <typename S>
156 void OcTree<S>::setCellDefaultOccupancy(S d)
157 {
158  default_occupancy = d;
159 }
160 
161 //==============================================================================
162 template <typename S>
163 void OcTree<S>::setOccupancyThres(S d)
164 {
165  occupancy_threshold_log_odds = octomap::logodds(d);
166 }
167 
168 //==============================================================================
169 template <typename S>
170 void OcTree<S>::setFreeThres(S d)
171 {
172  free_threshold_log_odds = octomap::logodds(d);
173 }
174 
175 //==============================================================================
176 template <typename S>
177 typename OcTree<S>::OcTreeNode* OcTree<S>::getNodeChild(
178  typename OcTree<S>::OcTreeNode* node, unsigned int childIdx)
179 {
180 #if OCTOMAP_VERSION_AT_LEAST(1,8,0)
181  return tree->getNodeChild(node, childIdx);
182 #else
183  return node->getChild(childIdx);
184 #endif
185 }
186 
187 //==============================================================================
188 template <typename S>
189 const typename OcTree<S>::OcTreeNode* OcTree<S>::getNodeChild(
190  const typename OcTree<S>::OcTreeNode* node, unsigned int childIdx) const
191 {
192 #if OCTOMAP_VERSION_AT_LEAST(1,8,0)
193  return tree->getNodeChild(node, childIdx);
194 #else
195  return node->getChild(childIdx);
196 #endif
197 }
198 
199 //==============================================================================
200 template <typename S>
201 bool OcTree<S>::nodeChildExists(
202  const typename OcTree<S>::OcTreeNode* node, unsigned int childIdx) const
203 {
204 #if OCTOMAP_VERSION_AT_LEAST(1,8,0)
205  return tree->nodeChildExists(node, childIdx);
206 #else
207  return node->childExists(childIdx);
208 #endif
209 }
210 
211 //==============================================================================
212 template <typename S>
213 bool OcTree<S>::nodeHasChildren(const typename OcTree<S>::OcTreeNode* node) const
214 {
215 #if OCTOMAP_VERSION_AT_LEAST(1,8,0)
216  return tree->nodeHasChildren(node);
217 #else
218  return node->hasChildren();
219 #endif
220 }
221 
222 //==============================================================================
223 template <typename S>
224 OBJECT_TYPE OcTree<S>::getObjectType() const
225 {
226  return OT_OCTREE;
227 }
228 
229 //==============================================================================
230 template <typename S>
231 NODE_TYPE OcTree<S>::getNodeType() const
232 {
233  return GEOM_OCTREE;
234 }
235 
236 //==============================================================================
237 template <typename S>
238 std::vector<std::array<S, 6>> OcTree<S>::toBoxes() const
239 {
240  std::vector<std::array<S, 6>> boxes;
241  boxes.reserve(tree->size() / 2);
242  for(auto it = tree->begin(tree->getTreeDepth()), end = tree->end();
243  it != end;
244  ++it)
245  {
246  // if(tree->isNodeOccupied(*it))
247  if(isNodeOccupied(&*it))
248  {
249  S size = it.getSize();
250  S x = it.getX();
251  S y = it.getY();
252  S z = it.getZ();
253  S c = (*it).getOccupancy();
254  S t = tree->getOccupancyThres();
255 
256  std::array<S, 6> box = {{x, y, z, size, c, t}};
257  boxes.push_back(box);
258  }
259  }
260  return boxes;
261 }
262 
263 //==============================================================================
264 template <typename S>
265 void computeChildBV(const AABB<S>& root_bv, unsigned int i, AABB<S>& child_bv)
266 {
267  if(i&1)
268  {
269  child_bv.min_[0] = (root_bv.min_[0] + root_bv.max_[0]) * 0.5;
270  child_bv.max_[0] = root_bv.max_[0];
271  }
272  else
273  {
274  child_bv.min_[0] = root_bv.min_[0];
275  child_bv.max_[0] = (root_bv.min_[0] + root_bv.max_[0]) * 0.5;
276  }
277 
278  if(i&2)
279  {
280  child_bv.min_[1] = (root_bv.min_[1] + root_bv.max_[1]) * 0.5;
281  child_bv.max_[1] = root_bv.max_[1];
282  }
283  else
284  {
285  child_bv.min_[1] = root_bv.min_[1];
286  child_bv.max_[1] = (root_bv.min_[1] + root_bv.max_[1]) * 0.5;
287  }
288 
289  if(i&4)
290  {
291  child_bv.min_[2] = (root_bv.min_[2] + root_bv.max_[2]) * 0.5;
292  child_bv.max_[2] = root_bv.max_[2];
293  }
294  else
295  {
296  child_bv.min_[2] = root_bv.min_[2];
297  child_bv.max_[2] = (root_bv.min_[2] + root_bv.max_[2]) * 0.5;
298  }
299 }
300 
301 //==============================================================================
302 template <typename S>
303 const typename OcTree<S>::OcTreeNode* OcTree<S>::getNodeByQueryCellId(
304  intptr_t id,
305  const Vector3<S>& point,
306  AABB<S>* aabb,
307  octomap::OcTreeKey* key,
308  unsigned int* depth) const
309 {
310  octomap::OcTree::leaf_bbx_iterator it;
311  if (!getOctomapIterator(id, point, &it))
312  {
313  return nullptr;
314  }
315  if (aabb != nullptr)
316  {
317  Vector3<S> center(it.getX(), it.getY(), it.getZ());
318  double half_size = it.getSize() / 2.0;
319  Vector3<S> half_extent(half_size, half_size, half_size);
320  aabb->min_ = center - half_extent;
321  aabb->max_ = center + half_extent;
322  }
323  if (key != nullptr)
324  *key = it.getKey();
325  if (depth != nullptr)
326  *depth = it.getDepth();
327  return &(*it);
328 }
329 
330 //==============================================================================
331 template <typename S>
332 bool OcTree<S>::getOctomapIterator(
333  intptr_t id,
334  const Vector3<S>& point,
335  octomap::OcTree::leaf_bbx_iterator* out) const
336 {
337  assert(out != nullptr);
338  // The octomap tree structure provides no way to find a node from its pointer
339  // short of an exhaustive search. This could take a long time on a large
340  // tree. Instead, require the user to supply the contact point or nearest
341  // point returned by the query that also returned the id. Use the point to
342  // create the bounds to search for the node pointer.
343  const octomap::OcTreeKey point_key = tree->coordToKey(
344  point[0], point[1], point[2]);
345  // Set the min and max keys used for the bbx to the point key plus or minus
346  // one (if not at the limits of the data type) so we are guaranteed to hit
347  // the correct cell even when the point is on a boundary and rounds to the
348  // wrong cell.
349  octomap::OcTreeKey min_key, max_key;
350  for (unsigned int i = 0; i < 3; ++i)
351  {
352  min_key[i] = (point_key[i] > std::numeric_limits<octomap::key_type>::min() ?
353  point_key[i] - 1 : point_key[i]);
354  max_key[i] = (point_key[i] < std::numeric_limits<octomap::key_type>::max() ?
355  point_key[i] + 1 : point_key[i]);
356  }
357  octomap::OcTree::leaf_bbx_iterator it = tree->begin_leafs_bbx(
358  min_key, max_key);
359  const octomap::OcTree::leaf_bbx_iterator end = tree->end_leafs_bbx();
360  const OcTreeNode* const node = getRoot() + id;
361  // While it may appear like this loop could take forever, in reality it will
362  // only take a few iterations. Octomap iterators use a fixed end iterator
363  // (copied above), and we are guaranteed to get to the end iterator after
364  // incrementing past the bounds of the octomap::OcTree::leaf_bbx_iterator.
365  // Incrementing end will keep the iterator at end as well. This functionality
366  // of octomap iterators is tested extensively in the octomap package tests.
367  while (it != end)
368  {
369  if (node == &(*it))
370  {
371  *out = it;
372  return true;
373  }
374  ++it;
375  }
376  return false;
377 }
378 
379 } // namespace fcl
380 
381 #endif
382 
383 #endif
utility.h
fcl::GEOM_OCTREE
@ GEOM_OCTREE
Definition: collision_geometry.h:54
max
static T max(T x, T y)
Definition: svm.cpp:52
octomap::probability
double probability(double logodds)
octomap::OcTreeKey
fcl::time::point
std::chrono::system_clock::time_point point
Representation of a point in time.
Definition: time.h:52
fcl::OBJECT_TYPE
OBJECT_TYPE
object type: BVH (mesh, points), basic geometry, octree
Definition: collision_geometry.h:50
octomap::logodds
float logodds(double probability)
fcl::intptr_t
std::intptr_t intptr_t
Definition: types.h:63
fcl::OT_OCTREE
@ OT_OCTREE
Definition: collision_geometry.h:50
half_size
Vector3< S > half_size
Definition: test_sphere_box.cpp:169
min
static T min(T x, T y)
Definition: svm.cpp:49
fcl::AABB< double >
template class FCL_EXPORT AABB< double >
octomap
aabb
SaPCollisionManager< S >::SaPAABB * aabb
back pointer to SAP interval
Definition: broadphase_SaP.h:184
octree.h
fcl::NODE_TYPE
NODE_TYPE
traversal node type: bounding volume (AABB, OBB, RSS, kIOS, OBBRSS, KDOP16, KDOP18,...
Definition: collision_geometry.h:53
fcl
Main namespace.
Definition: broadphase_bruteforce-inl.h:45


fcl
Author(s):
autogenerated on Tue Dec 5 2023 03:40:48