Public Types | Public Member Functions | Private Member Functions | Private Attributes | List of all members
hpp::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 hpp::fcl::OcTree:
Inheritance graph
[legend]

Public Types

typedef octomap::OcTreeNode OcTreeNode
 

Public Member Functions

OcTreeclone () const
 Clone *this into a new CollisionGeometry. More...
 
void computeLocalAABB ()
 compute the AABB for the octree in its local coordinate system More...
 
void exportAsObjFile (const std::string &filename) const
 
FCL_REAL getDefaultOccupancy () const
 
FCL_REAL getFreeThres () const
 the threshold used to decide whether one node is free, this is NOT the octree free_threshold More...
 
OcTreeNodegetNodeChild (OcTreeNode *node, unsigned int childIdx)
 
const OcTreeNodegetNodeChild (const OcTreeNode *node, unsigned int childIdx) const
 
NODE_TYPE getNodeType () const
 return node type, it is an octree More...
 
OBJECT_TYPE getObjectType () const
 return object type, it is an octree More...
 
FCL_REAL getOccupancyThres () const
 the threshold used to decide whether one node is occupied, this is NOT the octree occupied_thresold More...
 
OcTreeNodegetRoot () const
 get the root node of the octree More...
 
AABB getRootBV () const
 get the bounding volume for the root More...
 
unsigned int getTreeDepth () const
 Returns the depth of octree. More...
 
bool isNodeFree (const OcTreeNode *node) const
 whether one node is completely free More...
 
bool isNodeOccupied (const OcTreeNode *node) const
 whether one node is completely occupied More...
 
bool isNodeUncertain (const OcTreeNode *node) const
 whether one node is uncertain More...
 
bool nodeChildExists (const OcTreeNode *node, unsigned int childIdx) const
 return true if the child at childIdx exists More...
 
bool nodeHasChildren (const OcTreeNode *node) const
 return true if node has at least one child More...
 
 OcTree (FCL_REAL resolution)
 construct octree with a given resolution More...
 
 OcTree (const shared_ptr< const octomap::OcTree > &tree_)
 construct octree from octomap More...
 
 OcTree (const OcTree &other)
 
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). More...
 
- Public Member Functions inherited from hpp::fcl::CollisionGeometry
 CollisionGeometry ()
 
 CollisionGeometry (const CollisionGeometry &other)=default
 Copy constructor. More...
 
virtual Vec3f computeCOM () const
 compute center of mass More...
 
virtual Matrix3f computeMomentofInertia () const
 compute the inertia matrix, related to the origin More...
 
virtual Matrix3f computeMomentofInertiaRelatedToCOM () const
 compute the inertia matrix, related to the com More...
 
virtual FCL_REAL computeVolume () const
 compute the volume More...
 
void * getUserData () const
 get user data in geometry More...
 
bool isFree () const
 whether the object is completely free More...
 
bool isOccupied () const
 whether the object is completely occupied More...
 
bool isUncertain () const
 whether the object has some uncertainty More...
 
bool operator!= (const CollisionGeometry &other) const
 Difference operator. More...
 
bool operator== (const CollisionGeometry &other) const
 Equality operator. More...
 
void setUserData (void *data)
 set user data in geometry More...
 
virtual ~CollisionGeometry ()
 

Private Member Functions

virtual bool isEqual (const CollisionGeometry &_other) const
 equal operator with another object of derived type. More...
 

Private Attributes

FCL_REAL default_occupancy
 
FCL_REAL free_threshold
 
FCL_REAL occupancy_threshold
 
shared_ptr< const octomap::OcTreetree
 

Additional Inherited Members

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

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

◆ OcTreeNode

Definition at line 63 of file octree.h.

Constructor & Destructor Documentation

◆ OcTree() [1/3]

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

construct octree with a given resolution

Definition at line 66 of file octree.h.

◆ OcTree() [2/3]

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

construct octree from octomap

Definition at line 78 of file octree.h.

◆ OcTree() [3/3]

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

Definition at line 88 of file octree.h.

Member Function Documentation

◆ clone()

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

Clone *this into a new CollisionGeometry.

Implements hpp::fcl::CollisionGeometry.

Definition at line 95 of file octree.h.

◆ computeLocalAABB()

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

compute the AABB for the octree in its local coordinate system

Implements hpp::fcl::CollisionGeometry.

Definition at line 100 of file octree.h.

◆ exportAsObjFile()

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

Definition at line 107 of file src/octree.cpp.

◆ getDefaultOccupancy()

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

Definition at line 171 of file octree.h.

◆ 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

Definition at line 169 of file octree.h.

◆ getNodeChild() [1/2]

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

Definition at line 180 of file octree.h.

◆ getNodeChild() [2/2]

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

Definition at line 189 of file octree.h.

◆ getNodeType()

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

return node type, it is an octree

Reimplemented from hpp::fcl::CollisionGeometry.

Definition at line 220 of file octree.h.

◆ getObjectType()

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

return object type, it is an octree

Reimplemented from hpp::fcl::CollisionGeometry.

Definition at line 217 of file octree.h.

◆ 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

Definition at line 165 of file octree.h.

◆ getRoot()

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

get the root node of the octree

Definition at line 118 of file octree.h.

◆ getRootBV()

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

get the bounding volume for the root

Definition at line 107 of file octree.h.

◆ getTreeDepth()

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

Returns the depth of octree.

Definition at line 115 of file octree.h.

◆ isEqual()

virtual bool hpp::fcl::OcTree::isEqual ( const CollisionGeometry other) const
inlineprivatevirtual

equal operator with another object of derived type.

Implements hpp::fcl::CollisionGeometry.

Definition at line 223 of file octree.h.

◆ isNodeFree()

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

whether one node is completely free

Definition at line 127 of file octree.h.

◆ isNodeOccupied()

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

whether one node is completely occupied

Definition at line 121 of file octree.h.

◆ isNodeUncertain()

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

whether one node is uncertain

Definition at line 133 of file octree.h.

◆ nodeChildExists()

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

return true if the child at childIdx exists

Definition at line 199 of file octree.h.

◆ nodeHasChildren()

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

return true if node has at least one child

Definition at line 208 of file octree.h.

◆ setCellDefaultOccupancy()

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

Definition at line 173 of file octree.h.

◆ setFreeThres()

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

Definition at line 177 of file octree.h.

◆ setOccupancyThres()

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

Definition at line 175 of file octree.h.

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

Definition at line 140 of file octree.h.

Member Data Documentation

◆ default_occupancy

FCL_REAL hpp::fcl::OcTree::default_occupancy
private

Definition at line 57 of file octree.h.

◆ free_threshold

FCL_REAL hpp::fcl::OcTree::free_threshold
private

Definition at line 60 of file octree.h.

◆ occupancy_threshold

FCL_REAL hpp::fcl::OcTree::occupancy_threshold
private

Definition at line 59 of file octree.h.

◆ tree

shared_ptr<const octomap::OcTree> hpp::fcl::OcTree::tree
private

Definition at line 55 of file octree.h.


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


hpp-fcl
Author(s):
autogenerated on Fri Jun 2 2023 02:39:03