|  | 
| ColorOcTreeNode * | averageNodeColor (const OcTreeKey &key, uint8_t r, uint8_t g, uint8_t b) | 
|  | 
| ColorOcTreeNode * | averageNodeColor (float x, float y, float z, uint8_t r, uint8_t g, uint8_t b) | 
|  | 
|  | ColorOcTree (double resolution) | 
|  | Default constructor, sets resolution of leafs.  More... 
 | 
|  | 
| ColorOcTree * | create () const | 
|  | 
| std::string | getTreeType () const | 
|  | returns actual class name as string for identification  More... 
 | 
|  | 
| ColorOcTreeNode * | integrateNodeColor (const OcTreeKey &key, uint8_t r, uint8_t g, uint8_t b) | 
|  | 
| ColorOcTreeNode * | integrateNodeColor (float x, float y, float z, uint8_t r, uint8_t g, uint8_t b) | 
|  | 
| virtual bool | isNodeCollapsible (const ColorOcTreeNode *node) const | 
|  | 
| virtual bool | pruneNode (ColorOcTreeNode *node) | 
|  | 
| ColorOcTreeNode * | setNodeColor (const OcTreeKey &key, uint8_t r, uint8_t g, uint8_t b) | 
|  | 
| ColorOcTreeNode * | setNodeColor (float x, float y, float z, uint8_t r, uint8_t g, uint8_t b) | 
|  | 
| void | updateInnerOccupancy () | 
|  | 
| void | writeColorHistogram (std::string filename) | 
|  | 
| bool | bbxSet () const | 
|  | 
| virtual bool | castRay (const point3d &origin, const point3d &direction, point3d &end, bool ignoreUnknownCells=false, double maxRange=-1.0) const | 
|  | 
| KeyBoolMap::const_iterator | changedKeysBegin () const | 
|  | 
| KeyBoolMap::const_iterator | changedKeysEnd () const | 
|  | Iterator to traverse all keys of changed nodes.  More... 
 | 
|  | 
| void | computeDiscreteUpdate (const Pointcloud &scan, const octomap::point3d &origin, KeySet &free_cells, KeySet &occupied_cells, double maxrange) | 
|  | 
| void | computeUpdate (const Pointcloud &scan, const octomap::point3d &origin, KeySet &free_cells, KeySet &occupied_cells, double maxrange) | 
|  | 
| void | enableChangeDetection (bool enable) | 
|  | track or ignore changes while inserting scans (default: ignore)  More... 
 | 
|  | 
| point3d | getBBXBounds () const | 
|  | 
| point3d | getBBXCenter () const | 
|  | 
| point3d | getBBXMax () const | 
|  | 
| point3d | getBBXMin () const | 
|  | 
| bool | getNormals (const point3d &point, std::vector< point3d > &normals, bool unknownStatus=true) const | 
|  | 
| virtual bool | getRayIntersection (const point3d &origin, const point3d &direction, const point3d ¢er, point3d &intersection, double delta=0.0) const | 
|  | 
| bool | inBBX (const OcTreeKey &key) const | 
|  | 
| bool | inBBX (const point3d &p) const | 
|  | 
| virtual void | insertPointCloud (const Pointcloud &scan, const octomap::point3d &sensor_origin, double maxrange=-1., bool lazy_eval=false, bool discretize=false) | 
|  | 
| virtual void | insertPointCloud (const Pointcloud &scan, const point3d &sensor_origin, const pose6d &frame_origin, double maxrange=-1., bool lazy_eval=false, bool discretize=false) | 
|  | 
| virtual void | insertPointCloud (const ScanNode &scan, double maxrange=-1., bool lazy_eval=false, bool discretize=false) | 
|  | 
| virtual void | insertPointCloudRays (const Pointcloud &scan, const point3d &sensor_origin, double maxrange=-1., bool lazy_eval=false) | 
|  | 
| virtual bool | insertRay (const point3d &origin, const point3d &end, double maxrange=-1.0, bool lazy_eval=false) | 
|  | 
| virtual void | integrateHit (ColorOcTreeNode *occupancyNode) const | 
|  | integrate a "hit" measurement according to the tree's sensor model  More... 
 | 
|  | 
| virtual void | integrateMiss (ColorOcTreeNode *occupancyNode) const | 
|  | integrate a "miss" measurement according to the tree's sensor model  More... 
 | 
|  | 
| bool | isChangeDetectionEnabled () const | 
|  | 
| virtual void | nodeToMaxLikelihood (ColorOcTreeNode &occupancyNode) const | 
|  | converts the node to the maximum likelihood value according to the tree's parameter for "occupancy"  More... 
 | 
|  | 
| virtual void | nodeToMaxLikelihood (ColorOcTreeNode *occupancyNode) const | 
|  | converts the node to the maximum likelihood value according to the tree's parameter for "occupancy"  More... 
 | 
|  | 
| size_t | numChangesDetected () const | 
|  | Number of changes since last reset.  More... 
 | 
|  | 
|  | OccupancyOcTreeBase (const OccupancyOcTreeBase< ColorOcTreeNode > &rhs) | 
|  | Copy constructor.  More... 
 | 
|  | 
|  | OccupancyOcTreeBase (double resolution) | 
|  | Default constructor, sets resolution of leafs.  More... 
 | 
|  | 
| std::istream & | readBinaryData (std::istream &s) | 
|  | 
| std::istream & | readBinaryNode (std::istream &s, ColorOcTreeNode *node) | 
|  | 
| void | resetChangeDetection () | 
|  | Reset the set of changed keys. Call this after you obtained all changed nodes.  More... 
 | 
|  | 
| void | setBBXMax (const point3d &max) | 
|  | sets the maximum for a query bounding box to use  More... 
 | 
|  | 
| void | setBBXMin (const point3d &min) | 
|  | sets the minimum for a query bounding box to use  More... 
 | 
|  | 
| virtual ColorOcTreeNode * | setNodeValue (const OcTreeKey &key, float log_odds_value, bool lazy_eval=false) | 
|  | 
| virtual ColorOcTreeNode * | setNodeValue (const point3d &value, float log_odds_value, bool lazy_eval=false) | 
|  | 
| virtual ColorOcTreeNode * | setNodeValue (double x, double y, double z, float log_odds_value, bool lazy_eval=false) | 
|  | 
| virtual void | toMaxLikelihood () | 
|  | 
| void | updateInnerOccupancy () | 
|  | 
| virtual ColorOcTreeNode * | updateNode (const OcTreeKey &key, bool occupied, bool lazy_eval=false) | 
|  | 
| virtual ColorOcTreeNode * | updateNode (const OcTreeKey &key, float log_odds_update, bool lazy_eval=false) | 
|  | 
| virtual ColorOcTreeNode * | updateNode (const point3d &value, bool occupied, bool lazy_eval=false) | 
|  | 
| virtual ColorOcTreeNode * | updateNode (const point3d &value, float log_odds_update, bool lazy_eval=false) | 
|  | 
| virtual ColorOcTreeNode * | updateNode (double x, double y, double z, bool occupied, bool lazy_eval=false) | 
|  | 
| virtual ColorOcTreeNode * | updateNode (double x, double y, double z, float log_odds_update, bool lazy_eval=false) | 
|  | 
| virtual void | updateNodeLogOdds (ColorOcTreeNode *occupancyNode, const float &update) const | 
|  | update logodds value of node by adding to the current value.  More... 
 | 
|  | 
| void | useBBXLimit (bool enable) | 
|  | use or ignore BBX limit (default: ignore)  More... 
 | 
|  | 
| std::ostream & | writeBinaryData (std::ostream &s) const | 
|  | 
| std::ostream & | writeBinaryNode (std::ostream &s, const ColorOcTreeNode *node) const | 
|  | 
| virtual | ~OccupancyOcTreeBase () | 
|  | 
| OcTreeKey | adjustKeyAtDepth (const OcTreeKey &key, unsigned int depth) const | 
|  | 
| key_type | adjustKeyAtDepth (key_type key, unsigned int depth) const | 
|  | 
| iterator | begin (unsigned char maxDepth=0) const | 
|  | 
| leaf_iterator | begin_leafs (unsigned char maxDepth=0) const | 
|  | 
| leaf_bbx_iterator | begin_leafs_bbx (const OcTreeKey &min, const OcTreeKey &max, unsigned char maxDepth=0) const | 
|  | 
| leaf_bbx_iterator | begin_leafs_bbx (const point3d &min, const point3d &max, unsigned char maxDepth=0) const | 
|  | 
| tree_iterator | begin_tree (unsigned char maxDepth=0) const | 
|  | 
| size_t | calcNumNodes () const | 
|  | Traverses the tree to calculate the total number of nodes.  More... 
 | 
|  | 
| void | clear () | 
|  | Deletes the complete tree structure.  More... 
 | 
|  | 
| void | clearKeyRays () | 
|  | 
| bool | computeRay (const point3d &origin, const point3d &end, std::vector< point3d > &ray) | 
|  | 
| bool | computeRayKeys (const point3d &origin, const point3d &end, KeyRay &ray) const | 
|  | 
| OcTreeKey | coordToKey (const point3d &coord) const | 
|  | Converts from a 3D coordinate into a 3D addressing key.  More... 
 | 
|  | 
| OcTreeKey | coordToKey (const point3d &coord, unsigned depth) const | 
|  | Converts from a 3D coordinate into a 3D addressing key at a given depth.  More... 
 | 
|  | 
| key_type | coordToKey (double coordinate) const | 
|  | Converts from a single coordinate into a discrete key.  More... 
 | 
|  | 
| key_type | coordToKey (double coordinate, unsigned depth) const | 
|  | Converts from a single coordinate into a discrete key at a given depth.  More... 
 | 
|  | 
| OcTreeKey | coordToKey (double x, double y, double z) const | 
|  | Converts from a 3D coordinate into a 3D addressing key.  More... 
 | 
|  | 
| OcTreeKey | coordToKey (double x, double y, double z, unsigned depth) const | 
|  | Converts from a 3D coordinate into a 3D addressing key at a given depth.  More... 
 | 
|  | 
| bool | coordToKeyChecked (const point3d &coord, OcTreeKey &key) const | 
|  | 
| bool | coordToKeyChecked (const point3d &coord, unsigned depth, OcTreeKey &key) const | 
|  | 
| bool | coordToKeyChecked (double coordinate, key_type &key) const | 
|  | 
| bool | coordToKeyChecked (double coordinate, unsigned depth, key_type &key) const | 
|  | 
| bool | coordToKeyChecked (double x, double y, double z, OcTreeKey &key) const | 
|  | 
| bool | coordToKeyChecked (double x, double y, double z, unsigned depth, OcTreeKey &key) const | 
|  | 
| ColorOcTreeNode * | createNodeChild (ColorOcTreeNode *node, unsigned int childIdx) | 
|  | Creates (allocates) the i-th child of the node.  More... 
 | 
|  | 
| bool | deleteNode (const OcTreeKey &key, unsigned int depth=0) | 
|  | 
| bool | deleteNode (const point3d &value, unsigned int depth=0) | 
|  | 
| bool | deleteNode (double x, double y, double z, unsigned int depth=0) | 
|  | 
| void | deleteNodeChild (ColorOcTreeNode *node, unsigned int childIdx) | 
|  | Deletes the i-th child of the node.  More... 
 | 
|  | 
| const iterator | end () const | 
|  | 
| const leaf_iterator | end_leafs () const | 
|  | 
| const leaf_bbx_iterator | end_leafs_bbx () const | 
|  | 
| const tree_iterator | end_tree () const | 
|  | 
| virtual void | expand () | 
|  | 
| virtual void | expandNode (ColorOcTreeNode *node) | 
|  | 
| virtual void | getMetricMax (double &x, double &y, double &z) | 
|  | maximum value of the bounding box of all known space in x, y, z  More... 
 | 
|  | 
| void | getMetricMax (double &x, double &y, double &z) const | 
|  | maximum value of the bounding box of all known space in x, y, z  More... 
 | 
|  | 
| virtual void | getMetricMin (double &x, double &y, double &z) | 
|  | minimum value of the bounding box of all known space in x, y, z  More... 
 | 
|  | 
| void | getMetricMin (double &x, double &y, double &z) const | 
|  | minimum value of the bounding box of all known space in x, y, z  More... 
 | 
|  | 
| virtual void | getMetricSize (double &x, double &y, double &z) | 
|  | Size of OcTree (all known space) in meters for x, y and z dimension.  More... 
 | 
|  | 
| virtual void | getMetricSize (double &x, double &y, double &z) const | 
|  | Size of OcTree (all known space) in meters for x, y and z dimension.  More... 
 | 
|  | 
| ColorOcTreeNode * | getNodeChild (ColorOcTreeNode *node, unsigned int childIdx) const | 
|  | 
| const ColorOcTreeNode * | getNodeChild (const ColorOcTreeNode *node, unsigned int childIdx) const | 
|  | 
| double | getNodeSize (unsigned depth) const | 
|  | 
| size_t | getNumLeafNodes () const | 
|  | Traverses the tree to calculate the total number of leaf nodes.  More... 
 | 
|  | 
| double | getResolution () const | 
|  | 
| ColorOcTreeNode * | getRoot () const | 
|  | 
| unsigned int | getTreeDepth () const | 
|  | 
| std::string | getTreeType () const | 
|  | 
| void | getUnknownLeafCenters (point3d_list &node_centers, point3d pmin, point3d pmax, unsigned int depth=0) const | 
|  | return centers of leafs that do NOT exist (but could) in a given bounding box  More... 
 | 
|  | 
| point3d | keyToCoord (const OcTreeKey &key) const | 
|  | 
| point3d | keyToCoord (const OcTreeKey &key, unsigned depth) const | 
|  | 
| double | keyToCoord (key_type key) const | 
|  | 
| double | keyToCoord (key_type key, unsigned depth) const | 
|  | 
| unsigned long long | memoryFullGrid () const | 
|  | 
| virtual size_t | memoryUsage () const | 
|  | 
| virtual size_t | memoryUsageNode () const | 
|  | 
| bool | nodeChildExists (const ColorOcTreeNode *node, unsigned int childIdx) const | 
|  | 
| bool | nodeHasChildren (const ColorOcTreeNode *node) const | 
|  | 
|  | OcTreeBaseImpl (const OcTreeBaseImpl< ColorOcTreeNode, AbstractOccupancyOcTree > &rhs) | 
|  | Deep copy constructor.  More... 
 | 
|  | 
|  | OcTreeBaseImpl (double resolution) | 
|  | 
| bool | operator== (const OcTreeBaseImpl< ColorOcTreeNode, AbstractOccupancyOcTree > &rhs) const | 
|  | 
| virtual void | prune () | 
|  | 
| std::istream & | readData (std::istream &s) | 
|  | 
| ColorOcTreeNode * | search (const OcTreeKey &key, unsigned int depth=0) const | 
|  | 
| ColorOcTreeNode * | search (const point3d &value, unsigned int depth=0) const | 
|  | 
| ColorOcTreeNode * | search (double x, double y, double z, unsigned int depth=0) const | 
|  | 
| void | setResolution (double r) | 
|  | 
| virtual size_t | size () const | 
|  | 
| void | swapContent (OcTreeBaseImpl< ColorOcTreeNode, AbstractOccupancyOcTree > &rhs) | 
|  | 
| double | volume () | 
|  | 
| std::ostream & | writeData (std::ostream &s) const | 
|  | 
| virtual | ~OcTreeBaseImpl () | 
|  | 
|  | AbstractOccupancyOcTree () | 
|  | 
| double | getClampingThresMax () const | 
|  | 
| float | getClampingThresMaxLog () const | 
|  | 
| double | getClampingThresMin () const | 
|  | 
| float | getClampingThresMinLog () const | 
|  | 
| double | getOccupancyThres () const | 
|  | 
| float | getOccupancyThresLog () const | 
|  | 
| double | getProbHit () const | 
|  | 
| float | getProbHitLog () const | 
|  | 
| double | getProbMiss () const | 
|  | 
| float | getProbMissLog () const | 
|  | 
| bool | isNodeAtThreshold (const OcTreeNode &occupancyNode) const | 
|  | queries whether a node is at the clamping threshold according to the tree's parameter  More... 
 | 
|  | 
| bool | isNodeAtThreshold (const OcTreeNode *occupancyNode) const | 
|  | queries whether a node is at the clamping threshold according to the tree's parameter  More... 
 | 
|  | 
| bool | isNodeOccupied (const OcTreeNode &occupancyNode) const | 
|  | queries whether a node is occupied according to the tree's parameter for "occupancy"  More... 
 | 
|  | 
| bool | isNodeOccupied (const OcTreeNode *occupancyNode) const | 
|  | queries whether a node is occupied according to the tree's parameter for "occupancy"  More... 
 | 
|  | 
| bool | readBinary (const std::string &filename) | 
|  | 
| bool | readBinary (std::istream &s) | 
|  | 
| void | setClampingThresMax (double thresProb) | 
|  | sets the maximum threshold for occupancy clamping (sensor model)  More... 
 | 
|  | 
| void | setClampingThresMin (double thresProb) | 
|  | sets the minimum threshold for occupancy clamping (sensor model)  More... 
 | 
|  | 
| void | setOccupancyThres (double prob) | 
|  | sets the threshold for occupancy (sensor model)  More... 
 | 
|  | 
| void | setProbHit (double prob) | 
|  | sets the probability for a "hit" (will be converted to logodds) - sensor model  More... 
 | 
|  | 
| void | setProbMiss (double prob) | 
|  | sets the probability for a "miss" (will be converted to logodds) - sensor model  More... 
 | 
|  | 
| bool | writeBinary (const std::string &filename) | 
|  | 
| bool | writeBinary (std::ostream &s) | 
|  | 
| bool | writeBinaryConst (const std::string &filename) const | 
|  | 
| bool | writeBinaryConst (std::ostream &s) const | 
|  | 
| virtual | ~AbstractOccupancyOcTree () | 
|  | 
|  | AbstractOcTree () | 
|  | 
| virtual double | getResolution () const =0 | 
|  | 
| virtual size_t | memoryUsage () const =0 | 
|  | 
| virtual size_t | memoryUsageNode () const =0 | 
|  | 
| virtual size_t | size () const =0 | 
|  | 
| bool | write (const std::string &filename) const | 
|  | Write file header and complete tree to file (serialization)  More... 
 | 
|  | 
| bool | write (std::ostream &s) const | 
|  | Write file header and complete tree to stream (serialization)  More... 
 | 
|  | 
| virtual | ~AbstractOcTree () | 
|  |