All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Macros Pages
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:
Collaboration diagram for fcl::OcTree:

Public Types

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

Public Member Functions

 OcTree (FCL_REAL resolution)
 construct octree with a given resolution More...
 
 OcTree (const boost::shared_ptr< const octomap::OcTree > &tree_)
 construct octree from octomap More...
 
void computeLocalAABB ()
 compute the AABB for the octree in its local coordinate system More...
 
AABB getRootBV () const
 get the bounding volume for the root More...
 
OcTreeNodegetRoot () const
 get the root node of the octree More...
 
bool isNodeOccupied (const OcTreeNode *node) const
 whether one node is completely occupied More...
 
bool isNodeFree (const OcTreeNode *node) const
 whether one node is completely free More...
 
bool isNodeUncertain (const OcTreeNode *node) const
 whether one node is uncertain More...
 
std::vector< boost::array
< FCL_REAL, 6 > > 
toBoxes () const
 transform the octree into a bunch of boxes; uncertainty information is kept in the boxes. More...
 
FCL_REAL getOccupancyThres () const
 the threshold used to decide whether one node is occupied, this is NOT the octree occupied_thresold More...
 
FCL_REAL getFreeThres () const
 the threshold used to decide whether one node is occupied, this is NOT the octree free_threshold More...
 
FCL_REAL getDefaultOccupancy () const
 
void setCellDefaultOccupancy (FCL_REAL d)
 
void setOccupancyThres (FCL_REAL d)
 
void setFreeThres (FCL_REAL d)
 
OBJECT_TYPE getObjectType () const
 return object type, it is an octree More...
 
NODE_TYPE getNodeType () const
 return node type, it is an octree More...
 
- Public Member Functions inherited from fcl::CollisionGeometry
 CollisionGeometry ()
 
virtual ~CollisionGeometry ()
 
void * getUserData () const
 get user data in geometry More...
 
void setUserData (void *data)
 set user data in geometry More...
 
bool isOccupied () const
 whether the object is completely occupied More...
 
bool isFree () const
 whether the object is completely free More...
 
bool isUncertain () const
 whether the object has some uncertainty More...
 
virtual Vec3f computeCOM () const
 compute center of mass More...
 
virtual Matrix3f computeMomentofInertia () const
 compute the inertia matrix, related to the origin More...
 
virtual FCL_REAL computeVolume () const
 compute the volume More...
 
virtual Matrix3f computeMomentofInertiaRelatedToCOM () const
 compute the inertia matrix, related to the com More...
 

Additional Inherited Members

- Public Attributes inherited from fcl::CollisionGeometry
Vec3f aabb_center
 AABB center in local coordinate. More...
 
FCL_REAL aabb_radius
 AABB radius. More...
 
AABB aabb_local
 AABB in local coordinate, used for tight AABB when only translation transform. More...
 
void * user_data
 pointer to user defined data specific to this object More...
 
FCL_REAL cost_density
 collision cost for unit volume More...
 
FCL_REAL threshold_occupied
 threshold for occupied ( >= is occupied) More...
 
FCL_REAL threshold_free
 threshold for free (<= is free) More...
 

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

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

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 ( )
inlinevirtual
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

NODE_TYPE fcl::OcTree::getNodeType ( ) const
inlinevirtual

return node type, it is an octree

Reimplemented from fcl::CollisionGeometry.

References fcl::GEOM_OCTREE.

OBJECT_TYPE fcl::OcTree::getObjectType ( ) const
inlinevirtual

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

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

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