Template Class OcTreeBaseImpl

Inheritance Relationships

Base Type

  • public INTERFACE

Derived Types

Class Documentation

template<class NODE, class INTERFACE>
class OcTreeBaseImpl : public INTERFACE

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.

Note

You should probably not use this class directly, but OcTreeBase or OccupancyOcTreeBase instead

Template Parameters:

Subclassed by octomap::OcTreeBase< CountingOcTreeNode >, octomap::OccupancyOcTreeBase< ColorOcTreeNode >, octomap::OccupancyOcTreeBase< OcTreeNode >, octomap::OccupancyOcTreeBase< OcTreeNodeStamped >

Public Types

typedef NODE NodeType

Make the templated NODE type available from the outside.

typedef leaf_iterator iterator

Public Functions

OcTreeBaseImpl(double resolution)
virtual ~OcTreeBaseImpl()
OcTreeBaseImpl(const OcTreeBaseImpl<NODE, INTERFACE> &rhs)

Deep copy constructor.

void swapContent(OcTreeBaseImpl<NODE, INTERFACE> &rhs)

Swap contents of two octrees, i.e., only the underlying pointer / tree structure. You have to ensure yourself that the metadata (resolution etc) matches. No memory is cleared in this function

bool operator==(const OcTreeBaseImpl<NODE, INTERFACE> &rhs) const

Comparison between two octrees, all meta data, all nodes, and the structure must be identical

inline std::string getTreeType() const
void setResolution(double r)

Change the resolution of the octree, scaling all voxels. This will not preserve the (metric) scale!

inline double getResolution() const
inline unsigned int getTreeDepth() const
inline double getNodeSize(unsigned depth) const
inline void clearKeyRays()

Clear KeyRay vector to minimize unneeded memory. This is only useful for the StaticMemberInitializer classes, don’t call it for an octree that is actually used.

NODE *createNodeChild(NODE *node, unsigned int childIdx)

Creates (allocates) the i-th child of the node.

Returns:

ptr to newly create NODE

void deleteNodeChild(NODE *node, unsigned int childIdx)

Deletes the i-th child of the node.

NODE *getNodeChild(NODE *node, unsigned int childIdx) const
Returns:

ptr to child number childIdx of node

const NODE *getNodeChild(const NODE *node, unsigned int childIdx) const
Returns:

const ptr to child number childIdx of node

virtual bool isNodeCollapsible(const NODE *node) const

A node is collapsible if all children exist, don’t have children of their own and have the same occupancy value

bool nodeChildExists(const NODE *node, unsigned int childIdx) const

Safe test if node has a child at index childIdx. First tests if there are any children. Replaces node->childExists(…)

Returns:

true if the child at childIdx exists

bool nodeHasChildren(const NODE *node) const

Safe test if node has any children. Replaces node->hasChildren(…)

Returns:

true if node has at least one child

virtual void expandNode(NODE *node)

Expands a node (reverse of pruning): All children are created and their occupancy probability is set to the node’s value.

You need to verify that this is indeed a pruned node (i.e. not a leaf at the lowest level)

virtual bool pruneNode(NODE *node)

Prunes a node when it is collapsible

Returns:

true if pruning was successful

inline NODE *getRoot() const
Returns:

Pointer to the root node of the tree. This pointer should not be modified or deleted externally, the OcTree manages its memory itself. In an empty tree, root is NULL.

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). You need to check if the returned node is NULL, since it can be in unknown space.

Returns:

pointer to node if found, NULL otherwise

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) You need to check if the returned node is NULL, since it can be in unknown space.

Returns:

pointer to node if found, NULL otherwise

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) You need to check if the returned node is NULL, since it can be in unknown space.

Returns:

pointer to node if found, NULL otherwise

bool 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 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 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.

void clear()

Deletes the complete tree structure.

virtual void prune()

Lossless compression of the octree: A node will replace all of its eight children if they have identical values. You usually don’t have to call prune() after a regular occupancy update, updateNode() incrementally prunes all affected nodes.

virtual void expand()

Expands all pruned nodes (reverse of prune())

Note

This is an expensive operation, especially when the tree is nearly empty!

inline virtual size_t size() const
Returns:

The number of nodes in the tree

virtual size_t memoryUsage() const
Returns:

Memory usage of the complete octree in bytes (may vary between architectures)

inline virtual size_t memoryUsageNode() const
Returns:

Memory usage of a single octree node

unsigned long long memoryFullGrid() const

Note

this can be larger than the adressable memory - size_t may not be enough to hold it!

Returns:

Memory usage of a full grid of the same size as the OcTree in bytes (for comparison)

double volume()
virtual void getMetricSize(double &x, double &y, double &z)

Size of OcTree (all known space) in meters for x, y and z dimension.

virtual void getMetricSize(double &x, double &y, double &z) const

Size of OcTree (all known space) in meters for x, y and z dimension.

virtual void getMetricMin(double &x, double &y, double &z)

minimum value of the bounding box of all known space in x, y, z

void getMetricMin(double &x, double &y, double &z) const

minimum value of the bounding box of all known space in x, y, z

virtual void getMetricMax(double &x, double &y, double &z)

maximum value of the bounding box of all known space in x, y, z

void getMetricMax(double &x, double &y, double &z) const

maximum value of the bounding box of all known space in x, y, z

size_t calcNumNodes() const

Traverses the tree to calculate the total number of nodes.

size_t getNumLeafNodes() const

Traverses the tree to calculate the total number of leaf nodes.

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

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. You still need to check if a node at that coordinate exists (e.g. with search()).

Parameters:
  • origin – start coordinate of ray

  • end – end coordinate of ray

  • rayKeyRay structure that holds the keys of all nodes traversed by the ray, excluding “end”

Returns:

Success of operation. Returning false usually means that one of the coordinates is out of the OcTree’s range

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. You still need to check if a node at that coordinate exists (e.g. with search()).

Note

: use the faster computeRayKeys method if possible.

Parameters:
  • origin – start coordinate of ray

  • end – end coordinate of ray

  • rayKeyRay structure that holds the keys of all nodes traversed by the ray, excluding “end”

Returns:

Success of operation. Returning false usually means that one of the coordinates is out of the OcTree’s range

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. For general file IO, you should probably use AbstractOcTree::read() instead.

std::ostream &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)

inline iterator begin(unsigned char maxDepth = 0) const
Returns:

beginning of the tree as leaf iterator

inline const iterator end() const
Returns:

end of the tree as leaf iterator

inline leaf_iterator begin_leafs(unsigned char maxDepth = 0) const
Returns:

beginning of the tree as leaf iterator

inline const leaf_iterator end_leafs() const
Returns:

end of the tree as leaf iterator

inline leaf_bbx_iterator begin_leafs_bbx(const OcTreeKey &min, const OcTreeKey &max, unsigned char maxDepth = 0) const
Returns:

beginning of the tree as leaf iterator in a bounding box

inline leaf_bbx_iterator begin_leafs_bbx(const point3d &min, const point3d &max, unsigned char maxDepth = 0) const
Returns:

beginning of the tree as leaf iterator in a bounding box

inline const leaf_bbx_iterator end_leafs_bbx() const
Returns:

end of the tree as leaf iterator in a bounding box

inline tree_iterator begin_tree(unsigned char maxDepth = 0) const
Returns:

beginning of the tree as iterator to all nodes (incl. inner)

inline const tree_iterator end_tree() const
Returns:

end of the tree as iterator to all nodes (incl. inner)

inline key_type coordToKey(double coordinate) const

Converts from a single coordinate into a discrete key.

inline key_type coordToKey(double coordinate, unsigned depth) const

Converts from a single coordinate into a discrete key at a given depth.

inline OcTreeKey coordToKey(const point3d &coord) const

Converts from a 3D coordinate into a 3D addressing key.

inline OcTreeKey coordToKey(double x, double y, double z) const

Converts from a 3D coordinate into a 3D addressing key.

inline OcTreeKey coordToKey(const point3d &coord, unsigned depth) const

Converts from a 3D coordinate into a 3D addressing key at a given depth.

inline 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.

inline 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)

Parameters:
  • key – Input key, at the lowest tree level

  • depth – Target depth level for the new key

Returns:

Key for the new depth level

key_type adjustKeyAtDepth(key_type 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)

Parameters:
  • key – Input key, at the lowest tree level

  • depth – Target depth level for the new key

Returns:

Key for the new depth level

bool coordToKeyChecked(const point3d &coord, OcTreeKey &key) const

Converts a 3D coordinate into a 3D OcTreeKey, with boundary checking.

Parameters:
  • coord – 3d coordinate of a point

  • key – values that will be computed, an array of fixed size 3.

Returns:

true if point is within the octree (valid), false otherwise

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.

Parameters:
  • 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.

Returns:

true if point is within the octree (valid), false otherwise

bool coordToKeyChecked(double x, double y, double z, OcTreeKey &key) const

Converts a 3D coordinate into a 3D OcTreeKey, with boundary checking.

Parameters:
  • x

  • y

  • z

  • key – values that will be computed, an array of fixed size 3.

Returns:

true if point is within the octree (valid), false otherwise

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.

Parameters:
  • x

  • y

  • z

  • depth – level of the key from the top

  • key – values that will be computed, an array of fixed size 3.

Returns:

true if point is within the octree (valid), false otherwise

bool coordToKeyChecked(double coordinate, key_type &key) const

Converts a single coordinate into a discrete addressing key, with boundary checking.

Parameters:
  • coordinate – 3d coordinate of a point

  • key – discrete 16 bit adressing key, result

Returns:

true if coordinate is within the octree bounds (valid), false otherwise

bool coordToKeyChecked(double coordinate, unsigned depth, key_type &key) const

Converts a single coordinate into a discrete addressing key, with boundary checking.

Parameters:
  • coordinate – 3d coordinate of a point

  • depth – level of the key from the top

  • key – discrete 16 bit adressing key, result

Returns:

true if coordinate is within the octree bounds (valid), false otherwise

double keyToCoord(key_type key, unsigned depth) const

converts from a discrete key at a given depth into a coordinate corresponding to the key’s center

inline double keyToCoord(key_type key) const

converts from a discrete key at the lowest tree level into a coordinate corresponding to the key’s center

inline 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

inline 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

Protected Functions

OcTreeBaseImpl(double resolution, unsigned int tree_depth, unsigned int tree_max_val)

Constructor to enable derived classes to change tree constants. This usually requires a re-implementation of some core tree-traversal functions as well!

void init()

initialize non-trivial members, helper for constructors

void calcMinMax()

recalculates min and max in x, y, z. Does nothing when tree size didn’t change.

void calcNumNodesRecurs(NODE *node, size_t &num_nodes) const
std::istream &readNodesRecurs(NODE*, std::istream &s)

recursive call of readData()

std::ostream &writeNodesRecurs(const NODE*, std::ostream &s) const

recursive call of writeData()

void deleteNodeRecurs(NODE *node)

Recursively delete a node and all children. Deallocates memory but does NOT set the node ptr to NULL nor updates tree size.

bool deleteNodeRecurs(NODE *node, unsigned int depth, unsigned int max_depth, const OcTreeKey &key)

recursive call of deleteNode()

void pruneRecurs(NODE *node, unsigned int depth, unsigned int max_depth, unsigned int &num_pruned)

recursive call of prune()

void expandRecurs(NODE *node, unsigned int depth, unsigned int max_depth)

recursive call of expand()

size_t getNumLeafNodesRecurs(const NODE *parent) const
void allocNodeChildren(NODE *node)

Protected Attributes

NODE *root

Pointer to the root NODE, NULL for empty tree.

const unsigned int tree_depth

Maximum tree depth is fixed to 16 currently.

const unsigned int tree_max_val
double resolution

in meters

double resolution_factor

= 1. / resolution

size_t tree_size

number of nodes in tree

bool size_changed

flag to denote whether the octree extent changed (for lazy min/max eval)

point3d tree_center
double max_value[3]

max in x, y, z

double min_value[3]

min in x, y, z

std::vector<double> sizeLookupTable

contains the size of a voxel at level i (0: root node). tree_depth+1 levels (incl. 0)

std::vector<KeyRay> keyrays

data structure for ray casting, array for multithreading

const leaf_iterator leaf_iterator_end
const leaf_bbx_iterator leaf_iterator_bbx_end
const tree_iterator tree_iterator_end