Public Types | Public Member Functions | Protected Member Functions | Protected Attributes | Private Member Functions | List of all members
octomap::OcTreeBaseImpl< NODE, INTERFACE > Class Template Reference

#include <OcTreeBaseImpl.h>

Inheritance diagram for octomap::OcTreeBaseImpl< NODE, INTERFACE >:
Inheritance graph
[legend]

Public Types

typedef leaf_iterator iterator
 
typedef NODE NodeType
 Make the templated NODE type available from the outside. More...
 

Public Member Functions

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
 
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 (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...
 
bool coordToKeyChecked (const point3d &coord, OcTreeKey &key) const
 
bool coordToKeyChecked (const point3d &coord, unsigned depth, OcTreeKey &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
 
bool coordToKeyChecked (double coordinate, key_type &key) const
 
bool coordToKeyChecked (double coordinate, unsigned depth, key_type &key) const
 
NODE * createNodeChild (NODE *node, unsigned int childIdx)
 Creates (allocates) the i-th child of the node. More...
 
bool deleteNode (double x, double y, double z, unsigned int depth=0)
 
bool deleteNode (const point3d &value, unsigned int depth=0)
 
bool deleteNode (const OcTreeKey &key, unsigned int depth=0)
 
void deleteNodeChild (NODE *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 (NODE *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...
 
NODE * getNodeChild (NODE *node, unsigned int childIdx) const
 
const NODE * getNodeChild (const NODE *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
 
NODE * 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...
 
virtual bool isNodeCollapsible (const NODE *node) const
 
double keyToCoord (key_type key, unsigned depth) const
 
double keyToCoord (key_type key) const
 
point3d keyToCoord (const OcTreeKey &key) const
 
point3d keyToCoord (const OcTreeKey &key, unsigned depth) const
 
unsigned long long memoryFullGrid () const
 
virtual size_t memoryUsage () const
 
virtual size_t memoryUsageNode () const
 
bool nodeChildExists (const NODE *node, unsigned int childIdx) const
 
bool nodeHasChildren (const NODE *node) const
 
 OcTreeBaseImpl (double resolution)
 
 OcTreeBaseImpl (const OcTreeBaseImpl< NODE, INTERFACE > &rhs)
 Deep copy constructor. More...
 
bool operator== (const OcTreeBaseImpl< NODE, INTERFACE > &rhs) const
 
virtual void prune ()
 
virtual bool pruneNode (NODE *node)
 
std::istream & readData (std::istream &s)
 
NODE * search (double x, double y, double z, unsigned int depth=0) const
 
NODE * search (const point3d &value, unsigned int depth=0) const
 
NODE * search (const OcTreeKey &key, unsigned int depth=0) const
 
void setResolution (double r)
 
virtual size_t size () const
 
void swapContent (OcTreeBaseImpl< NODE, INTERFACE > &rhs)
 
double volume ()
 
std::ostream & writeData (std::ostream &s) const
 
virtual ~OcTreeBaseImpl ()
 

Protected Member Functions

void allocNodeChildren (NODE *node)
 
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
 
void deleteNodeRecurs (NODE *node)
 
bool deleteNodeRecurs (NODE *node, unsigned int depth, unsigned int max_depth, const OcTreeKey &key)
 recursive call of deleteNode() More...
 
void expandRecurs (NODE *node, unsigned int depth, unsigned int max_depth)
 recursive call of expand() More...
 
size_t getNumLeafNodesRecurs (const NODE *parent) const
 
void init ()
 initialize non-trivial members, helper for constructors More...
 
 OcTreeBaseImpl (double resolution, unsigned int tree_depth, unsigned int tree_max_val)
 
void pruneRecurs (NODE *node, unsigned int depth, unsigned int max_depth, unsigned int &num_pruned)
 recursive call of prune() More...
 
std::istream & readNodesRecurs (NODE *, std::istream &s)
 recursive call of readData() More...
 
std::ostream & writeNodesRecurs (const NODE *, std::ostream &s) const
 recursive call of writeData() More...
 

Protected Attributes

std::vector< KeyRaykeyrays
 data structure for ray casting, array for multithreading More...
 
const leaf_bbx_iterator leaf_iterator_bbx_end
 
const leaf_iterator leaf_iterator_end
 
double max_value [3]
 max in x, y, z More...
 
double min_value [3]
 
double resolution
 in meters More...
 
double resolution_factor
 = 1. / resolution More...
 
NODE * root
 Pointer to the root NODE, NULL for empty tree. More...
 
bool size_changed
 flag to denote whether the octree extent changed (for lazy min/max eval) More...
 
std::vector< double > sizeLookupTable
 contains the size of a voxel at level i (0: root node). tree_depth+1 levels (incl. 0) More...
 
point3d tree_center
 
const unsigned int tree_depth
 Maximum tree depth is fixed to 16 currently. More...
 
const tree_iterator tree_iterator_end
 
const unsigned int tree_max_val
 
size_t tree_size
 

Private Member Functions

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

Detailed Description

template<class NODE, class INTERFACE>
class octomap::OcTreeBaseImpl< NODE, 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
NODENode class to be used in tree (usually derived from OcTreeDataNode)
INTERFACEInterface to be derived from, should be either AbstractOcTree or AbstractOccupancyOcTree

Definition at line 75 of file OcTreeBaseImpl.h.

Member Typedef Documentation

◆ iterator

template<class NODE, class INTERFACE>
typedef leaf_iterator octomap::OcTreeBaseImpl< NODE, INTERFACE >::iterator

Definition at line 324 of file OcTreeBaseImpl.h.

◆ NodeType

template<class NODE, class INTERFACE>
typedef NODE octomap::OcTreeBaseImpl< NODE, INTERFACE >::NodeType

Make the templated NODE type available from the outside.

Definition at line 79 of file OcTreeBaseImpl.h.

Constructor & Destructor Documentation

◆ OcTreeBaseImpl() [1/3]

template<class NODE, class INTERFACE>
octomap::OcTreeBaseImpl< NODE, INTERFACE >::OcTreeBaseImpl ( double  resolution)

◆ ~OcTreeBaseImpl()

template<class NODE, class INTERFACE>
virtual octomap::OcTreeBaseImpl< NODE, INTERFACE >::~OcTreeBaseImpl ( )
virtual

◆ OcTreeBaseImpl() [2/3]

template<class NODE, class INTERFACE>
octomap::OcTreeBaseImpl< NODE, INTERFACE >::OcTreeBaseImpl ( const OcTreeBaseImpl< NODE, INTERFACE > &  rhs)

Deep copy constructor.

◆ OcTreeBaseImpl() [3/3]

template<class NODE, class INTERFACE>
octomap::OcTreeBaseImpl< NODE, INTERFACE >::OcTreeBaseImpl ( double  resolution,
unsigned int  tree_depth,
unsigned int  tree_max_val 
)
protected

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

Member Function Documentation

◆ adjustKeyAtDepth() [1/2]

template<class NODE, class INTERFACE>
OcTreeKey octomap::OcTreeBaseImpl< NODE, INTERFACE >::adjustKeyAtDepth ( const OcTreeKey key,
unsigned int  depth 
) const
inline

Adjusts a 3D key from the lowest level to correspond to a higher depth (by shifting the key values)

Parameters
keyInput key, at the lowest tree level
depthTarget depth level for the new key
Returns
Key for the new depth level

Definition at line 399 of file OcTreeBaseImpl.h.

◆ adjustKeyAtDepth() [2/2]

template<class NODE, class INTERFACE>
key_type octomap::OcTreeBaseImpl< NODE, INTERFACE >::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
keyInput key, at the lowest tree level
depthTarget depth level for the new key
Returns
Key for the new depth level

◆ allocNodeChildren()

template<class NODE, class INTERFACE>
void octomap::OcTreeBaseImpl< NODE, INTERFACE >::allocNodeChildren ( NODE *  node)
protected

◆ begin()

template<class NODE, class INTERFACE>
iterator octomap::OcTreeBaseImpl< NODE, INTERFACE >::begin ( unsigned char  maxDepth = 0) const
inline
Returns
beginning of the tree as leaf iterator

Definition at line 327 of file OcTreeBaseImpl.h.

◆ begin_leafs()

template<class NODE, class INTERFACE>
leaf_iterator octomap::OcTreeBaseImpl< NODE, INTERFACE >::begin_leafs ( unsigned char  maxDepth = 0) const
inline
Returns
beginning of the tree as leaf iterator

Definition at line 332 of file OcTreeBaseImpl.h.

◆ begin_leafs_bbx() [1/2]

template<class NODE, class INTERFACE>
leaf_bbx_iterator octomap::OcTreeBaseImpl< NODE, INTERFACE >::begin_leafs_bbx ( const OcTreeKey min,
const OcTreeKey max,
unsigned char  maxDepth = 0 
) const
inline
Returns
beginning of the tree as leaf iterator in a bounding box

Definition at line 337 of file OcTreeBaseImpl.h.

◆ begin_leafs_bbx() [2/2]

template<class NODE, class INTERFACE>
leaf_bbx_iterator octomap::OcTreeBaseImpl< NODE, INTERFACE >::begin_leafs_bbx ( const point3d min,
const point3d max,
unsigned char  maxDepth = 0 
) const
inline
Returns
beginning of the tree as leaf iterator in a bounding box

Definition at line 341 of file OcTreeBaseImpl.h.

◆ begin_tree()

template<class NODE, class INTERFACE>
tree_iterator octomap::OcTreeBaseImpl< NODE, INTERFACE >::begin_tree ( unsigned char  maxDepth = 0) const
inline
Returns
beginning of the tree as iterator to all nodes (incl. inner)

Definition at line 348 of file OcTreeBaseImpl.h.

◆ calcMinMax()

template<class NODE, class INTERFACE>
void octomap::OcTreeBaseImpl< NODE, INTERFACE >::calcMinMax ( )
protected

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

◆ calcNumNodes()

template<class NODE, class INTERFACE>
size_t octomap::OcTreeBaseImpl< NODE, INTERFACE >::calcNumNodes ( ) const

Traverses the tree to calculate the total number of nodes.

◆ calcNumNodesRecurs()

template<class NODE, class INTERFACE>
void octomap::OcTreeBaseImpl< NODE, INTERFACE >::calcNumNodesRecurs ( NODE *  node,
size_t &  num_nodes 
) const
protected

◆ clear()

template<class NODE, class INTERFACE>
void octomap::OcTreeBaseImpl< NODE, INTERFACE >::clear ( )

Deletes the complete tree structure.

◆ clearKeyRays()

template<class NODE, class INTERFACE>
void octomap::OcTreeBaseImpl< NODE, INTERFACE >::clearKeyRays ( )
inline

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.

Definition at line 120 of file OcTreeBaseImpl.h.

◆ computeRay()

template<class NODE, class INTERFACE>
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()).

Note
: use the faster computeRayKeys method if possible.
Parameters
originstart coordinate of ray
endend 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

◆ computeRayKeys()

template<class NODE, class INTERFACE>
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()).

Parameters
originstart coordinate of ray
endend 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

◆ coordToKey() [1/6]

template<class NODE, class INTERFACE>
key_type octomap::OcTreeBaseImpl< NODE, INTERFACE >::coordToKey ( double  coordinate) const
inline

Converts from a single coordinate into a discrete key.

Definition at line 357 of file OcTreeBaseImpl.h.

◆ coordToKey() [2/6]

template<class NODE, class INTERFACE>
key_type octomap::OcTreeBaseImpl< NODE, INTERFACE >::coordToKey ( double  coordinate,
unsigned  depth 
) const

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

◆ coordToKey() [3/6]

template<class NODE, class INTERFACE>
OcTreeKey octomap::OcTreeBaseImpl< NODE, INTERFACE >::coordToKey ( const point3d coord) const
inline

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

Definition at line 366 of file OcTreeBaseImpl.h.

◆ coordToKey() [4/6]

template<class NODE, class INTERFACE>
OcTreeKey octomap::OcTreeBaseImpl< NODE, INTERFACE >::coordToKey ( double  x,
double  y,
double  z 
) const
inline

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

Definition at line 371 of file OcTreeBaseImpl.h.

◆ coordToKey() [5/6]

template<class NODE, class INTERFACE>
OcTreeKey octomap::OcTreeBaseImpl< NODE, INTERFACE >::coordToKey ( const point3d coord,
unsigned  depth 
) const
inline

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

Definition at line 376 of file OcTreeBaseImpl.h.

◆ coordToKey() [6/6]

template<class NODE, class INTERFACE>
OcTreeKey octomap::OcTreeBaseImpl< NODE, INTERFACE >::coordToKey ( double  x,
double  y,
double  z,
unsigned  depth 
) const
inline

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

Definition at line 384 of file OcTreeBaseImpl.h.

◆ coordToKeyChecked() [1/6]

template<class NODE, class INTERFACE>
bool octomap::OcTreeBaseImpl< NODE, INTERFACE >::coordToKeyChecked ( const point3d coord,
OcTreeKey key 
) const

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

Parameters
coord3d coordinate of a point
keyvalues that will be computed, an array of fixed size 3.
Returns
true if point is within the octree (valid), false otherwise

◆ coordToKeyChecked() [2/6]

template<class NODE, class INTERFACE>
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.

Parameters
coord3d coordinate of a point
depthlevel of the key from the top
keyvalues that will be computed, an array of fixed size 3.
Returns
true if point is within the octree (valid), false otherwise

◆ coordToKeyChecked() [3/6]

template<class NODE, class INTERFACE>
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.

Parameters
x
y
z
keyvalues that will be computed, an array of fixed size 3.
Returns
true if point is within the octree (valid), false otherwise

◆ coordToKeyChecked() [4/6]

template<class NODE, class INTERFACE>
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.

Parameters
x
y
z
depthlevel of the key from the top
keyvalues that will be computed, an array of fixed size 3.
Returns
true if point is within the octree (valid), false otherwise

◆ coordToKeyChecked() [5/6]

template<class NODE, class INTERFACE>
bool octomap::OcTreeBaseImpl< NODE, INTERFACE >::coordToKeyChecked ( double  coordinate,
key_type key 
) const

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

Parameters
coordinate3d coordinate of a point
keydiscrete 16 bit adressing key, result
Returns
true if coordinate is within the octree bounds (valid), false otherwise

◆ coordToKeyChecked() [6/6]

template<class NODE, class INTERFACE>
bool octomap::OcTreeBaseImpl< NODE, INTERFACE >::coordToKeyChecked ( double  coordinate,
unsigned  depth,
key_type key 
) const

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

Parameters
coordinate3d coordinate of a point
depthlevel of the key from the top
keydiscrete 16 bit adressing key, result
Returns
true if coordinate is within the octree bounds (valid), false otherwise

◆ createNodeChild()

template<class NODE, class INTERFACE>
NODE* octomap::OcTreeBaseImpl< NODE, INTERFACE >::createNodeChild ( NODE *  node,
unsigned int  childIdx 
)

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

Returns
ptr to newly create NODE

◆ deleteNode() [1/3]

template<class NODE, class INTERFACE>
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.

◆ deleteNode() [2/3]

template<class NODE, class INTERFACE>
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.

◆ deleteNode() [3/3]

template<class NODE, class INTERFACE>
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.

◆ deleteNodeChild()

template<class NODE, class INTERFACE>
void octomap::OcTreeBaseImpl< NODE, INTERFACE >::deleteNodeChild ( NODE *  node,
unsigned int  childIdx 
)

Deletes the i-th child of the node.

◆ deleteNodeRecurs() [1/2]

template<class NODE, class INTERFACE>
void octomap::OcTreeBaseImpl< NODE, INTERFACE >::deleteNodeRecurs ( NODE *  node)
protected

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

◆ deleteNodeRecurs() [2/2]

template<class NODE, class INTERFACE>
bool octomap::OcTreeBaseImpl< NODE, INTERFACE >::deleteNodeRecurs ( NODE *  node,
unsigned int  depth,
unsigned int  max_depth,
const OcTreeKey key 
)
protected

recursive call of deleteNode()

◆ end()

template<class NODE, class INTERFACE>
const iterator octomap::OcTreeBaseImpl< NODE, INTERFACE >::end ( ) const
inline
Returns
end of the tree as leaf iterator

Definition at line 329 of file OcTreeBaseImpl.h.

◆ end_leafs()

template<class NODE, class INTERFACE>
const leaf_iterator octomap::OcTreeBaseImpl< NODE, INTERFACE >::end_leafs ( ) const
inline
Returns
end of the tree as leaf iterator

Definition at line 334 of file OcTreeBaseImpl.h.

◆ end_leafs_bbx()

template<class NODE, class INTERFACE>
const leaf_bbx_iterator octomap::OcTreeBaseImpl< NODE, INTERFACE >::end_leafs_bbx ( ) const
inline
Returns
end of the tree as leaf iterator in a bounding box

Definition at line 345 of file OcTreeBaseImpl.h.

◆ end_tree()

template<class NODE, class INTERFACE>
const tree_iterator octomap::OcTreeBaseImpl< NODE, INTERFACE >::end_tree ( ) const
inline
Returns
end of the tree as iterator to all nodes (incl. inner)

Definition at line 350 of file OcTreeBaseImpl.h.

◆ expand()

template<class NODE, class INTERFACE>
virtual void octomap::OcTreeBaseImpl< NODE, INTERFACE >::expand ( )
virtual

Expands all pruned nodes (reverse of prune())

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

◆ expandNode()

template<class NODE, class INTERFACE>
virtual void octomap::OcTreeBaseImpl< NODE, INTERFACE >::expandNode ( NODE *  node)
virtual

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)

◆ expandRecurs()

template<class NODE, class INTERFACE>
void octomap::OcTreeBaseImpl< NODE, INTERFACE >::expandRecurs ( NODE *  node,
unsigned int  depth,
unsigned int  max_depth 
)
protected

recursive call of expand()

◆ getMetricMax() [1/2]

template<class NODE, class INTERFACE>
virtual void octomap::OcTreeBaseImpl< NODE, INTERFACE >::getMetricMax ( double &  x,
double &  y,
double &  z 
)
virtual

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

◆ getMetricMax() [2/2]

template<class NODE, class INTERFACE>
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

◆ getMetricMin() [1/2]

template<class NODE, class INTERFACE>
virtual void octomap::OcTreeBaseImpl< NODE, INTERFACE >::getMetricMin ( double &  x,
double &  y,
double &  z 
)
virtual

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

◆ getMetricMin() [2/2]

template<class NODE, class INTERFACE>
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

◆ getMetricSize() [1/2]

template<class NODE, class INTERFACE>
virtual void octomap::OcTreeBaseImpl< NODE, INTERFACE >::getMetricSize ( double &  x,
double &  y,
double &  z 
)
virtual

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

◆ getMetricSize() [2/2]

template<class NODE, class INTERFACE>
virtual void octomap::OcTreeBaseImpl< NODE, INTERFACE >::getMetricSize ( double &  x,
double &  y,
double &  z 
) const
virtual

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

◆ getNodeChild() [1/2]

template<class NODE, class INTERFACE>
NODE* octomap::OcTreeBaseImpl< NODE, INTERFACE >::getNodeChild ( NODE *  node,
unsigned int  childIdx 
) const
Returns
ptr to child number childIdx of node

◆ getNodeChild() [2/2]

template<class NODE, class INTERFACE>
const NODE* octomap::OcTreeBaseImpl< NODE, INTERFACE >::getNodeChild ( const NODE *  node,
unsigned int  childIdx 
) const
Returns
const ptr to child number childIdx of node

◆ getNodeSize()

template<class NODE, class INTERFACE>
double octomap::OcTreeBaseImpl< NODE, INTERFACE >::getNodeSize ( unsigned  depth) const
inline

Definition at line 113 of file OcTreeBaseImpl.h.

◆ getNumLeafNodes()

template<class NODE, class INTERFACE>
size_t octomap::OcTreeBaseImpl< NODE, INTERFACE >::getNumLeafNodes ( ) const

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

◆ getNumLeafNodesRecurs()

template<class NODE, class INTERFACE>
size_t octomap::OcTreeBaseImpl< NODE, INTERFACE >::getNumLeafNodesRecurs ( const NODE *  parent) const
protected

◆ getResolution()

template<class NODE, class INTERFACE>
double octomap::OcTreeBaseImpl< NODE, INTERFACE >::getResolution ( ) const
inline

Definition at line 109 of file OcTreeBaseImpl.h.

◆ getRoot()

template<class NODE, class INTERFACE>
NODE* octomap::OcTreeBaseImpl< NODE, INTERFACE >::getRoot ( ) const
inline
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.

Definition at line 179 of file OcTreeBaseImpl.h.

◆ getTreeDepth()

template<class NODE, class INTERFACE>
unsigned int octomap::OcTreeBaseImpl< NODE, INTERFACE >::getTreeDepth ( ) const
inline

Definition at line 111 of file OcTreeBaseImpl.h.

◆ getTreeType()

template<class NODE, class INTERFACE>
std::string octomap::OcTreeBaseImpl< NODE, INTERFACE >::getTreeType ( ) const
inline

Definition at line 104 of file OcTreeBaseImpl.h.

◆ getUnknownLeafCenters()

template<class NODE, class INTERFACE>
void octomap::OcTreeBaseImpl< NODE, INTERFACE >::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

◆ init()

template<class NODE, class INTERFACE>
void octomap::OcTreeBaseImpl< NODE, INTERFACE >::init ( )
protected

initialize non-trivial members, helper for constructors

◆ isNodeCollapsible()

template<class NODE, class INTERFACE>
virtual bool octomap::OcTreeBaseImpl< NODE, INTERFACE >::isNodeCollapsible ( const NODE *  node) const
virtual

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

Reimplemented in octomap::ColorOcTree.

◆ keyToCoord() [1/4]

template<class NODE, class INTERFACE>
double octomap::OcTreeBaseImpl< NODE, INTERFACE >::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

◆ keyToCoord() [2/4]

template<class NODE, class INTERFACE>
double octomap::OcTreeBaseImpl< NODE, INTERFACE >::keyToCoord ( key_type  key) const
inline

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

Definition at line 484 of file OcTreeBaseImpl.h.

◆ keyToCoord() [3/4]

template<class NODE, class INTERFACE>
point3d octomap::OcTreeBaseImpl< NODE, INTERFACE >::keyToCoord ( const OcTreeKey key) const
inline

converts from an addressing key at the lowest tree level into a coordinate corresponding to the key's center

Definition at line 490 of file OcTreeBaseImpl.h.

◆ keyToCoord() [4/4]

template<class NODE, class INTERFACE>
point3d octomap::OcTreeBaseImpl< NODE, INTERFACE >::keyToCoord ( const OcTreeKey key,
unsigned  depth 
) const
inline

converts from an addressing key at a given depth into a coordinate corresponding to the key's center

Definition at line 496 of file OcTreeBaseImpl.h.

◆ memoryFullGrid()

template<class NODE, class INTERFACE>
unsigned long long octomap::OcTreeBaseImpl< NODE, INTERFACE >::memoryFullGrid ( ) const
Returns
Memory usage of a full grid of the same size as the OcTree in bytes (for comparison)
Note
this can be larger than the adressable memory - size_t may not be enough to hold it!

◆ memoryUsage()

template<class NODE, class INTERFACE>
virtual size_t octomap::OcTreeBaseImpl< NODE, INTERFACE >::memoryUsage ( ) const
virtual
Returns
Memory usage of the complete octree in bytes (may vary between architectures)

◆ memoryUsageNode()

template<class NODE, class INTERFACE>
virtual size_t octomap::OcTreeBaseImpl< NODE, INTERFACE >::memoryUsageNode ( ) const
inlinevirtual
Returns
Memory usage of a single octree node

Definition at line 247 of file OcTreeBaseImpl.h.

◆ nodeChildExists()

template<class NODE, class INTERFACE>
bool octomap::OcTreeBaseImpl< NODE, INTERFACE >::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

◆ nodeHasChildren()

template<class NODE, class INTERFACE>
bool octomap::OcTreeBaseImpl< NODE, INTERFACE >::nodeHasChildren ( const NODE *  node) const

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

Returns
true if node has at least one child

◆ operator=()

template<class NODE, class INTERFACE>
OcTreeBaseImpl<NODE,INTERFACE>& octomap::OcTreeBaseImpl< NODE, INTERFACE >::operator= ( const OcTreeBaseImpl< NODE, INTERFACE > &  )
private

Assignment operator is private: don't (re-)assign octrees (const-parameters can't be changed) - use the copy constructor instead.

◆ operator==()

template<class NODE, class INTERFACE>
bool octomap::OcTreeBaseImpl< NODE, INTERFACE >::operator== ( const OcTreeBaseImpl< NODE, INTERFACE > &  rhs) const

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

◆ prune()

template<class NODE, class INTERFACE>
virtual void octomap::OcTreeBaseImpl< NODE, INTERFACE >::prune ( )
virtual

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.

◆ pruneNode()

template<class NODE, class INTERFACE>
virtual bool octomap::OcTreeBaseImpl< NODE, INTERFACE >::pruneNode ( NODE *  node)
virtual

Prunes a node when it is collapsible

Returns
true if pruning was successful

Reimplemented in octomap::ColorOcTree.

◆ pruneRecurs()

template<class NODE, class INTERFACE>
void octomap::OcTreeBaseImpl< NODE, INTERFACE >::pruneRecurs ( NODE *  node,
unsigned int  depth,
unsigned int  max_depth,
unsigned int &  num_pruned 
)
protected

recursive call of prune()

◆ readData()

template<class NODE, class INTERFACE>
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.

◆ readNodesRecurs()

template<class NODE, class INTERFACE>
std::istream& octomap::OcTreeBaseImpl< NODE, INTERFACE >::readNodesRecurs ( NODE *  ,
std::istream &  s 
)
protected

recursive call of readData()

◆ search() [1/3]

template<class NODE, class INTERFACE>
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). 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

◆ search() [2/3]

template<class NODE, class INTERFACE>
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) 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

◆ search() [3/3]

template<class NODE, class INTERFACE>
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) 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

◆ setResolution()

template<class NODE, class INTERFACE>
void octomap::OcTreeBaseImpl< NODE, INTERFACE >::setResolution ( double  r)

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

◆ size()

template<class NODE, class INTERFACE>
virtual size_t octomap::OcTreeBaseImpl< NODE, INTERFACE >::size ( ) const
inlinevirtual
Returns
The number of nodes in the tree

Definition at line 241 of file OcTreeBaseImpl.h.

◆ swapContent()

template<class NODE, class INTERFACE>
void octomap::OcTreeBaseImpl< NODE, INTERFACE >::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

◆ volume()

template<class NODE, class INTERFACE>
double octomap::OcTreeBaseImpl< NODE, INTERFACE >::volume ( )

◆ writeData()

template<class NODE, class INTERFACE>
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)

◆ writeNodesRecurs()

template<class NODE, class INTERFACE>
std::ostream& octomap::OcTreeBaseImpl< NODE, INTERFACE >::writeNodesRecurs ( const NODE *  ,
std::ostream &  s 
) const
protected

recursive call of writeData()

Member Data Documentation

◆ keyrays

template<class NODE, class INTERFACE>
std::vector<KeyRay> octomap::OcTreeBaseImpl< NODE, INTERFACE >::keyrays
protected

data structure for ray casting, array for multithreading

Definition at line 562 of file OcTreeBaseImpl.h.

◆ leaf_iterator_bbx_end

template<class NODE, class INTERFACE>
const leaf_bbx_iterator octomap::OcTreeBaseImpl< NODE, INTERFACE >::leaf_iterator_bbx_end
protected

Definition at line 565 of file OcTreeBaseImpl.h.

◆ leaf_iterator_end

template<class NODE, class INTERFACE>
const leaf_iterator octomap::OcTreeBaseImpl< NODE, INTERFACE >::leaf_iterator_end
protected

Definition at line 564 of file OcTreeBaseImpl.h.

◆ max_value

template<class NODE, class INTERFACE>
double octomap::OcTreeBaseImpl< NODE, INTERFACE >::max_value[3]
protected

max in x, y, z

Definition at line 556 of file OcTreeBaseImpl.h.

◆ min_value

template<class NODE, class INTERFACE>
double octomap::OcTreeBaseImpl< NODE, INTERFACE >::min_value[3]
protected

min in x, y, z

Definition at line 557 of file OcTreeBaseImpl.h.

◆ resolution

template<class NODE, class INTERFACE>
double octomap::OcTreeBaseImpl< NODE, INTERFACE >::resolution
protected

in meters

Definition at line 547 of file OcTreeBaseImpl.h.

◆ resolution_factor

template<class NODE, class INTERFACE>
double octomap::OcTreeBaseImpl< NODE, INTERFACE >::resolution_factor
protected

= 1. / resolution

Definition at line 548 of file OcTreeBaseImpl.h.

◆ root

template<class NODE, class INTERFACE>
NODE* octomap::OcTreeBaseImpl< NODE, INTERFACE >::root
protected

Pointer to the root NODE, NULL for empty tree.

Definition at line 542 of file OcTreeBaseImpl.h.

◆ size_changed

template<class NODE, class INTERFACE>
bool octomap::OcTreeBaseImpl< NODE, INTERFACE >::size_changed
protected

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

Definition at line 552 of file OcTreeBaseImpl.h.

◆ sizeLookupTable

template<class NODE, class INTERFACE>
std::vector<double> octomap::OcTreeBaseImpl< NODE, INTERFACE >::sizeLookupTable
protected

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

Definition at line 559 of file OcTreeBaseImpl.h.

◆ tree_center

template<class NODE, class INTERFACE>
point3d octomap::OcTreeBaseImpl< NODE, INTERFACE >::tree_center
protected

Definition at line 554 of file OcTreeBaseImpl.h.

◆ tree_depth

template<class NODE, class INTERFACE>
const unsigned int octomap::OcTreeBaseImpl< NODE, INTERFACE >::tree_depth
protected

Maximum tree depth is fixed to 16 currently.

Definition at line 545 of file OcTreeBaseImpl.h.

◆ tree_iterator_end

template<class NODE, class INTERFACE>
const tree_iterator octomap::OcTreeBaseImpl< NODE, INTERFACE >::tree_iterator_end
protected

Definition at line 566 of file OcTreeBaseImpl.h.

◆ tree_max_val

template<class NODE, class INTERFACE>
const unsigned int octomap::OcTreeBaseImpl< NODE, INTERFACE >::tree_max_val
protected

Definition at line 546 of file OcTreeBaseImpl.h.

◆ tree_size

template<class NODE, class INTERFACE>
size_t octomap::OcTreeBaseImpl< NODE, INTERFACE >::tree_size
protected

number of nodes in tree

Definition at line 550 of file OcTreeBaseImpl.h.


The documentation for this class was generated from the following file:


octomap
Author(s): Kai M. Wurm , Armin Hornung
autogenerated on Mon Feb 28 2022 22:58:06