All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Defines
Public Types | Public Member Functions | Private Attributes
fcl::OcTree Class Reference

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

#include <octree.h>

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

List of all members.

Public Types

typedef octomap::OcTreeNode OcTreeNode
 OcTreeNode must implement the following interfaces: 1) childExists(i) 2) getChild(i) 3) hasChildren()

Public Member Functions

void computeLocalAABB ()
 compute the AABB for the octree in its local coordinate system
FCL_REAL getDefaultOccupancy () const
FCL_REAL getFreeThres () const
 the threshold used to decide whether one node is occupied, this is NOT the octree free_threshold
NODE_TYPE getNodeType () const
 return node type, it is an octree
OBJECT_TYPE getObjectType () const
 return object type, it is an octree
FCL_REAL getOccupancyThres () const
 the threshold used to decide whether one node is occupied, this is NOT the octree occupied_thresold
OcTreeNodegetRoot () const
 get the root node of the octree
AABB getRootBV () const
 get the bounding volume for the root
bool isNodeFree (const OcTreeNode *node) const
 whether one node is completely free
bool isNodeOccupied (const OcTreeNode *node) const
 whether one node is completely occupied
bool isNodeUncertain (const OcTreeNode *node) const
 whether one node is uncertain
 OcTree (FCL_REAL resolution)
 construct octree with a given resolution
 OcTree (const boost::shared_ptr< const octomap::OcTree > &tree_)
 construct octree from octomap
void setCellDefaultOccupancy (FCL_REAL d)
void setFreeThres (FCL_REAL d)
void setOccupancyThres (FCL_REAL d)
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).

Private Attributes

FCL_REAL default_occupancy
FCL_REAL free_threshold
FCL_REAL occupancy_threshold
boost::shared_ptr< const
octomap::OcTree > 
tree

Detailed Description

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

Definition at line 53 of file octree.h.


Member Typedef Documentation

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

OcTreeNode must implement the following interfaces: 1) childExists(i) 2) getChild(i) 3) hasChildren()

Definition at line 69 of file octree.h.


Constructor & Destructor Documentation

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

construct octree with a given resolution

Definition at line 72 of file octree.h.

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

construct octree from octomap

Definition at line 82 of file octree.h.


Member Function Documentation

void fcl::OcTree::computeLocalAABB ( ) [inline, virtual]

compute the AABB for the octree in its local coordinate system

Implements fcl::CollisionGeometry.

Definition at line 92 of file octree.h.

Definition at line 173 of file octree.h.

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

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

Definition at line 168 of file octree.h.

NODE_TYPE fcl::OcTree::getNodeType ( ) const [inline, virtual]

return node type, it is an octree

Reimplemented from fcl::CollisionGeometry.

Definition at line 197 of file octree.h.

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

return object type, it is an octree

Reimplemented from fcl::CollisionGeometry.

Definition at line 194 of file octree.h.

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

Definition at line 162 of file octree.h.

OcTreeNode* fcl::OcTree::getRoot ( ) const [inline]

get the root node of the octree

Definition at line 109 of file octree.h.

AABB fcl::OcTree::getRootBV ( ) const [inline]

get the bounding volume for the root

Definition at line 100 of file octree.h.

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

whether one node is completely free

Definition at line 122 of file octree.h.

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

whether one node is completely occupied

Definition at line 115 of file octree.h.

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

whether one node is uncertain

Definition at line 129 of file octree.h.

Definition at line 178 of file octree.h.

void fcl::OcTree::setFreeThres ( FCL_REAL  d) [inline]

Definition at line 188 of file octree.h.

Definition at line 183 of file octree.h.

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

Definition at line 136 of file octree.h.


Member Data Documentation

Definition at line 58 of file octree.h.

Definition at line 61 of file octree.h.

Definition at line 60 of file octree.h.

boost::shared_ptr<const octomap::OcTree> fcl::OcTree::tree [private]

Definition at line 56 of file octree.h.


The documentation for this class was generated from the following file:
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Defines


fcl
Author(s): Jia Pan
autogenerated on Tue Jan 15 2013 16:05:31