Go to the documentation of this file.
38 #ifndef HPP_FCL_OCTREE_H
39 #define HPP_FCL_OCTREE_H
41 #include <boost/array.hpp>
43 #include <octomap/octomap.h>
55 shared_ptr<const octomap::OcTree>
tree;
69 default_occupancy = tree->getOccupancyThres();
73 occupancy_threshold = tree->getOccupancyThres();
78 explicit OcTree(
const shared_ptr<const octomap::OcTree>& tree_)
80 default_occupancy = tree->getOccupancyThres();
84 occupancy_threshold = tree->getOccupancyThres();
91 default_occupancy(other.default_occupancy),
92 occupancy_threshold(other.occupancy_threshold),
93 free_threshold(other.free_threshold) {}
97 void exportAsObjFile(
const std::string&
filename)
const;
101 aabb_local = getRootBV();
102 aabb_center = aabb_local.center();
103 aabb_radius = (aabb_local.min_ - aabb_center).norm();
108 FCL_REAL delta = (1 << tree->getTreeDepth()) * tree->getResolution() / 2;
111 return AABB(
Vec3f(-delta, -delta, -delta),
Vec3f(delta, delta, delta));
123 return node->getOccupancy() >= occupancy_threshold;
129 return node->getOccupancy() <= free_threshold;
134 return (!isNodeOccupied(node)) && (!isNodeFree(node));
140 std::vector<boost::array<FCL_REAL, 6> >
toBoxes()
const {
141 std::vector<boost::array<FCL_REAL, 6> > boxes;
142 boxes.reserve(tree->size() / 2);
143 for (octomap::OcTree::iterator
144 it = tree->begin((
unsigned char)tree->getTreeDepth()),
148 if (isNodeOccupied(&*it)) {
156 boost::array<FCL_REAL, 6>
box = {{
x,
y, z, size,
c,
t}};
157 boxes.push_back(
box);
181 #if OCTOMAP_VERSION_AT_LEAST(1, 8, 0)
182 return tree->getNodeChild(node, childIdx);
184 return node->getChild(childIdx);
190 unsigned int childIdx)
const {
191 #if OCTOMAP_VERSION_AT_LEAST(1, 8, 0)
192 return tree->getNodeChild(node, childIdx);
194 return node->getChild(childIdx);
200 #if OCTOMAP_VERSION_AT_LEAST(1, 8, 0)
201 return tree->nodeChildExists(node, childIdx);
203 return node->childExists(childIdx);
209 #if OCTOMAP_VERSION_AT_LEAST(1, 8, 0)
210 return tree->nodeHasChildren(node);
212 return node->hasChildren();
224 const OcTree* other_ptr =
dynamic_cast<const OcTree*
>(&_other);
225 if (other_ptr ==
nullptr)
return false;
226 const OcTree& other = *other_ptr;
228 return tree.get() == other.
tree.get() &&
235 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
242 child_bv.
min_[0] = (root_bv.
min_[0] + root_bv.
max_[0]) * 0.5;
246 child_bv.
max_[0] = (root_bv.
min_[0] + root_bv.
max_[0]) * 0.5;
250 child_bv.
min_[1] = (root_bv.
min_[1] + root_bv.
max_[1]) * 0.5;
254 child_bv.
max_[1] = (root_bv.
min_[1] + root_bv.
max_[1]) * 0.5;
258 child_bv.
min_[2] = (root_bv.
min_[2] + root_bv.
max_[2]) * 0.5;
262 child_bv.
max_[2] = (root_bv.
min_[2] + root_bv.
max_[2]) * 0.5;
275 makeOctree(
const Eigen::Matrix<FCL_REAL, Eigen::Dynamic, 3>& point_cloud,
Eigen::Matrix< FCL_REAL, 3, 1 > Vec3f
bool nodeHasChildren(const OcTreeNode *node) const
return true if node has at least one child
FCL_REAL getFreeThres() const
the threshold used to decide whether one node is free, this is NOT the octree free_threshold
shared_ptr< OcTree > OcTreePtr_t
void setFreeThres(FCL_REAL d)
Vec3f min_
The min point in the AABB.
FCL_REAL default_occupancy
Vec3f max_
The max point in the AABB.
void setCellDefaultOccupancy(FCL_REAL d)
FCL_REAL getOccupancyThres() const
the threshold used to decide whether one node is occupied, this is NOT the octree occupied_thresold
void computeLocalAABB()
compute the AABB for the octree in its local coordinate system
The geometry for the object for collision or distance computation.
NODE_TYPE
traversal node type: bounding volume (AABB, OBB, RSS, kIOS, OBBRSS, KDOP16, KDOP18,...
virtual bool isEqual(const CollisionGeometry &_other) const
equal operator with another object of derived type.
OcTreeNode * getRoot() const
get the root node of the octree
octomap::OcTreeNode OcTreeNode
HPP_FCL_DLLAPI OcTreePtr_t makeOctree(const Eigen::Matrix< FCL_REAL, Eigen::Dynamic, 3 > &point_cloud, const FCL_REAL resolution)
Build an OcTree from a point cloud and a given resolution.
static void computeChildBV(const AABB &root_bv, unsigned int i, AABB &child_bv)
compute the bounding volume of an octree node's i-th child
OBJECT_TYPE
object type: BVH (mesh, points), basic geometry, octree
AABB getRootBV() const
get the bounding volume for the root
bool isNodeUncertain(const OcTreeNode *node) const
whether one node is uncertain
OcTree(const shared_ptr< const octomap::OcTree > &tree_)
construct octree from octomap
OcTreeNode * getNodeChild(OcTreeNode *node, unsigned int childIdx)
OcTree * clone() const
Clone *this into a new CollisionGeometry.
A class describing the AABB collision structure, which is a box in 3D space determined by two diagona...
FCL_REAL occupancy_threshold
bool nodeChildExists(const OcTreeNode *node, unsigned int childIdx) const
return true if the child at childIdx exists
shared_ptr< const octomap::OcTree > tree
NODE_TYPE getNodeType() const
return node type, it is an octree
bool isNodeOccupied(const OcTreeNode *node) const
whether one node is completely occupied
void setOccupancyThres(FCL_REAL d)
std::vector< boost::array< FCL_REAL, 6 > > toBoxes() const
transform the octree into a bunch of boxes; uncertainty information is kept in the boxes....
bool isNodeFree(const OcTreeNode *node) const
whether one node is completely free
FCL_REAL getDefaultOccupancy() const
const OcTreeNode * getNodeChild(const OcTreeNode *node, unsigned int childIdx) const
OBJECT_TYPE getObjectType() const
return object type, it is an octree
Octree is one type of collision geometry which can encode uncertainty information in the sensor data.
OcTree(FCL_REAL resolution)
construct octree with a given resolution
unsigned int getTreeDepth() const
Returns the depth of octree.
OcTree(const OcTree &other)
hpp-fcl
Author(s):
autogenerated on Fri Aug 2 2024 02:45:14