hpp-fcl 2.4.5
HPP fork of FCL -- The Flexible Collision Library
Loading...
Searching...
No Matches
hpp::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 hpp::fcl::OcTree:
Collaboration diagram for hpp::fcl::OcTree:

Public Types

typedef octomap::OcTreeNode OcTreeNode
 

Public Member Functions

 OcTree (FCL_REAL resolution)
 construct octree with a given resolution
 
 OcTree (const shared_ptr< const octomap::OcTree > &tree_)
 construct octree from octomap
 
 OcTree (const OcTree &other)
 
OcTreeclone () const
 Clone *this into a new CollisionGeometry.
 
void exportAsObjFile (const std::string &filename) const
 
void computeLocalAABB ()
 compute the AABB for the octree in its local coordinate system
 
AABB getRootBV () const
 get the bounding volume for the root
 
unsigned int getTreeDepth () const
 Returns the depth of octree.
 
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. However, we only keep the occupied boxes (i.e., the boxes whose occupied probability is higher enough).
 
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 free, 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
 
- Public Member Functions inherited from hpp::fcl::CollisionGeometry
 CollisionGeometry ()
 
 CollisionGeometry (const CollisionGeometry &other)=default
 Copy constructor.
 
virtual ~CollisionGeometry ()
 
bool operator== (const CollisionGeometry &other) const
 Equality operator.
 
bool operator!= (const CollisionGeometry &other) const
 Difference operator.
 
void * getUserData () const
 get user data in geometry
 
void setUserData (void *data)
 set user data in geometry
 
bool isOccupied () const
 whether the object is completely occupied
 
bool isFree () const
 whether the object is completely free
 
bool isUncertain () const
 whether the object has some uncertainty
 
virtual Vec3f computeCOM () const
 compute center of mass
 
virtual Matrix3f computeMomentofInertia () const
 compute the inertia matrix, related to the origin
 
virtual FCL_REAL computeVolume () const
 compute the volume
 
virtual Matrix3f computeMomentofInertiaRelatedToCOM () const
 compute the inertia matrix, related to the com
 

Additional Inherited Members

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

Detailed Description

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

Member Typedef Documentation

◆ OcTreeNode

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

Constructor & Destructor Documentation

◆ OcTree() [1/3]

hpp::fcl::OcTree::OcTree ( FCL_REAL resolution)
inlineexplicit

construct octree with a given resolution

◆ OcTree() [2/3]

hpp::fcl::OcTree::OcTree ( const shared_ptr< const octomap::OcTree > & tree_)
inlineexplicit

construct octree from octomap

◆ OcTree() [3/3]

hpp::fcl::OcTree::OcTree ( const OcTree & other)
inline

Member Function Documentation

◆ clone()

OcTree * hpp::fcl::OcTree::clone ( ) const
inlinevirtual

Clone *this into a new CollisionGeometry.

Implements hpp::fcl::CollisionGeometry.

◆ computeLocalAABB()

void hpp::fcl::OcTree::computeLocalAABB ( )
inlinevirtual

compute the AABB for the octree in its local coordinate system

Implements hpp::fcl::CollisionGeometry.

◆ exportAsObjFile()

void hpp::fcl::OcTree::exportAsObjFile ( const std::string & filename) const

◆ getDefaultOccupancy()

FCL_REAL hpp::fcl::OcTree::getDefaultOccupancy ( ) const
inline

◆ getFreeThres()

FCL_REAL hpp::fcl::OcTree::getFreeThres ( ) const
inline

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

◆ getNodeChild() [1/2]

const OcTreeNode * hpp::fcl::OcTree::getNodeChild ( const OcTreeNode * node,
unsigned int childIdx ) const
inline
Returns
const ptr to child number childIdx of node

◆ getNodeChild() [2/2]

OcTreeNode * hpp::fcl::OcTree::getNodeChild ( OcTreeNode * node,
unsigned int childIdx )
inline
Returns
ptr to child number childIdx of node

◆ getNodeType()

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

return node type, it is an octree

Reimplemented from hpp::fcl::CollisionGeometry.

◆ getObjectType()

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

return object type, it is an octree

Reimplemented from hpp::fcl::CollisionGeometry.

◆ getOccupancyThres()

FCL_REAL hpp::fcl::OcTree::getOccupancyThres ( ) const
inline

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

◆ getRoot()

OcTreeNode * hpp::fcl::OcTree::getRoot ( ) const
inline

get the root node of the octree

◆ getRootBV()

AABB hpp::fcl::OcTree::getRootBV ( ) const
inline

get the bounding volume for the root

◆ getTreeDepth()

unsigned int hpp::fcl::OcTree::getTreeDepth ( ) const
inline

Returns the depth of octree.

◆ isNodeFree()

bool hpp::fcl::OcTree::isNodeFree ( const OcTreeNode * node) const
inline

whether one node is completely free

◆ isNodeOccupied()

bool hpp::fcl::OcTree::isNodeOccupied ( const OcTreeNode * node) const
inline

whether one node is completely occupied

◆ isNodeUncertain()

bool hpp::fcl::OcTree::isNodeUncertain ( const OcTreeNode * node) const
inline

whether one node is uncertain

◆ nodeChildExists()

bool hpp::fcl::OcTree::nodeChildExists ( const OcTreeNode * node,
unsigned int childIdx ) const
inline

return true if the child at childIdx exists

◆ nodeHasChildren()

bool hpp::fcl::OcTree::nodeHasChildren ( const OcTreeNode * node) const
inline

return true if node has at least one child

◆ setCellDefaultOccupancy()

void hpp::fcl::OcTree::setCellDefaultOccupancy ( FCL_REAL d)
inline

◆ setFreeThres()

void hpp::fcl::OcTree::setFreeThres ( FCL_REAL d)
inline

◆ setOccupancyThres()

void hpp::fcl::OcTree::setOccupancyThres ( FCL_REAL d)
inline

◆ toBoxes()

std::vector< boost::array< FCL_REAL, 6 > > hpp::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).


The documentation for this class was generated from the following file: