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 | 
| Public Member Functions | |
| OcTree * | clone () const | 
| Clone *this into a new Octree.  More... | |
| void | computeLocalAABB () | 
| compute the AABB for the octree in its local coordinate system  More... | |
| void | exportAsObjFile (const std::string &filename) const | 
| CoalScalar | getDefaultOccupancy () const | 
| CoalScalar | getFreeThres () const | 
| the threshold used to decide whether one node is free, this is NOT the octree free_threshold  More... | |
| const OcTreeNode * | getNodeChild (const OcTreeNode *node, unsigned int childIdx) const | 
| OcTreeNode * | getNodeChild (OcTreeNode *node, unsigned int childIdx) | 
| NODE_TYPE | getNodeType () const | 
| return node type, it is an octree  More... | |
| OBJECT_TYPE | getObjectType () const | 
| return object type, it is an octree  More... | |
| CoalScalar | getOccupancyThres () const | 
| the threshold used to decide whether one node is occupied, this is NOT the octree occupied_thresold  More... | |
| CoalScalar | getResolution () const | 
| Returns the resolution of the octree.  More... | |
| OcTreeNode * | getRoot () const | 
| get the root node of the octree  More... | |
| AABB | getRootBV () const | 
| get the bounding volume for the root  More... | |
| shared_ptr< const octomap::OcTree > | getTree () const | 
| Returns the tree associated to the underlying octomap OcTree.  More... | |
| unsigned int | getTreeDepth () const | 
| Returns the depth of the 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 (CoalScalar resolution) | |
| construct octree with a given resolution  More... | |
| OcTree (const OcTree &other) | |
| More... | |
| OcTree (const shared_ptr< const octomap::OcTree > &tree_) | |
| construct octree from octomap  More... | |
| void | setCellDefaultOccupancy (CoalScalar d) | 
| void | setFreeThres (CoalScalar d) | 
| void | setOccupancyThres (CoalScalar d) | 
| unsigned long | size () const | 
| Returns the size of the octree.  More... | |
| std::vector< Vec6s > | 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... | |
| std::vector< uint8_t > | tobytes () const | 
| Returns a byte description of *this.  More... | |
|  Public Member Functions inherited from coal::CollisionGeometry | |
| CollisionGeometry () | |
| CollisionGeometry (const CollisionGeometry &other)=default | |
| Copy constructor.  More... | |
| virtual Vec3s | computeCOM () const | 
| compute center of mass  More... | |
| virtual Matrix3s | computeMomentofInertia () const | 
| compute the inertia matrix, related to the origin  More... | |
| virtual Matrix3s | computeMomentofInertiaRelatedToCOM () const | 
| compute the inertia matrix, related to the com  More... | |
| virtual CoalScalar | 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 () | 
| Protected Attributes | |
| CoalScalar | default_occupancy | 
| CoalScalar | free_threshold | 
| CoalScalar | occupancy_threshold | 
| shared_ptr< const octomap::OcTree > | tree | 
| Private Member Functions | |
| virtual bool | isEqual (const CollisionGeometry &_other) const | 
| equal operator with another object of derived type.  More... | |
| Additional Inherited Members | |
|  Public Attributes inherited from coal::CollisionGeometry | |
| Vec3s | aabb_center | 
| AABB center in local coordinate.  More... | |
| AABB | aabb_local | 
| AABB in local coordinate, used for tight AABB when only translation transform.  More... | |
| CoalScalar | aabb_radius | 
| AABB radius.  More... | |
| CoalScalar | cost_density | 
| collision cost for unit volume  More... | |
| CoalScalar | threshold_free | 
| threshold for free (<= is free)  More... | |
| CoalScalar | threshold_occupied | 
| threshold for occupied ( >= is occupied)  More... | |
| void * | user_data | 
| pointer to user defined data specific to this object  More... | |
Octree is one type of collision geometry which can encode uncertainty information in the sensor data.
Definition at line 53 of file coal/octree.h.
| typedef octomap::OcTreeNode coal::OcTree::OcTreeNode | 
Definition at line 63 of file coal/octree.h.
| 
 | inlineexplicit | 
construct octree with a given resolution
Definition at line 66 of file coal/octree.h.
| 
 | inlineexplicit | 
construct octree from octomap
Definition at line 78 of file coal/octree.h.
| 
 | inline | 
| 
 | inlinevirtual | 
Clone *this into a new Octree.
Implements coal::CollisionGeometry.
Definition at line 97 of file coal/octree.h.
| 
 | inlinevirtual | 
compute the AABB for the octree in its local coordinate system
Implements coal::CollisionGeometry.
Definition at line 105 of file coal/octree.h.
| void coal::OcTree::exportAsObjFile | ( | const std::string & | filename | ) | const | 
Definition at line 108 of file src/octree.cpp.
| 
 | inline | 
Definition at line 231 of file coal/octree.h.
| 
 | inline | 
the threshold used to decide whether one node is free, this is NOT the octree free_threshold
Definition at line 229 of file coal/octree.h.
| 
 | inline | 
Definition at line 249 of file coal/octree.h.
| 
 | inline | 
Definition at line 240 of file coal/octree.h.
| 
 | inlinevirtual | 
return node type, it is an octree
Reimplemented from coal::CollisionGeometry.
Definition at line 280 of file coal/octree.h.
| 
 | inlinevirtual | 
return object type, it is an octree
Reimplemented from coal::CollisionGeometry.
Definition at line 277 of file coal/octree.h.
| 
 | inline | 
the threshold used to decide whether one node is occupied, this is NOT the octree occupied_thresold
Definition at line 225 of file coal/octree.h.
| 
 | inline | 
Returns the resolution of the octree.
Definition at line 153 of file coal/octree.h.
| 
 | inline | 
get the root node of the octree
Definition at line 156 of file coal/octree.h.
| 
 | inline | 
get the bounding volume for the root
Definition at line 139 of file coal/octree.h.
| 
 | inline | 
Returns the tree associated to the underlying octomap OcTree.
Definition at line 100 of file coal/octree.h.
| 
 | inline | 
Returns the depth of the octree.
Definition at line 147 of file coal/octree.h.
| 
 | inlineprivatevirtual | 
equal operator with another object of derived type.
Implements coal::CollisionGeometry.
Definition at line 283 of file coal/octree.h.
| 
 | inline | 
whether one node is completely free
Definition at line 165 of file coal/octree.h.
| 
 | inline | 
whether one node is completely occupied
Definition at line 159 of file coal/octree.h.
| 
 | inline | 
whether one node is uncertain
Definition at line 171 of file coal/octree.h.
| 
 | inline | 
return true if the child at childIdx exists
Definition at line 259 of file coal/octree.h.
| 
 | inline | 
return true if node has at least one child
Definition at line 268 of file coal/octree.h.
| 
 | inline | 
Definition at line 233 of file coal/octree.h.
| 
 | inline | 
Definition at line 237 of file coal/octree.h.
| 
 | inline | 
Definition at line 235 of file coal/octree.h.
| 
 | inline | 
Returns the size of the octree.
Definition at line 150 of file coal/octree.h.
| 
 | 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 178 of file coal/octree.h.
| 
 | inline | 
Returns a byte description of *this.
Definition at line 203 of file coal/octree.h.
| 
 | protected | 
Definition at line 57 of file coal/octree.h.
| 
 | protected | 
Definition at line 60 of file coal/octree.h.
| 
 | protected | 
Definition at line 59 of file coal/octree.h.
| 
 | protected | 
Definition at line 55 of file coal/octree.h.