Public Types | Public Member Functions
fcl::OcTree Class Reference

Octree is one type of collision geometry which can encode uncertainty information in the sensor data. More...

#include <hpp/fcl/octree.h>

Inheritance diagram for fcl::OcTree:
[legend]
Collaboration diagram for fcl::OcTree:
[legend]

List of all members.

Public Types

typedef octomap::OcTreeNode OcTreeNode

Public Member Functions

 OcTree (FCL_REAL resolution)
 construct octree with a given resolution
 OcTree (const boost::shared_ptr< const octomap::OcTree > &tree_)
 construct octree from octomap
void computeLocalAABB ()
 compute the AABB for the octree in its local coordinate system
AABB getRootBV () const
 get the bounding volume for the root
OcTreeNodegetRoot () const
 get the root node of the octree
bool isNodeOccupied (const OcTreeNode *node) const
 whether one node is completely occupied
bool isNodeFree (const OcTreeNode *node) const
 whether one node is completely free
bool isNodeUncertain (const OcTreeNode *node) const
 whether one node is uncertain
std::vector< boost::array
< FCL_REAL, 6 > > 
toBoxes () const
 transform the octree into a bunch of boxes; uncertainty information is kept in the boxes.
FCL_REAL getOccupancyThres () const
 the threshold used to decide whether one node is occupied, this is NOT the octree occupied_thresold
FCL_REAL getFreeThres () const
 the threshold used to decide whether one node is occupied, this is NOT the octree free_threshold
FCL_REAL getDefaultOccupancy () const
void setCellDefaultOccupancy (FCL_REAL d)
void setOccupancyThres (FCL_REAL d)
void setFreeThres (FCL_REAL d)
OcTreeNodegetNodeChild (OcTreeNode *node, unsigned int childIdx)
const OcTreeNodegetNodeChild (const OcTreeNode *node, unsigned int childIdx) const
bool nodeChildExists (const OcTreeNode *node, unsigned int childIdx) const
 return true if the child at childIdx exists
bool nodeHasChildren (const OcTreeNode *node) const
 return true if node has at least one child
OBJECT_TYPE getObjectType () const
 return object type, it is an octree
NODE_TYPE getNodeType () const
 return node type, it is an octree

Detailed Description

Octree is one type of collision geometry which can encode uncertainty information in the sensor data.


Member Typedef Documentation

typedef octomap::OcTreeNode fcl::OcTree::OcTreeNode

Constructor & Destructor Documentation

fcl::OcTree::OcTree ( FCL_REAL  resolution) [inline]

construct octree with a given resolution

fcl::OcTree::OcTree ( const boost::shared_ptr< const octomap::OcTree > &  tree_) [inline]

construct octree from octomap


Member Function Documentation

void fcl::OcTree::computeLocalAABB ( ) [inline, virtual]
FCL_REAL fcl::OcTree::getDefaultOccupancy ( ) const [inline]
FCL_REAL fcl::OcTree::getFreeThres ( ) const [inline]

the threshold used to decide whether one node is occupied, this is NOT the octree free_threshold

OcTreeNode* fcl::OcTree::getNodeChild ( OcTreeNode node,
unsigned int  childIdx 
) [inline]
Returns:
ptr to child number childIdx of node
const OcTreeNode* fcl::OcTree::getNodeChild ( const OcTreeNode node,
unsigned int  childIdx 
) const [inline]
Returns:
const ptr to child number childIdx of node
NODE_TYPE fcl::OcTree::getNodeType ( ) const [inline, virtual]

return node type, it is an octree

Reimplemented from fcl::CollisionGeometry.

References fcl::GEOM_OCTREE.

OBJECT_TYPE fcl::OcTree::getObjectType ( ) const [inline, virtual]

return object type, it is an octree

Reimplemented from fcl::CollisionGeometry.

References fcl::OT_OCTREE.

FCL_REAL fcl::OcTree::getOccupancyThres ( ) const [inline]

the threshold used to decide whether one node is occupied, this is NOT the octree occupied_thresold

OcTreeNode* fcl::OcTree::getRoot ( ) const [inline]
AABB fcl::OcTree::getRootBV ( ) const [inline]
bool fcl::OcTree::isNodeFree ( const OcTreeNode node) const [inline]

whether one node is completely free

Referenced by isNodeUncertain().

bool fcl::OcTree::isNodeOccupied ( const OcTreeNode node) const [inline]

whether one node is completely occupied

Referenced by isNodeUncertain(), and toBoxes().

bool fcl::OcTree::isNodeUncertain ( const OcTreeNode node) const [inline]

whether one node is uncertain

References isNodeFree(), and isNodeOccupied().

bool fcl::OcTree::nodeChildExists ( const OcTreeNode node,
unsigned int  childIdx 
) const [inline]

return true if the child at childIdx exists

bool fcl::OcTree::nodeHasChildren ( const OcTreeNode node) const [inline]

return true if node has at least one child

void fcl::OcTree::setCellDefaultOccupancy ( FCL_REAL  d) [inline]
void fcl::OcTree::setFreeThres ( FCL_REAL  d) [inline]
void fcl::OcTree::setOccupancyThres ( FCL_REAL  d) [inline]
std::vector<boost::array<FCL_REAL, 6> > fcl::OcTree::toBoxes ( ) const [inline]

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).

References isNodeOccupied().

 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Defines