41 #include "fcl/config.h" 64 class FCL_EXPORT OcTree :
public CollisionGeometry<S>
67 std::shared_ptr<const octomap::OcTree> tree;
71 S occupancy_threshold_log_odds;
72 S free_threshold_log_odds;
82 OcTree(
const std::shared_ptr<const octomap::OcTree>& tree_);
85 void computeLocalAABB();
88 AABB<S> getRootBV()
const;
91 OcTreeNode* getRoot()
const;
94 bool isNodeOccupied(
const OcTreeNode* node)
const;
97 bool isNodeFree(
const OcTreeNode* node)
const;
100 bool isNodeUncertain(
const OcTreeNode* node)
const;
105 std::vector<std::array<S, 6> > toBoxes()
const;
109 S getOccupancyThres()
const;
113 S getFreeThres()
const;
115 S getDefaultOccupancy()
const;
117 void setCellDefaultOccupancy(S d);
119 void setOccupancyThres(S d);
121 void setFreeThres(S d);
124 OcTreeNode* getNodeChild(OcTreeNode* node,
unsigned int childIdx);
127 const OcTreeNode* getNodeChild(
const OcTreeNode* node,
unsigned int childIdx)
const;
130 bool nodeChildExists(
const OcTreeNode* node,
unsigned int childIdx)
const;
133 bool nodeHasChildren(
const OcTreeNode* node)
const;
171 const OcTreeNode* getNodeByQueryCellId(
173 const Vector3<S>&
point,
174 AABB<S>*
aabb =
nullptr,
176 unsigned int* depth =
nullptr)
const;
182 bool getOctomapIterator(
184 const Vector3<S>&
point,
185 octomap::OcTree::leaf_bbx_iterator* out)
const;
188 using OcTreef = OcTree<float>;
189 using OcTreed = OcTree<double>;
192 template <
typename S>
194 void computeChildBV(
const AABB<S>& root_bv,
unsigned int i, AABB<S>& child_bv);
200 #endif // #if FCL_HAVE_OCTOMAP
NODE_TYPE
traversal node type: bounding volume (AABB, OBB, RSS, kIOS, OBBRSS, KDOP16, KDOP18, kDOP24), basic shape (box, sphere, ellipsoid, capsule, cone, cylinder, convex, plane, halfspace, triangle), and octree
SaPCollisionManager< S >::SaPAABB * aabb
back pointer to SAP interval
OBJECT_TYPE
object type: BVH (mesh, points), basic geometry, octree
std::chrono::system_clock::time_point point
Representation of a point in time.