Class OcTree
Defined in File octree.h
Inheritance Relationships
Base Type
public coal::CollisionGeometry
(Class CollisionGeometry)
Derived Type
public boost::serialization::internal::OcTreeAccessor
(Struct OcTreeAccessor)
Class Documentation
-
class OcTree : public coal::CollisionGeometry
Octree is one type of collision geometry which can encode uncertainty information in the sensor data.
Subclassed by boost::serialization::internal::OcTreeAccessor
Public Types
-
typedef octomap::OcTreeNode OcTreeNode
Public Functions
-
inline explicit OcTree(CoalScalar resolution)
construct octree with a given resolution
construct octree from octomap
-
inline shared_ptr<const octomap::OcTree> getTree() const
Returns the tree associated to the underlying octomap OcTree.
-
void exportAsObjFile(const std::string &filename) const
-
inline virtual void computeLocalAABB()
compute the AABB for the octree in its local coordinate system
-
inline unsigned int getTreeDepth() const
Returns the depth of the octree.
-
inline unsigned long size() const
Returns the size of the octree.
-
inline CoalScalar getResolution() const
Returns the resolution of the octree.
-
inline OcTreeNode *getRoot() const
get the root node of the octree
-
inline bool isNodeOccupied(const OcTreeNode *node) const
whether one node is completely occupied
-
inline bool isNodeFree(const OcTreeNode *node) const
whether one node is completely free
-
inline bool isNodeUncertain(const OcTreeNode *node) const
whether one node is uncertain
-
inline std::vector<Vec6s> toBoxes() const
transform the octree into a bunch of boxes; uncertainty information is kept in the boxes. However, we only keep the occupied boxes (i.e., the boxes whose occupied probability is higher enough).
-
inline std::vector<uint8_t> tobytes() const
Returns a byte description of *this.
-
inline CoalScalar getOccupancyThres() const
the threshold used to decide whether one node is occupied, this is NOT the octree occupied_thresold
-
inline CoalScalar getFreeThres() const
the threshold used to decide whether one node is free, this is NOT the octree free_threshold
-
inline CoalScalar getDefaultOccupancy() const
-
inline void setCellDefaultOccupancy(CoalScalar d)
-
inline void setOccupancyThres(CoalScalar d)
-
inline void setFreeThres(CoalScalar d)
-
inline OcTreeNode *getNodeChild(OcTreeNode *node, unsigned int childIdx)
- Returns:
ptr to child number childIdx of node
-
inline const OcTreeNode *getNodeChild(const OcTreeNode *node, unsigned int childIdx) const
- Returns:
const ptr to child number childIdx of node
-
inline bool nodeChildExists(const OcTreeNode *node, unsigned int childIdx) const
return true if the child at childIdx exists
-
inline bool nodeHasChildren(const OcTreeNode *node) const
return true if node has at least one child
-
inline virtual OBJECT_TYPE getObjectType() const
return object type, it is an octree
Protected Attributes
-
shared_ptr<const octomap::OcTree> tree
-
CoalScalar default_occupancy
-
CoalScalar occupancy_threshold
-
CoalScalar free_threshold
-
typedef octomap::OcTreeNode OcTreeNode