Octree is one type of collision geometry which can encode uncertainty information in the sensor data. More...
#include <octree.h>

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 | |
| OcTreeNode * | getRoot () 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 |
Octree is one type of collision geometry which can encode uncertainty information in the sensor data.
| typedef octomap::OcTreeNode fcl::OcTree::OcTreeNode |
| fcl::OcTree::OcTree | ( | FCL_REAL | resolution | ) | [inline] |
| fcl::OcTree::OcTree | ( | const boost::shared_ptr< const octomap::OcTree > & | tree_ | ) | [inline] |
| void fcl::OcTree::computeLocalAABB | ( | ) | [inline, virtual] |
compute the AABB for the octree in its local coordinate system
Implements fcl::CollisionGeometry.
| FCL_REAL fcl::OcTree::getDefaultOccupancy | ( | ) | const [inline] |
| FCL_REAL fcl::OcTree::getFreeThres | ( | ) | const [inline] |
| NODE_TYPE fcl::OcTree::getNodeType | ( | ) | const [inline, virtual] |
return node type, it is an octree
Reimplemented from fcl::CollisionGeometry.
| OBJECT_TYPE fcl::OcTree::getObjectType | ( | ) | const [inline, virtual] |
return object type, it is an octree
Reimplemented from fcl::CollisionGeometry.
| FCL_REAL fcl::OcTree::getOccupancyThres | ( | ) | const [inline] |
| OcTreeNode* fcl::OcTree::getRoot | ( | ) | const [inline] |
| AABB fcl::OcTree::getRootBV | ( | ) | const [inline] |
| bool fcl::OcTree::isNodeFree | ( | const OcTreeNode * | node | ) | const [inline] |
| bool fcl::OcTree::isNodeOccupied | ( | const OcTreeNode * | node | ) | const [inline] |
| bool fcl::OcTree::isNodeUncertain | ( | const OcTreeNode * | node | ) | const [inline] |
| 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] |
FCL_REAL fcl::OcTree::default_occupancy [private] |
FCL_REAL fcl::OcTree::free_threshold [private] |
FCL_REAL fcl::OcTree::occupancy_threshold [private] |
boost::shared_ptr<const octomap::OcTree> fcl::OcTree::tree [private] |