39 #ifndef HPP_FCL_OCTREE_H
40 #define HPP_FCL_OCTREE_H
44 #include <octomap/octomap.h>
56 shared_ptr<const octomap::OcTree>
tree;
68 : tree(shared_ptr<const octomap::
OcTree>(
69 new octomap::
OcTree(resolution))) {
70 default_occupancy = tree->getOccupancyThres();
74 occupancy_threshold = tree->getOccupancyThres();
79 explicit OcTree(
const shared_ptr<const octomap::OcTree>& tree_)
81 default_occupancy = tree->getOccupancyThres();
85 occupancy_threshold = tree->getOccupancyThres();
93 default_occupancy(other.default_occupancy),
94 occupancy_threshold(other.occupancy_threshold),
95 free_threshold(other.free_threshold) {}
101 shared_ptr<const octomap::OcTree>
getTree()
const {
return tree; }
107 typedef Eigen::Matrix<float, 3, 1> Vec3float;
108 Vec3float max_extent, min_extent;
110 octomap::OcTree::iterator it =
111 tree->begin((
unsigned char)tree->getTreeDepth());
112 octomap::OcTree::iterator end = tree->end();
114 if (it == end)
return;
117 const octomap::point3d& coord =
119 max_extent = min_extent = Eigen::Map<const Vec3float>(&coord.x());
120 for (++it; it != end; ++it) {
121 const octomap::point3d& coord = it.getCoordinate();
122 const Vec3float pos = Eigen::Map<const Vec3float>(&coord.x());
123 max_extent = max_extent.array().max(pos.array());
124 min_extent = min_extent.array().min(pos.array());
129 const FCL_REAL resolution = tree->getResolution();
130 max_extent.array() += float(resolution / 2.);
131 min_extent.array() -= float(resolution / 2.);
134 aabb_center = aabb_local.center();
135 aabb_radius = (aabb_local.min_ - aabb_center).norm();
140 FCL_REAL delta = (1 << tree->getTreeDepth()) * tree->getResolution() / 2;
143 return AABB(
Vec3f(-delta, -delta, -delta),
Vec3f(delta, delta, delta));
150 unsigned long size()
const {
return tree->size(); }
161 return node->getOccupancy() >= occupancy_threshold;
167 return node->getOccupancy() <= free_threshold;
172 return (!isNodeOccupied(node)) && (!isNodeFree(node));
179 std::vector<Vec6f> boxes;
180 boxes.reserve(tree->size() / 2);
181 for (octomap::OcTree::iterator
182 it = tree->begin((
unsigned char)tree->getTreeDepth()),
186 if (isNodeOccupied(&*it)) {
192 FCL_REAL t = tree->getOccupancyThres();
195 box << x, y, z, size, c, t;
196 boxes.push_back(box);
204 typedef Eigen::Matrix<float, 3, 1> Vec3float;
205 const size_t total_size = (tree->size() *
sizeof(
FCL_REAL) * 3) / 2;
206 std::vector<uint8_t> bytes;
207 bytes.reserve(total_size);
209 for (octomap::OcTree::iterator
210 it = tree->begin((
unsigned char)tree->getTreeDepth()),
213 const Vec3f box_pos =
214 Eigen::Map<Vec3float>(&it.getCoordinate().x()).cast<
FCL_REAL>();
215 if (isNodeOccupied(&*it))
216 std::copy(box_pos.data(), box_pos.data() +
sizeof(
FCL_REAL) * 3,
217 std::back_inserter(bytes));
241 #if OCTOMAP_VERSION_AT_LEAST(1, 8, 0)
242 return tree->getNodeChild(node, childIdx);
244 return node->getChild(childIdx);
250 unsigned int childIdx)
const {
251 #if OCTOMAP_VERSION_AT_LEAST(1, 8, 0)
252 return tree->getNodeChild(node, childIdx);
254 return node->getChild(childIdx);
260 #if OCTOMAP_VERSION_AT_LEAST(1, 8, 0)
261 return tree->nodeChildExists(node, childIdx);
263 return node->childExists(childIdx);
269 #if OCTOMAP_VERSION_AT_LEAST(1, 8, 0)
270 return tree->nodeHasChildren(node);
272 return node->hasChildren();
284 const OcTree* other_ptr =
dynamic_cast<const OcTree*
>(&_other);
285 if (other_ptr ==
nullptr)
return false;
286 const OcTree& other = *other_ptr;
288 return (tree.get() == other.
tree.get() || toBoxes() == other.
toBoxes()) &&
295 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
299 static inline void computeChildBV(
const AABB& root_bv,
unsigned int i,
302 child_bv.min_[0] = (root_bv.min_[0] + root_bv.max_[0]) * 0.5;
303 child_bv.max_[0] = root_bv.max_[0];
305 child_bv.min_[0] = root_bv.min_[0];
306 child_bv.max_[0] = (root_bv.min_[0] + root_bv.max_[0]) * 0.5;
310 child_bv.min_[1] = (root_bv.min_[1] + root_bv.max_[1]) * 0.5;
311 child_bv.max_[1] = root_bv.max_[1];
313 child_bv.min_[1] = root_bv.min_[1];
314 child_bv.max_[1] = (root_bv.min_[1] + root_bv.max_[1]) * 0.5;
318 child_bv.min_[2] = (root_bv.min_[2] + root_bv.max_[2]) * 0.5;
319 child_bv.max_[2] = root_bv.max_[2];
321 child_bv.min_[2] = root_bv.min_[2];
322 child_bv.max_[2] = (root_bv.min_[2] + root_bv.max_[2]) * 0.5;
335 makeOctree(
const Eigen::Matrix<FCL_REAL, Eigen::Dynamic, 3>& point_cloud,
A class describing the AABB collision structure, which is a box in 3D space determined by two diagona...
Definition: AABB.h:56
The geometry for the object for collision or distance computation.
Definition: collision_object.h:95
Octree is one type of collision geometry which can encode uncertainty information in the sensor data.
Definition: octree.h:54
AABB getRootBV() const
get the bounding volume for the root
Definition: octree.h:139
unsigned long size() const
Returns the size of the octree.
Definition: octree.h:150
OcTree(FCL_REAL resolution)
construct octree with a given resolution
Definition: octree.h:67
shared_ptr< const octomap::OcTree > tree
Definition: octree.h:56
OBJECT_TYPE getObjectType() const
return object type, it is an octree
Definition: octree.h:277
FCL_REAL default_occupancy
Definition: octree.h:58
bool isNodeOccupied(const OcTreeNode *node) const
whether one node is completely occupied
Definition: octree.h:159
FCL_REAL getFreeThres() const
the threshold used to decide whether one node is free, this is NOT the octree free_threshold
Definition: octree.h:229
FCL_REAL getDefaultOccupancy() const
Definition: octree.h:231
OcTree(const OcTree &other)
 
Definition: octree.h:90
octomap::OcTreeNode OcTreeNode
Definition: octree.h:64
void setCellDefaultOccupancy(FCL_REAL d)
Definition: octree.h:233
OcTreeNode * getNodeChild(OcTreeNode *node, unsigned int childIdx)
Definition: octree.h:240
OcTreeNode * getRoot() const
get the root node of the octree
Definition: octree.h:156
void exportAsObjFile(const std::string &filename) const
unsigned int getTreeDepth() const
Returns the depth of the octree.
Definition: octree.h:147
void setFreeThres(FCL_REAL d)
Definition: octree.h:237
std::vector< Vec6f > toBoxes() const
transform the octree into a bunch of boxes; uncertainty information is kept in the boxes....
Definition: octree.h:178
bool isNodeUncertain(const OcTreeNode *node) const
whether one node is uncertain
Definition: octree.h:171
OcTree * clone() const
Clone *this into a new Octree.
Definition: octree.h:98
void setOccupancyThres(FCL_REAL d)
Definition: octree.h:235
bool nodeChildExists(const OcTreeNode *node, unsigned int childIdx) const
return true if the child at childIdx exists
Definition: octree.h:259
FCL_REAL getOccupancyThres() const
the threshold used to decide whether one node is occupied, this is NOT the octree occupied_thresold
Definition: octree.h:225
FCL_REAL getResolution() const
Returns the resolution of the octree.
Definition: octree.h:153
const OcTreeNode * getNodeChild(const OcTreeNode *node, unsigned int childIdx) const
Definition: octree.h:249
void computeLocalAABB()
compute the AABB for the octree in its local coordinate system
Definition: octree.h:106
FCL_REAL occupancy_threshold
Definition: octree.h:60
bool nodeHasChildren(const OcTreeNode *node) const
return true if node has at least one child
Definition: octree.h:268
OcTree(const shared_ptr< const octomap::OcTree > &tree_)
construct octree from octomap
Definition: octree.h:79
shared_ptr< const octomap::OcTree > getTree() const
Returns the tree associated to the underlying octomap OcTree.
Definition: octree.h:101
NODE_TYPE getNodeType() const
return node type, it is an octree
Definition: octree.h:280
bool isNodeFree(const OcTreeNode *node) const
whether one node is completely free
Definition: octree.h:165
std::vector< uint8_t > tobytes() const
Returns a byte description of *this.
Definition: octree.h:203
FCL_REAL free_threshold
Definition: octree.h:61
#define HPP_FCL_DLLAPI
Definition: config.hh:88
@ OT_OCTREE
Definition: collision_object.h:57
@ GEOM_OCTREE
Definition: collision_object.h:84
Eigen::Matrix< FCL_REAL, 3, 1 > Vec3f
Definition: data_types.h:67
OBJECT_TYPE
object type: BVH (mesh, points), basic geometry, octree
Definition: collision_object.h:53
NODE_TYPE
traversal node type: bounding volume (AABB, OBB, RSS, kIOS, OBBRSS, KDOP16, KDOP18,...
Definition: collision_object.h:65
shared_ptr< OcTree > OcTreePtr_t
Definition: fwd.hh:145
bool isEqual(const Eigen::MatrixBase< Derived > &lhs, const Eigen::MatrixBase< OtherDerived > &rhs, const FCL_REAL tol=std::numeric_limits< FCL_REAL >::epsilon() *100)
Definition: tools.h:205
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.
double FCL_REAL
Definition: data_types.h:66
Eigen::Matrix< FCL_REAL, 6, 1 > Vec6f
Definition: data_types.h:69
Main namespace.
Definition: broadphase_bruteforce.h:44