OcTree base class, to be used with with any kind of OcTreeDataNode.
This tree implementation currently has a maximum depth of 16 nodes. For this reason, coordinates values have to be, e.g., below +/- 327.68 meters (2^15) at a maximum resolution of 0.01m.
This limitation enables the use of an efficient key generation method which uses the binary representation of the data point coordinates.
| NODE | Node class to be used in tree (usually derived from OcTreeDataNode) |
| INTERFACE | Interface to be derived from, should be either AbstractOcTree or AbstractOccupancyOcTree |
Definition at line 85 of file OcTreeBaseImpl.h.
#include <mrpt/otherlibs/octomap/OcTreeBaseImpl.h>

Classes | |
| class | iterator_base |
| Base class for OcTree iterators. More... | |
| class | leaf_bbx_iterator |
| Bounding-box leaf iterator. More... | |
| class | leaf_iterator |
| Iterator to iterate over all leafs of the tree. More... | |
| class | tree_iterator |
| Iterator over the complete tree (inner nodes and leafs). More... | |
Public Types | |
| typedef NODE | NodeType |
| Make the templated NODE type available from the outside. More... | |
| typedef leaf_iterator | iterator |
Public Member Functions | |
| OcTreeBaseImpl (double resolution) | |
| virtual | ~OcTreeBaseImpl () |
| OcTreeBaseImpl (const OcTreeBaseImpl< NODE, INTERFACE > &rhs) | |
| bool | operator== (const OcTreeBaseImpl< NODE, INTERFACE > &rhs) const |
| std::string | getTreeType () const |
| void | setResolution (double r) |
| Change the resolution of the octree, scaling all voxels. More... | |
| double | getResolution () const |
| unsigned int | getTreeDepth () const |
| double | getNodeSize (unsigned depth) const |
| NODE * | getRoot () const |
| NODE * | search (double x, double y, double z, unsigned int depth=0) const |
| Search node at specified depth given a 3d point (depth=0: search full tree depth) More... | |
| NODE * | search (const point3d &value, unsigned int depth=0) const |
| Search node at specified depth given a 3d point (depth=0: search full tree depth) More... | |
| NODE * | search (const OcTreeKey &key, unsigned int depth=0) const |
| Search a node at specified depth given an addressing key (depth=0: search full tree depth) More... | |
| bool | deleteNode (double x, double y, double z, unsigned int depth=0) |
| Delete a node (if exists) given a 3d point. More... | |
| bool | deleteNode (const point3d &value, unsigned int depth=0) |
| Delete a node (if exists) given a 3d point. More... | |
| bool | deleteNode (const OcTreeKey &key, unsigned int depth=0) |
| Delete a node (if exists) given an addressing key. More... | |
| void | clear () |
| Deletes the complete tree structure (only the root node will remain) More... | |
| virtual void | prune () |
| Lossless compression of OcTree: merge children to parent when there are eight children with identical values. More... | |
| virtual void | expand () |
| Expands all pruned nodes (reverse of prune()) More... | |
| virtual size_t | size () const |
| virtual size_t | memoryUsage () const |
| virtual size_t | memoryUsageNode () const |
| size_t | memoryFullGrid () const |
| double | volume () const |
| 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... | |
| 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 | 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... | |
| size_t | calcNumNodes () const |
| Traverses the tree to calculate the total number of nodes. More... | |
| size_t | getNumLeafNodes () const |
| Traverses the tree to calculate the total number of leaf nodes. More... | |
| void | getUnknownLeafCenters (point3d_list &node_centers, point3d pmin, point3d pmax) const |
| return centers of leafs that do NOT exist (but could) in a given bounding box More... | |
| bool | computeRayKeys (const point3d &origin, const point3d &end, KeyRay &ray) const |
| Traces a ray from origin to end (excluding), returning an OcTreeKey of all nodes traversed by the beam. More... | |
| bool | computeRay (const point3d &origin, const point3d &end, std::vector< point3d > &ray) |
| Traces a ray from origin to end (excluding), returning the coordinates of all nodes traversed by the beam. More... | |
| std::istream & | readData (std::istream &s) |
| Read all nodes from the input stream (without file header), for this the tree needs to be already created. More... | |
| std::ostream & | writeData (std::ostream &s) const |
| Write complete state of tree to stream (without file header) unmodified. More... | |
| iterator | begin (unsigned char maxDepth=0) const |
| const iterator | end () const |
| leaf_iterator | begin_leafs (unsigned char maxDepth=0) const |
| const leaf_iterator | end_leafs () 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 |
| const leaf_bbx_iterator | end_leafs_bbx () const |
| tree_iterator | begin_tree (unsigned char maxDepth=0) const |
| const tree_iterator | end_tree () const |
| unsigned short int | coordToKey (double coordinate) const |
| Converts from a single coordinate into a discrete key. More... | |
| unsigned short int | coordToKey (double coordinate, unsigned depth) const |
| Converts from a single coordinate into a discrete key at a given depth. More... | |
| OcTreeKey | coordToKey (const point3d &coord) const |
| Converts from a 3D coordinate into a 3D addressing key. More... | |
| OcTreeKey | coordToKey (double x, double y, double z) 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... | |
| 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... | |
| OcTreeKey | adjustKeyAtDepth (const OcTreeKey &key, unsigned int depth) const |
| Adjusts a 3D key from the lowest level to correspond to a higher depth (by shifting the key values) More... | |
| unsigned short int | adjustKeyAtDepth (unsigned short int key, unsigned int depth) const |
| Adjusts a single key value from the lowest level to correspond to a higher depth (by shifting the key value) More... | |
| bool | coordToKeyChecked (const point3d &coord, OcTreeKey &key) const |
| Converts a 3D coordinate into a 3D OcTreeKey, with boundary checking. More... | |
| bool | coordToKeyChecked (const point3d &coord, unsigned depth, OcTreeKey &key) const |
| Converts a 3D coordinate into a 3D OcTreeKey at a certain depth, with boundary checking. More... | |
| bool | coordToKeyChecked (double x, double y, double z, OcTreeKey &key) const |
| Converts a 3D coordinate into a 3D OcTreeKey, with boundary checking. More... | |
| bool | coordToKeyChecked (double x, double y, double z, unsigned depth, OcTreeKey &key) const |
| Converts a 3D coordinate into a 3D OcTreeKey at a certain depth, with boundary checking. More... | |
| bool | coordToKeyChecked (double coordinate, unsigned short int &key) const |
| Converts a single coordinate into a discrete addressing key, with boundary checking. More... | |
| bool | coordToKeyChecked (double coordinate, unsigned depth, unsigned short int &key) const |
| Converts a single coordinate into a discrete addressing key, with boundary checking. More... | |
| double | keyToCoord (unsigned short int key, unsigned depth) const |
| converts from a discrete key at a given depth into a coordinate corresponding to the key's center More... | |
| double | keyToCoord (unsigned short int key) const |
| converts from a discrete key at the lowest tree level into a coordinate corresponding to the key's center More... | |
| point3d | keyToCoord (const OcTreeKey &key) const |
| converts from an addressing key at the lowest tree level into a coordinate corresponding to the key's center More... | |
| point3d | keyToCoord (const OcTreeKey &key, unsigned depth) const |
| converts from an addressing key at a given depth into a coordinate corresponding to the key's center More... | |
| DEPRECATED (bool genKeyValue(double coordinate, unsigned short int &keyval) const) | |
| DEPRECATED (bool genKey(const point3d &point, OcTreeKey &key) const ) | |
| DEPRECATED (bool genKeyValueAtDepth(const unsigned short int keyval, unsigned int depth, unsigned short int &out_keyval) const ) | |
| DEPRECATED (bool genKeyAtDepth(const OcTreeKey &key, unsigned int depth, OcTreeKey &out_key) const ) | |
| DEPRECATED (bool genCoordFromKey(const unsigned short int &key, unsigned depth, float &coord) const ) | |
| DEPRECATED (inline bool genCoordFromKey(const unsigned short int &key, float &coord, unsigned depth) const) | |
| DEPRECATED (inline bool genCoordFromKey(const unsigned short int &key, float &coord) const) | |
| DEPRECATED (double genCoordFromKey(const unsigned short int &key, unsigned depth) const) | |
| DEPRECATED (inline double genCoordFromKey(const unsigned short int &key) const) | |
| DEPRECATED (inline bool genCoords(const OcTreeKey &key, unsigned int depth, point3d &point) const) | |
| DEPRECATED (inline void genPos(const OcTreeKey &key, int depth, unsigned int &pos) const) | |
| generate child index (between 0 and 7) from key at given tree depth DEPRECATED More... | |
Protected Member Functions | |
| OcTreeBaseImpl (double resolution, unsigned int tree_depth, unsigned int tree_max_val) | |
| Constructor to enable derived classes to change tree constants. More... | |
| void | calcMinMax () |
| recalculates min and max in x, y, z. Does nothing when tree size didn't change. More... | |
| void | calcNumNodesRecurs (NODE *node, size_t &num_nodes) const |
| bool | deleteNodeRecurs (NODE *node, unsigned int depth, unsigned int max_depth, const OcTreeKey &key) |
| recursive call of deleteNode() More... | |
| void | pruneRecurs (NODE *node, unsigned int depth, unsigned int max_depth, unsigned int &num_pruned) |
| recursive call of prune() More... | |
| void | expandRecurs (NODE *node, unsigned int depth, unsigned int max_depth) |
| recursive call of expand() More... | |
| size_t | getNumLeafNodesRecurs (const NODE *parent) const |
Protected Attributes | |
| NODE * | root |
| const unsigned int | tree_depth |
| Maximum tree depth is fixed to 16 currently. More... | |
| const unsigned int | tree_max_val |
| double | resolution |
| in meters More... | |
| double | resolution_factor |
| = 1. / resolution More... | |
| size_t | tree_size |
| number of nodes in tree More... | |
| bool | size_changed |
| flag to denote whether the octree extent changed (for lazy min/max eval) More... | |
| point3d | tree_center |
| double | max_value [3] |
| max in x, y, z More... | |
| double | min_value [3] |
| min in x, y, z More... | |
| std::vector< double > | sizeLookupTable |
| contains the size of a voxel at level i (0: root node). tree_depth+1 levels (incl. 0) More... | |
| KeyRay | keyray |
| const leaf_iterator | leaf_iterator_end |
| const leaf_bbx_iterator | leaf_iterator_bbx_end |
| const tree_iterator | tree_iterator_end |
Private Member Functions | |
| OcTreeBaseImpl< NODE, INTERFACE > & | operator= (const OcTreeBaseImpl< NODE, INTERFACE > &) |
| Assignment operator is private: don't (re-)assign octrees (const-parameters can't be changed) - use the copy constructor instead. More... | |
| typedef leaf_iterator octomap::OcTreeBaseImpl< NODE, INTERFACE >::iterator |
Definition at line 261 of file OcTreeBaseImpl.h.
| typedef NODE octomap::OcTreeBaseImpl< NODE, INTERFACE >::NodeType |
Make the templated NODE type available from the outside.
Definition at line 89 of file OcTreeBaseImpl.h.
| octomap::OcTreeBaseImpl< NODE, INTERFACE >::OcTreeBaseImpl | ( | double | resolution | ) |
|
virtual |
| octomap::OcTreeBaseImpl< NODE, INTERFACE >::OcTreeBaseImpl | ( | const OcTreeBaseImpl< NODE, INTERFACE > & | rhs | ) |
|
protected |
Constructor to enable derived classes to change tree constants.
This usually requires a re-implementation of some core tree-traversal functions as well!
|
inline |
Adjusts a 3D key from the lowest level to correspond to a higher depth (by shifting the key values)
| key | Input key, at the lowest tree level |
| depth | Target depth level for the new key |
Definition at line 336 of file OcTreeBaseImpl.h.
Referenced by octomap::OcTreeBaseImpl< OcTreeNodeStamped, AbstractOccupancyOcTree >::adjustKeyAtDepth().
| unsigned short int octomap::OcTreeBaseImpl< NODE, INTERFACE >::adjustKeyAtDepth | ( | unsigned short int | key, |
| unsigned int | depth | ||
| ) | const |
Adjusts a single key value from the lowest level to correspond to a higher depth (by shifting the key value)
| key | Input key, at the lowest tree level |
| depth | Target depth level for the new key |
|
inline |
Definition at line 264 of file OcTreeBaseImpl.h.
|
inline |
Definition at line 269 of file OcTreeBaseImpl.h.
|
inline |
Definition at line 274 of file OcTreeBaseImpl.h.
|
inline |
Definition at line 278 of file OcTreeBaseImpl.h.
|
inline |
Definition at line 285 of file OcTreeBaseImpl.h.
|
protected |
recalculates min and max in x, y, z. Does nothing when tree size didn't change.
| size_t octomap::OcTreeBaseImpl< NODE, INTERFACE >::calcNumNodes | ( | ) | const |
Traverses the tree to calculate the total number of nodes.
|
protected |
| void octomap::OcTreeBaseImpl< NODE, INTERFACE >::clear | ( | ) |
Deletes the complete tree structure (only the root node will remain)
| bool octomap::OcTreeBaseImpl< NODE, INTERFACE >::computeRay | ( | const point3d & | origin, |
| const point3d & | end, | ||
| std::vector< point3d > & | ray | ||
| ) |
Traces a ray from origin to end (excluding), returning the coordinates of all nodes traversed by the beam.
You still need to check if a node at that coordinate exists (e.g. with search()).
| origin | start coordinate of ray |
| end | end coordinate of ray |
| ray | KeyRay structure that holds the keys of all nodes traversed by the ray, excluding "end" |
| bool octomap::OcTreeBaseImpl< NODE, INTERFACE >::computeRayKeys | ( | const point3d & | origin, |
| const point3d & | end, | ||
| KeyRay & | ray | ||
| ) | const |
Traces a ray from origin to end (excluding), returning an OcTreeKey of all nodes traversed by the beam.
You still need to check if a node at that coordinate exists (e.g. with search()).
| origin | start coordinate of ray |
| end | end coordinate of ray |
| ray | KeyRay structure that holds the keys of all nodes traversed by the ray, excluding "end" |
|
inline |
Converts from a single coordinate into a discrete key.
Definition at line 294 of file OcTreeBaseImpl.h.
Referenced by octomap::OcTreeBaseImpl< OcTreeNodeStamped, AbstractOccupancyOcTree >::coordToKey().
| unsigned short int octomap::OcTreeBaseImpl< NODE, INTERFACE >::coordToKey | ( | double | coordinate, |
| unsigned | depth | ||
| ) | const |
Converts from a single coordinate into a discrete key at a given depth.
|
inline |
Converts from a 3D coordinate into a 3D addressing key.
Definition at line 303 of file OcTreeBaseImpl.h.
|
inline |
Converts from a 3D coordinate into a 3D addressing key.
Definition at line 308 of file OcTreeBaseImpl.h.
|
inline |
Converts from a 3D coordinate into a 3D addressing key at a given depth.
Definition at line 313 of file OcTreeBaseImpl.h.
|
inline |
Converts from a 3D coordinate into a 3D addressing key at a given depth.
Definition at line 321 of file OcTreeBaseImpl.h.
| bool octomap::OcTreeBaseImpl< NODE, INTERFACE >::coordToKeyChecked | ( | const point3d & | coord, |
| OcTreeKey & | key | ||
| ) | const |
Converts a 3D coordinate into a 3D OcTreeKey, with boundary checking.
| coord | 3d coordinate of a point |
| key | values that will be computed, an array of fixed size 3. |
Referenced by octomap::OcTreeBaseImpl< OcTreeNodeStamped, AbstractOccupancyOcTree >::DEPRECATED().
| bool octomap::OcTreeBaseImpl< NODE, INTERFACE >::coordToKeyChecked | ( | const point3d & | coord, |
| unsigned | depth, | ||
| OcTreeKey & | key | ||
| ) | const |
Converts a 3D coordinate into a 3D OcTreeKey at a certain depth, with boundary checking.
| coord | 3d coordinate of a point |
| depth | level of the key from the top |
| key | values that will be computed, an array of fixed size 3. |
| bool octomap::OcTreeBaseImpl< NODE, INTERFACE >::coordToKeyChecked | ( | double | x, |
| double | y, | ||
| double | z, | ||
| OcTreeKey & | key | ||
| ) | const |
Converts a 3D coordinate into a 3D OcTreeKey, with boundary checking.
| x | |
| y | |
| z | |
| key | values that will be computed, an array of fixed size 3. |
| bool octomap::OcTreeBaseImpl< NODE, INTERFACE >::coordToKeyChecked | ( | double | x, |
| double | y, | ||
| double | z, | ||
| unsigned | depth, | ||
| OcTreeKey & | key | ||
| ) | const |
Converts a 3D coordinate into a 3D OcTreeKey at a certain depth, with boundary checking.
| x | |
| y | |
| z | |
| depth | level of the key from the top |
| key | values that will be computed, an array of fixed size 3. |
| bool octomap::OcTreeBaseImpl< NODE, INTERFACE >::coordToKeyChecked | ( | double | coordinate, |
| unsigned short int & | key | ||
| ) | const |
Converts a single coordinate into a discrete addressing key, with boundary checking.
| coordinate | 3d coordinate of a point |
| key | discrete 16 bit adressing key, result |
| bool octomap::OcTreeBaseImpl< NODE, INTERFACE >::coordToKeyChecked | ( | double | coordinate, |
| unsigned | depth, | ||
| unsigned short int & | key | ||
| ) | const |
Converts a single coordinate into a discrete addressing key, with boundary checking.
| coordinate | 3d coordinate of a point |
| depth | level of the key from the top |
| key | discrete 16 bit adressing key, result |
| bool octomap::OcTreeBaseImpl< NODE, INTERFACE >::deleteNode | ( | double | x, |
| double | y, | ||
| double | z, | ||
| unsigned int | depth = 0 |
||
| ) |
Delete a node (if exists) given a 3d point.
Will always delete at the lowest level unless depth !=0, and expand pruned inner nodes as needed. Pruned nodes at level "depth" will directly be deleted as a whole.
| bool octomap::OcTreeBaseImpl< NODE, INTERFACE >::deleteNode | ( | const point3d & | value, |
| unsigned int | depth = 0 |
||
| ) |
Delete a node (if exists) given a 3d point.
Will always delete at the lowest level unless depth !=0, and expand pruned inner nodes as needed. Pruned nodes at level "depth" will directly be deleted as a whole.
| bool octomap::OcTreeBaseImpl< NODE, INTERFACE >::deleteNode | ( | const OcTreeKey & | key, |
| unsigned int | depth = 0 |
||
| ) |
Delete a node (if exists) given an addressing key.
Will always delete at the lowest level unless depth !=0, and expand pruned inner nodes as needed. Pruned nodes at level "depth" will directly be deleted as a whole.
|
protected |
recursive call of deleteNode()
|
inline |
Definition at line 438 of file OcTreeBaseImpl.h.
|
inline |
Definition at line 443 of file OcTreeBaseImpl.h.
| octomap::OcTreeBaseImpl< NODE, INTERFACE >::DEPRECATED | ( | bool genKeyValueAtDepth(const unsigned short int keyval, unsigned int depth, unsigned short int &out_keyval) | const | ) |
| octomap::OcTreeBaseImpl< NODE, INTERFACE >::DEPRECATED | ( | bool genKeyAtDepth(const OcTreeKey &key, unsigned int depth, OcTreeKey &out_key) | const | ) |
|
inline |
Definition at line 455 of file OcTreeBaseImpl.h.
|
inline |
Definition at line 462 of file OcTreeBaseImpl.h.
|
inline |
Definition at line 469 of file OcTreeBaseImpl.h.
|
inline |
Definition at line 475 of file OcTreeBaseImpl.h.
|
inline |
Definition at line 480 of file OcTreeBaseImpl.h.
|
inline |
Definition at line 486 of file OcTreeBaseImpl.h.
|
inline |
generate child index (between 0 and 7) from key at given tree depth DEPRECATED
Definition at line 493 of file OcTreeBaseImpl.h.
|
inline |
Definition at line 266 of file OcTreeBaseImpl.h.
|
inline |
Definition at line 271 of file OcTreeBaseImpl.h.
|
inline |
Definition at line 282 of file OcTreeBaseImpl.h.
|
inline |
Definition at line 287 of file OcTreeBaseImpl.h.
|
virtual |
Expands all pruned nodes (reverse of prune())
|
protected |
recursive call of expand()
|
virtual |
maximum value of the bounding box of all known space in x, y, z
| void octomap::OcTreeBaseImpl< NODE, INTERFACE >::getMetricMax | ( | double & | x, |
| double & | y, | ||
| double & | z | ||
| ) | const |
maximum value of the bounding box of all known space in x, y, z
|
virtual |
minimum value of the bounding box of all known space in x, y, z
| void octomap::OcTreeBaseImpl< NODE, INTERFACE >::getMetricMin | ( | double & | x, |
| double & | y, | ||
| double & | z | ||
| ) | const |
minimum value of the bounding box of all known space in x, y, z
|
virtual |
Size of OcTree (all known space) in meters for x, y and z dimension.
|
virtual |
Size of OcTree (all known space) in meters for x, y and z dimension.
|
inline |
Definition at line 111 of file OcTreeBaseImpl.h.
| size_t octomap::OcTreeBaseImpl< NODE, INTERFACE >::getNumLeafNodes | ( | ) | const |
Traverses the tree to calculate the total number of leaf nodes.
|
protected |
|
inline |
Definition at line 107 of file OcTreeBaseImpl.h.
|
inline |
Definition at line 118 of file OcTreeBaseImpl.h.
|
inline |
Definition at line 109 of file OcTreeBaseImpl.h.
|
inline |
Definition at line 102 of file OcTreeBaseImpl.h.
| void octomap::OcTreeBaseImpl< NODE, INTERFACE >::getUnknownLeafCenters | ( | point3d_list & | node_centers, |
| point3d | pmin, | ||
| point3d | pmax | ||
| ) | const |
return centers of leafs that do NOT exist (but could) in a given bounding box
| double octomap::OcTreeBaseImpl< NODE, INTERFACE >::keyToCoord | ( | unsigned short int | key, |
| unsigned | depth | ||
| ) | const |
converts from a discrete key at a given depth into a coordinate corresponding to the key's center
Referenced by octomap::OcTreeBaseImpl< OcTreeNodeStamped, AbstractOccupancyOcTree >::DEPRECATED(), and octomap::OcTreeBaseImpl< OcTreeNodeStamped, AbstractOccupancyOcTree >::keyToCoord().
|
inline |
converts from a discrete key at the lowest tree level into a coordinate corresponding to the key's center
Definition at line 421 of file OcTreeBaseImpl.h.
|
inline |
converts from an addressing key at the lowest tree level into a coordinate corresponding to the key's center
Definition at line 427 of file OcTreeBaseImpl.h.
|
inline |
converts from an addressing key at a given depth into a coordinate corresponding to the key's center
Definition at line 433 of file OcTreeBaseImpl.h.
| size_t octomap::OcTreeBaseImpl< NODE, INTERFACE >::memoryFullGrid | ( | ) | const |
|
virtual |
|
inlinevirtual |
Definition at line 182 of file OcTreeBaseImpl.h.
|
private |
Assignment operator is private: don't (re-)assign octrees (const-parameters can't be changed) - use the copy constructor instead.
| bool octomap::OcTreeBaseImpl< NODE, INTERFACE >::operator== | ( | const OcTreeBaseImpl< NODE, INTERFACE > & | rhs | ) | const |
|
virtual |
Lossless compression of OcTree: merge children to parent when there are eight children with identical values.
|
protected |
recursive call of prune()
| std::istream& octomap::OcTreeBaseImpl< NODE, INTERFACE >::readData | ( | std::istream & | s | ) |
Read all nodes from the input stream (without file header), for this the tree needs to be already created.
For general file IO, you should probably use AbstractOcTree::read() instead.
| NODE* octomap::OcTreeBaseImpl< NODE, INTERFACE >::search | ( | double | x, |
| double | y, | ||
| double | z, | ||
| unsigned int | depth = 0 |
||
| ) | const |
Search node at specified depth given a 3d point (depth=0: search full tree depth)
| NODE* octomap::OcTreeBaseImpl< NODE, INTERFACE >::search | ( | const point3d & | value, |
| unsigned int | depth = 0 |
||
| ) | const |
Search node at specified depth given a 3d point (depth=0: search full tree depth)
| NODE* octomap::OcTreeBaseImpl< NODE, INTERFACE >::search | ( | const OcTreeKey & | key, |
| unsigned int | depth = 0 |
||
| ) | const |
Search a node at specified depth given an addressing key (depth=0: search full tree depth)
| void octomap::OcTreeBaseImpl< NODE, INTERFACE >::setResolution | ( | double | r | ) |
Change the resolution of the octree, scaling all voxels.
This will not preserve the (metric) scale!
|
inlinevirtual |
Definition at line 176 of file OcTreeBaseImpl.h.
| double octomap::OcTreeBaseImpl< NODE, INTERFACE >::volume | ( | ) | const |
| std::ostream& octomap::OcTreeBaseImpl< NODE, INTERFACE >::writeData | ( | std::ostream & | s | ) | const |
Write complete state of tree to stream (without file header) unmodified.
Pruning the tree first produces smaller files (lossless compression)
|
protected |
Definition at line 544 of file OcTreeBaseImpl.h.
|
protected |
Definition at line 547 of file OcTreeBaseImpl.h.
Referenced by octomap::OcTreeBaseImpl< NODE, INTERFACE >::leaf_iterator::operator++().
|
protected |
Definition at line 546 of file OcTreeBaseImpl.h.
Referenced by octomap::OcTreeBaseImpl< OcTreeNodeStamped, AbstractOccupancyOcTree >::end(), and octomap::OcTreeBaseImpl< OcTreeNodeStamped, AbstractOccupancyOcTree >::end_leafs().
|
protected |
max in x, y, z
Definition at line 539 of file OcTreeBaseImpl.h.
|
protected |
min in x, y, z
Definition at line 540 of file OcTreeBaseImpl.h.
|
protected |
in meters
Definition at line 530 of file OcTreeBaseImpl.h.
Referenced by octomap::OcTreeBaseImpl< NODE, INTERFACE >::iterator_base::operator->(), and octomap::OcTreeBaseImpl< NODE, INTERFACE >::leaf_bbx_iterator::singleIncrement().
|
protected |
= 1. / resolution
Definition at line 531 of file OcTreeBaseImpl.h.
Referenced by octomap::OcTreeBaseImpl< OcTreeNodeStamped, AbstractOccupancyOcTree >::coordToKey().
|
protected |
Definition at line 525 of file OcTreeBaseImpl.h.
Referenced by octomap::OcTreeBaseImpl< OcTreeNodeStamped, AbstractOccupancyOcTree >::getRoot().
|
protected |
flag to denote whether the octree extent changed (for lazy min/max eval)
Definition at line 535 of file OcTreeBaseImpl.h.
|
protected |
contains the size of a voxel at level i (0: root node). tree_depth+1 levels (incl. 0)
Definition at line 542 of file OcTreeBaseImpl.h.
Referenced by octomap::OcTreeBaseImpl< NODE, INTERFACE >::iterator_base::operator*().
|
protected |
Definition at line 537 of file OcTreeBaseImpl.h.
|
protected |
Maximum tree depth is fixed to 16 currently.
Definition at line 528 of file OcTreeBaseImpl.h.
Referenced by octomap::OcTreeBaseImpl< OcTreeNodeStamped, AbstractOccupancyOcTree >::adjustKeyAtDepth(), octomap::OcTreeBaseImpl< OcTreeNodeStamped, AbstractOccupancyOcTree >::coordToKey(), octomap::OcTreeBaseImpl< OcTreeNodeStamped, AbstractOccupancyOcTree >::getTreeDepth(), and octomap::OcTreeBaseImpl< NODE, INTERFACE >::iterator_base::operator*().
|
protected |
Definition at line 548 of file OcTreeBaseImpl.h.
Referenced by octomap::OcTreeBaseImpl< OcTreeNodeStamped, AbstractOccupancyOcTree >::end_tree().
|
protected |
Definition at line 529 of file OcTreeBaseImpl.h.
Referenced by octomap::OcTreeBaseImpl< OcTreeNodeStamped, AbstractOccupancyOcTree >::coordToKey(), and octomap::OcTreeBaseImpl< NODE, INTERFACE >::leaf_bbx_iterator::singleIncrement().
|
protected |
number of nodes in tree
Definition at line 533 of file OcTreeBaseImpl.h.
Referenced by octomap::OcTreeBaseImpl< OcTreeNodeStamped, AbstractOccupancyOcTree >::size().
| Page generated by Doxygen 1.8.9.1 for MRPT 1.3.2 SVN:Unversioned directory at Thu Dec 10 00:07:55 UTC 2015 |