Go to the documentation of this file.
   44 #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();
 
   92         default_occupancy(other.default_occupancy),
 
   93         occupancy_threshold(other.occupancy_threshold),
 
   94         free_threshold(other.free_threshold) {}
 
  100   shared_ptr<const octomap::OcTree> 
getTree()
 const { 
return tree; }
 
  102   void exportAsObjFile(
const std::string& 
filename) 
const;
 
  106     typedef Eigen::Matrix<float, 3, 1> Vec3sloat;
 
  107     Vec3sloat max_extent, min_extent;
 
  109     octomap::OcTree::iterator it =
 
  110         tree->begin((
unsigned char)tree->getTreeDepth());
 
  111     octomap::OcTree::iterator end = tree->end();
 
  113     if (it == end) 
return;
 
  116       const octomap::point3d& coord =
 
  118       max_extent = min_extent = Eigen::Map<const Vec3sloat>(&coord.x());
 
  119       for (++it; it != end; ++it) {
 
  120         const octomap::point3d& coord = it.getCoordinate();
 
  121         const Vec3sloat 
pos = Eigen::Map<const Vec3sloat>(&coord.x());
 
  122         max_extent = max_extent.array().max(
pos.array());
 
  123         min_extent = min_extent.array().min(
pos.array());
 
  128     const CoalScalar resolution = tree->getResolution();
 
  129     max_extent.array() += float(resolution / 2.);
 
  130     min_extent.array() -= float(resolution / 2.);
 
  134     aabb_center = aabb_local.center();
 
  135     aabb_radius = (aabb_local.min_ - aabb_center).norm();
 
  140     CoalScalar delta = (1 << tree->getTreeDepth()) * tree->getResolution() / 2;
 
  143     return AABB(
Vec3s(-delta, -delta, -delta), 
Vec3s(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<Vec6s> boxes;
 
  180     boxes.reserve(tree->size() / 2);
 
  181     for (octomap::OcTree::iterator
 
  182              it = tree->begin((
unsigned char)tree->getTreeDepth()),
 
  186       if (isNodeOccupied(&*it)) {
 
  196         boxes.push_back(
box);
 
  204     typedef Eigen::Matrix<float, 3, 1> Vec3sloat;
 
  205     const size_t total_size = (tree->size() * 
sizeof(
CoalScalar) * 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 Vec3s box_pos =
 
  214           Eigen::Map<Vec3sloat>(&it.getCoordinate().x()).cast<
CoalScalar>();
 
  215       if (isNodeOccupied(&*it))
 
  216         std::copy(box_pos.data(), box_pos.data() + 
sizeof(
CoalScalar) * 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
 
  302     child_bv.
min_[0] = (root_bv.
min_[0] + root_bv.
max_[0]) * 0.5;
 
  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;
 
  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;
 
  322     child_bv.
max_[2] = (root_bv.
min_[2] + root_bv.
max_[2]) * 0.5;
 
  335 makeOctree(
const Eigen::Matrix<CoalScalar, Eigen::Dynamic, 3>& point_cloud,
 
  
const OcTreeNode * getNodeChild(const OcTreeNode *node, unsigned int childIdx) const
std::vector< Vec6s > toBoxes() const
transform the octree into a bunch of boxes; uncertainty information is kept in the boxes....
NODE_TYPE getNodeType() const
return node type, it is an octree
Eigen::Matrix< CoalScalar, 3, 1 > Vec3s
shared_ptr< const octomap::OcTree > tree
OcTreeNode * getRoot() const
get the root node of the octree
AABB getRootBV() const
get the bounding volume for the root
NODE_TYPE
traversal node type: bounding volume (AABB, OBB, RSS, kIOS, OBBRSS, KDOP16, KDOP18,...
CoalScalar occupancy_threshold
CoalScalar free_threshold
unsigned long size() const
Returns the size of the octree.
std::vector< uint8_t > tobytes() const
Returns a byte description of *this.
COAL_DLLAPI OcTreePtr_t makeOctree(const Eigen::Matrix< CoalScalar, Eigen::Dynamic, 3 > &point_cloud, const CoalScalar resolution)
Build an OcTree from a point cloud and a given resolution.
bool isNodeOccupied(const OcTreeNode *node) const
whether one node is completely occupied
CoalScalar getResolution() const
Returns the resolution of the octree.
The geometry for the object for collision or distance computation.
OBJECT_TYPE getObjectType() const
return object type, it is an octree
A class describing the AABB collision structure, which is a box in 3D space determined by two diagona...
bool nodeHasChildren(const OcTreeNode *node) const
return true if node has at least one child
bool isNodeFree(const OcTreeNode *node) const
whether one node is completely free
Vec3s max_
The max point in the AABB.
OcTreeNode * getNodeChild(OcTreeNode *node, unsigned int childIdx)
OcTree(CoalScalar resolution)
construct octree with a given resolution
CoalScalar getOccupancyThres() const
the threshold used to decide whether one node is occupied, this is NOT the octree occupied_thresold
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
Eigen::Matrix< CoalScalar, 6, 1 > Vec6s
void setFreeThres(CoalScalar d)
void setOccupancyThres(CoalScalar d)
bool nodeChildExists(const OcTreeNode *node, unsigned int childIdx) const
return true if the child at childIdx exists
void computeLocalAABB()
compute the AABB for the octree in its local coordinate system
void setCellDefaultOccupancy(CoalScalar d)
OBJECT_TYPE
object type: BVH (mesh, points), basic geometry, octree
bool isNodeUncertain(const OcTreeNode *node) const
whether one node is uncertain
Vec3s min_
The min point in the AABB.
shared_ptr< OcTree > OcTreePtr_t
octomap::OcTreeNode OcTreeNode
Octree is one type of collision geometry which can encode uncertainty information in the sensor data.
virtual bool isEqual(const CollisionGeometry &_other) const
equal operator with another object of derived type.
CoalScalar getDefaultOccupancy() const
shared_ptr< const octomap::OcTree > getTree() const
Returns the tree associated to the underlying octomap OcTree.
OcTree * clone() const
Clone *this into a new Octree.
CoalScalar getFreeThres() const
the threshold used to decide whether one node is free, this is NOT the octree free_threshold
CoalScalar default_occupancy
OcTree(const shared_ptr< const octomap::OcTree > &tree_)
construct octree from octomap
unsigned int getTreeDepth() const
Returns the depth of the octree.
OcTree(const OcTree &other)
 
hpp-fcl
Author(s): 
autogenerated on Fri Feb 14 2025 03:45:51