Class OcTree
Defined in File octree.h
Inheritance Relationships
Base Type
public hpp::fcl::CollisionGeometry
(Class CollisionGeometry)
Class Documentation
-
class OcTree : public hpp::fcl::CollisionGeometry
Octree is one type of collision geometry which can encode uncertainty information in the sensor data.
Public Types
-
typedef octomap::OcTreeNode OcTreeNode
Public Functions
construct octree from octomap
-
inline virtual OcTree *clone() const
Clone *this into a new CollisionGeometry.
-
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 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<boost::array<FCL_REAL, 6>> 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 FCL_REAL getOccupancyThres() const
the threshold used to decide whether one node is occupied, this is NOT the octree occupied_thresold
-
inline FCL_REAL getFreeThres() const
the threshold used to decide whether one node is free, this is NOT the octree free_threshold
-
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
-
typedef octomap::OcTreeNode OcTreeNode