38 #ifndef FCL_OCTREE_INL_H
39 #define FCL_OCTREE_INL_H
43 #include "fcl/config.h"
54 class FCL_EXPORT OcTree<double>;
62 OcTree<S>::OcTree(S resolution)
63 : tree(std::shared_ptr<const
octomap::OcTree>(new
octomap::OcTree(resolution)))
65 default_occupancy = tree->getOccupancyThres();
68 occupancy_threshold_log_odds = tree->getOccupancyThresLog();
69 free_threshold_log_odds = 0.0;
74 OcTree<S>::OcTree(
const std::shared_ptr<const octomap::OcTree>& tree_)
77 default_occupancy = tree->getOccupancyThres();
80 occupancy_threshold_log_odds = tree->getOccupancyThresLog();
81 free_threshold_log_odds = 0;
86 void OcTree<S>::computeLocalAABB()
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();
95 AABB<S> OcTree<S>::getRootBV()
const
97 S delta = (1 << tree->getTreeDepth()) * tree->getResolution() / 2;
100 return AABB<S>(Vector3<S>(-delta, -delta, -delta), Vector3<S>(delta, delta, delta));
104 template <
typename S>
105 typename OcTree<S>::OcTreeNode* OcTree<S>::getRoot()
const
107 return tree->getRoot();
111 template <
typename S>
112 bool OcTree<S>::isNodeOccupied(
const typename OcTree<S>::OcTreeNode* node)
const
115 return node->getLogOdds() >= occupancy_threshold_log_odds;
119 template <
typename S>
120 bool OcTree<S>::isNodeFree(
const typename OcTree<S>::OcTreeNode* node)
const
123 return node->getLogOdds() <= free_threshold_log_odds;
127 template <
typename S>
128 bool OcTree<S>::isNodeUncertain(
const typename OcTree<S>::OcTreeNode* node)
const
130 return (!isNodeOccupied(node)) && (!isNodeFree(node));
134 template <
typename S>
135 S OcTree<S>::getOccupancyThres()
const
141 template <
typename S>
142 S OcTree<S>::getFreeThres()
const
148 template <
typename S>
149 S OcTree<S>::getDefaultOccupancy()
const
151 return default_occupancy;
155 template <
typename S>
156 void OcTree<S>::setCellDefaultOccupancy(S d)
158 default_occupancy = d;
162 template <
typename S>
163 void OcTree<S>::setOccupancyThres(S d)
169 template <
typename S>
170 void OcTree<S>::setFreeThres(S d)
176 template <
typename S>
177 typename OcTree<S>::OcTreeNode* OcTree<S>::getNodeChild(
178 typename OcTree<S>::OcTreeNode* node,
unsigned int childIdx)
180 #if OCTOMAP_VERSION_AT_LEAST(1,8,0)
181 return tree->getNodeChild(node, childIdx);
183 return node->getChild(childIdx);
188 template <
typename S>
189 const typename OcTree<S>::OcTreeNode* OcTree<S>::getNodeChild(
190 const typename OcTree<S>::OcTreeNode* node,
unsigned int childIdx)
const
192 #if OCTOMAP_VERSION_AT_LEAST(1,8,0)
193 return tree->getNodeChild(node, childIdx);
195 return node->getChild(childIdx);
200 template <
typename S>
201 bool OcTree<S>::nodeChildExists(
202 const typename OcTree<S>::OcTreeNode* node,
unsigned int childIdx)
const
204 #if OCTOMAP_VERSION_AT_LEAST(1,8,0)
205 return tree->nodeChildExists(node, childIdx);
207 return node->childExists(childIdx);
212 template <
typename S>
213 bool OcTree<S>::nodeHasChildren(
const typename OcTree<S>::OcTreeNode* node)
const
215 #if OCTOMAP_VERSION_AT_LEAST(1,8,0)
216 return tree->nodeHasChildren(node);
218 return node->hasChildren();
223 template <
typename S>
230 template <
typename S>
237 template <
typename S>
238 std::vector<std::array<S, 6>> OcTree<S>::toBoxes()
const
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();
247 if(isNodeOccupied(&*it))
249 S size = it.getSize();
253 S c = (*it).getOccupancy();
254 S t = tree->getOccupancyThres();
256 std::array<S, 6> box = {{x, y, z, size, c, t}};
257 boxes.push_back(box);
264 template <
typename S>
265 void computeChildBV(
const AABB<S>& root_bv,
unsigned int i, AABB<S>& child_bv)
269 child_bv.min_[0] = (root_bv.min_[0] + root_bv.max_[0]) * 0.5;
270 child_bv.max_[0] = root_bv.max_[0];
274 child_bv.min_[0] = root_bv.min_[0];
275 child_bv.max_[0] = (root_bv.min_[0] + root_bv.max_[0]) * 0.5;
280 child_bv.min_[1] = (root_bv.min_[1] + root_bv.max_[1]) * 0.5;
281 child_bv.max_[1] = root_bv.max_[1];
285 child_bv.min_[1] = root_bv.min_[1];
286 child_bv.max_[1] = (root_bv.min_[1] + root_bv.max_[1]) * 0.5;
291 child_bv.min_[2] = (root_bv.min_[2] + root_bv.max_[2]) * 0.5;
292 child_bv.max_[2] = root_bv.max_[2];
296 child_bv.min_[2] = root_bv.min_[2];
297 child_bv.max_[2] = (root_bv.min_[2] + root_bv.max_[2]) * 0.5;
302 template <
typename S>
303 const typename OcTree<S>::OcTreeNode* OcTree<S>::getNodeByQueryCellId(
305 const Vector3<S>&
point,
308 unsigned int* depth)
const
310 octomap::OcTree::leaf_bbx_iterator it;
311 if (!getOctomapIterator(
id,
point, &it))
317 Vector3<S> center(it.getX(), it.getY(), it.getZ());
320 aabb->min_ = center - half_extent;
321 aabb->max_ = center + half_extent;
325 if (depth !=
nullptr)
326 *depth = it.getDepth();
331 template <
typename S>
332 bool OcTree<S>::getOctomapIterator(
334 const Vector3<S>&
point,
335 octomap::OcTree::leaf_bbx_iterator* out)
const
337 assert(out !=
nullptr);
350 for (
unsigned int i = 0; i < 3; ++i)
353 point_key[i] - 1 : point_key[i]);
355 point_key[i] + 1 : point_key[i]);
357 octomap::OcTree::leaf_bbx_iterator it = tree->begin_leafs_bbx(
359 const octomap::OcTree::leaf_bbx_iterator end = tree->end_leafs_bbx();
360 const OcTreeNode*
const node = getRoot() + id;