octomap 1.9.8
Loading...
Searching...
No Matches
octomap::OcTree Class Reference

octomap main map data structure, stores 3D occupancy grid map in an OcTree. More...

#include <OcTree.h>

+ Inheritance diagram for octomap::OcTree:
+ Collaboration diagram for octomap::OcTree:

Data Structures

class  StaticMemberInitializer
 Static member object which ensures that this OcTree's prototype ends up in the classIDMapping only once. More...
 

Public Types

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

Public Member Functions

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)
 
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)
 
bool bbxSet () 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.
 
virtual bool castRay (const point3d &origin, const point3d &direction, point3d &end, bool ignoreUnknownCells=false, double maxRange=-1.0) const
 Performs raycasting in 3d, similar to computeRay().
 
KeyBoolMap::const_iterator changedKeysBegin () const
 Iterator to traverse all keys of changed nodes.
 
KeyBoolMap::const_iterator changedKeysEnd () const
 Iterator to traverse all keys of changed nodes.
 
void clear ()
 Deletes the complete tree structure.
 
void clearKeyRays ()
 Clear KeyRay vector to minimize unneeded memory.
 
void computeDiscreteUpdate (const Pointcloud &scan, const octomap::point3d &origin, KeySet &free_cells, KeySet &occupied_cells, double maxrange)
 Helper for insertPointCloud().
 
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.
 
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.
 
void computeUpdate (const Pointcloud &scan, const octomap::point3d &origin, KeySet &free_cells, KeySet &occupied_cells, double maxrange)
 Helper for insertPointCloud().
 
OcTreeKey coordToKey (const point3d &coord) const
 Converts from a 3D coordinate into a 3D addressing key.
 
OcTreeKey coordToKey (const point3d &coord, unsigned depth) const
 Converts from a 3D coordinate into a 3D addressing key at a given depth.
 
key_type coordToKey (double coordinate) const
 Converts from a single coordinate into a discrete key.
 
key_type coordToKey (double coordinate, unsigned depth) const
 Converts from a single coordinate into a discrete key at a given depth.
 
OcTreeKey coordToKey (double x, double y, double z) const
 Converts from a 3D coordinate into a 3D addressing key.
 
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.
 
bool coordToKeyChecked (const point3d &coord, OcTreeKey &key) const
 Converts a 3D coordinate into a 3D OcTreeKey, with boundary checking.
 
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.
 
bool coordToKeyChecked (double coordinate, key_type &key) const
 Converts a single coordinate into a discrete addressing key, with boundary checking.
 
bool coordToKeyChecked (double coordinate, unsigned depth, key_type &key) const
 Converts a single coordinate into a discrete addressing key, with boundary checking.
 
bool coordToKeyChecked (double x, double y, double z, OcTreeKey &key) const
 Converts a 3D coordinate into a 3D OcTreeKey, with boundary checking.
 
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.
 
OcTreecreate () const
 virtual constructor: creates a new object of same type (Covariant return type requires an up-to-date compiler)
 
NODE * createNodeChild (NODE *node, unsigned int childIdx)
 Creates (allocates) the i-th child of the node.
 
bool deleteNode (const OcTreeKey &key, unsigned int depth=0)
 Delete a node (if exists) given an addressing key.
 
bool deleteNode (const point3d &value, unsigned int depth=0)
 Delete a node (if exists) given a 3d point.
 
bool deleteNode (double x, double y, double z, unsigned int depth=0)
 Delete a node (if exists) given a 3d point.
 
void deleteNodeChild (NODE *node, unsigned int childIdx)
 Deletes the i-th child of the node.
 
void enableChangeDetection (bool enable)
 track or ignore changes while inserting scans (default: ignore)
 
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 ()
 Expands all pruned nodes (reverse of prune())
 
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.
 
point3d getBBXBounds () const
 
point3d getBBXCenter () const
 
point3d getBBXMax () const
 
point3d getBBXMin () const
 
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
 
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 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.
 
const NODE * getNodeChild (const NODE *node, unsigned int childIdx) const
 
NODE * getNodeChild (NODE *node, unsigned int childIdx) const
 
double getNodeSize (unsigned depth) const
 
bool getNormals (const point3d &point, std::vector< point3d > &normals, bool unknownStatus=true) const
 Performs a step of the marching cubes surface reconstruction algorithm to retrieve the normal of the triangles that fall in the cube formed by the voxels located at the vertex of a given voxel.
 
size_t getNumLeafNodes () const
 Traverses the tree to calculate the total number of leaf nodes.
 
virtual bool getRayIntersection (const point3d &origin, const point3d &direction, const point3d &center, point3d &intersection, double delta=0.0) const
 Retrieves the entry point of a ray into a voxel.
 
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
 
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)
 Integrate a Pointcloud (in global reference frame), parallelized with OpenMP.
 
virtual void insertPointCloud (const Pointcloud &scan, const point3d &sensor_origin, const pose6d &frame_origin, double maxrange=-1., bool lazy_eval=false, bool discretize=false)
 Integrate a 3d scan (transform scan before tree update), parallelized with OpenMP.
 
virtual void insertPointCloud (const ScanNode &scan, double maxrange=-1., bool lazy_eval=false, bool discretize=false)
 Insert a 3d scan (given as a ScanNode) into the tree, parallelized with OpenMP.
 
virtual void insertPointCloudRays (const Pointcloud &scan, const point3d &sensor_origin, double maxrange=-1., bool lazy_eval=false)
 Integrate a Pointcloud (in global reference frame), parallelized with OpenMP.
 
virtual bool insertRay (const point3d &origin, const point3d &end, double maxrange=-1.0, bool lazy_eval=false)
 Insert one ray between origin and end into the tree.
 
virtual void integrateHit (OcTreeNode *occupancyNode) const
 integrate a "hit" measurement according to the tree's sensor model
 
virtual void integrateMiss (OcTreeNode *occupancyNode) const
 integrate a "miss" measurement according to the tree's sensor model
 
bool isChangeDetectionEnabled () const
 
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.
 
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
 
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
 
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
 
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
 
unsigned long long memoryFullGrid () const
 
virtual size_t memoryUsage () const
 
virtual size_t memoryUsageNode () const
 
bool nodeChildExists (const NODE *node, unsigned int childIdx) const
 Safe test if node has a child at index childIdx.
 
bool nodeHasChildren (const NODE *node) const
 Safe test if node has any children.
 
virtual void nodeToMaxLikelihood (OcTreeNode &occupancyNode) const
 converts the node to the maximum likelihood value according to the tree's parameter for "occupancy"
 
virtual void nodeToMaxLikelihood (OcTreeNode *occupancyNode) const
 converts the node to the maximum likelihood value according to the tree's parameter for "occupancy"
 
size_t numChangesDetected () const
 Number of changes since last reset.
 
 OcTree (double resolution)
 Default constructor, sets resolution of leafs.
 
 OcTree (std::string _filename)
 Reads an OcTree from a binary file.
 
bool operator== (const OcTreeBaseImpl< NODE, INTERFACE > &rhs) const
 Comparison between two octrees, all meta data, all nodes, and the structure must be identical.
 
virtual void prune ()
 Lossless compression of the octree: A node will replace all of its eight children if they have identical values.
 
virtual bool pruneNode (NODE *node)
 Prunes a node when it is collapsible.
 
std::istream & readBinaryData (std::istream &s)
 Reads only the data (=complete tree structure) from the input stream.
 
std::istream & readBinaryNode (std::istream &s, OcTreeNode *node)
 Read node from binary stream (max-likelihood value), recursively continue with all children.
 
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.
 
void resetChangeDetection ()
 Reset the set of changed keys. Call this after you obtained all changed nodes.
 
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.
 
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.
 
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).
 
void setBBXMax (const point3d &max)
 sets the maximum for a query bounding box to use
 
void setBBXMin (const point3d &min)
 sets the minimum for a query bounding box to use
 
virtual OcTreeNodesetNodeValue (const OcTreeKey &key, float log_odds_value, bool lazy_eval=false)
 Set log_odds value of voxel to log_odds_value.
 
virtual OcTreeNodesetNodeValue (const point3d &value, float log_odds_value, bool lazy_eval=false)
 Set log_odds value of voxel to log_odds_value.
 
virtual OcTreeNodesetNodeValue (double x, double y, double z, float log_odds_value, bool lazy_eval=false)
 Set log_odds value of voxel to log_odds_value.
 
void setResolution (double r)
 Change the resolution of the octree, scaling all voxels. This will not preserve the (metric) scale!
 
virtual size_t size () const
 
void swapContent (OcTreeBaseImpl< NODE, INTERFACE > &rhs)
 Swap contents of two octrees, i.e., only the underlying pointer / tree structure.
 
virtual void toMaxLikelihood ()
 Creates the maximum likelihood map by calling toMaxLikelihood on all tree nodes, setting their occupancy to the corresponding occupancy thresholds.
 
void updateInnerOccupancy ()
 Updates the occupancy of all inner nodes to reflect their children's occupancy.
 
virtual OcTreeNodeupdateNode (const OcTreeKey &key, bool occupied, bool lazy_eval=false)
 Integrate occupancy measurement.
 
virtual OcTreeNodeupdateNode (const OcTreeKey &key, float log_odds_update, bool lazy_eval=false)
 Manipulate log_odds value of a voxel by changing it by log_odds_update (relative).
 
virtual OcTreeNodeupdateNode (const point3d &value, bool occupied, bool lazy_eval=false)
 Integrate occupancy measurement.
 
virtual OcTreeNodeupdateNode (const point3d &value, float log_odds_update, bool lazy_eval=false)
 Manipulate log_odds value of a voxel by changing it by log_odds_update (relative).
 
virtual OcTreeNodeupdateNode (double x, double y, double z, bool occupied, bool lazy_eval=false)
 Integrate occupancy measurement.
 
virtual OcTreeNodeupdateNode (double x, double y, double z, float log_odds_update, bool lazy_eval=false)
 Manipulate log_odds value of a voxel by changing it by log_odds_update (relative).
 
virtual void updateNodeLogOdds (OcTreeNode *occupancyNode, const float &update) const
 update logodds value of node by adding to the current value.
 
void useBBXLimit (bool enable)
 use or ignore BBX limit (default: ignore)
 
double volume ()
 
std::ostream & writeBinaryData (std::ostream &s) const
 Writes the data of the tree (without header) to the stream, recursively calling writeBinaryNode (starting with root)
 
std::ostream & writeBinaryNode (std::ostream &s, const OcTreeNode *node) const
 Write node to binary stream (max-likelihood value), recursively continue with all children.
 
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)
 
virtual ~OcTree ()
 

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.
 
void calcNumNodesRecurs (NODE *node, size_t &num_nodes) const
 
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 expandRecurs (NODE *node, unsigned int depth, unsigned int max_depth)
 recursive call of expand()
 
size_t getNumLeafNodesRecurs (const NODE *parent) const
 
void init ()
 initialize non-trivial members, helper for constructors
 
bool integrateMissOnRay (const point3d &origin, const point3d &end, bool lazy_eval=false)
 Traces a ray from origin to end and updates all voxels on the way as free.
 
void pruneRecurs (NODE *node, unsigned int depth, unsigned int max_depth, unsigned int &num_pruned)
 recursive call of prune()
 
std::istream & readNodesRecurs (NODE *, std::istream &s)
 recursive call of readData()
 
OcTreeNodesetNodeValueRecurs (OcTreeNode *node, bool node_just_created, const OcTreeKey &key, unsigned int depth, const float &log_odds_value, bool lazy_eval=false)
 
void toMaxLikelihoodRecurs (OcTreeNode *node, unsigned int depth, unsigned int max_depth)
 
void updateInnerOccupancyRecurs (OcTreeNode *node, unsigned int depth)
 
OcTreeNodeupdateNodeRecurs (OcTreeNode *node, bool node_just_created, const OcTreeKey &key, unsigned int depth, const float &log_odds_update, bool lazy_eval=false)
 
std::ostream & writeNodesRecurs (const NODE *, std::ostream &s) const
 recursive call of writeData()
 

Protected Attributes

point3d bbx_max
 
OcTreeKey bbx_max_key
 
point3d bbx_min
 
OcTreeKey bbx_min_key
 
KeyBoolMap changed_keys
 Set of leaf keys (lowest level) which changed since last resetChangeDetection.
 
std::vector< KeyRaykeyrays
 data structure for ray casting, array for multithreading
 
const leaf_bbx_iterator leaf_iterator_bbx_end
 
const leaf_iterator leaf_iterator_end
 
double max_value [3]
 max in x, y, z
 
double min_value [3]
 min in x, y, z contains the size of a voxel at level i (0: root node). tree_depth+1 levels (incl. 0)
 
double resolution
 in meters
 
double resolution_factor
 = 1. / resolution
 
NODE * root
 Pointer to the root NODE, NULL for empty tree.
 
bool size_changed
 
std::vector< double > sizeLookupTable
 
point3d tree_center
 
const unsigned int tree_depth
 Maximum tree depth is fixed to 16 currently.
 
const tree_iterator tree_iterator_end
 
const unsigned int tree_max_val
 
size_t tree_size
 number of nodes in tree flag to denote whether the octree extent changed (for lazy min/max eval)
 
bool use_bbx_limit
 use bounding box for queries (needs to be set)?
 
bool use_change_detection
 

Static Protected Attributes

static StaticMemberInitializer ocTreeMemberInit
 to ensure static initialization (only once)
 

Detailed Description

octomap main map data structure, stores 3D occupancy grid map in an OcTree.

Basic functionality is implemented in OcTreeBase.

Member Typedef Documentation

◆ iterator

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

◆ NodeType

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

Make the templated NODE type available from the outside.

Constructor & Destructor Documentation

◆ OcTree() [1/2]

octomap::OcTree::OcTree ( double  resolution)

Default constructor, sets resolution of leafs.

References octomap::OcTree::StaticMemberInitializer::ensureLinking(), and ocTreeMemberInit.

◆ OcTree() [2/2]

octomap::OcTree::OcTree ( std::string  _filename)

Reads an OcTree from a binary file.

Parameters
_filename

◆ ~OcTree()

virtual octomap::OcTree::~OcTree ( )
inlinevirtual

Member Function Documentation

◆ adjustKeyAtDepth() [1/2]

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

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

References octomap::OcTreeBaseImpl< NODE, INTERFACE >::adjustKeyAtDepth(), and octomap::OcTreeBaseImpl< NODE, INTERFACE >::tree_depth.

Referenced by octomap::OcTreeBaseImpl< NODE, INTERFACE >::adjustKeyAtDepth().

◆ adjustKeyAtDepth() [2/2]

template<class NODE , class I >
key_type octomap::OcTreeBaseImpl< NODE, I >::adjustKeyAtDepth ( key_type  key,
unsigned int  depth 
) const
inherited

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 I >
void octomap::OcTreeBaseImpl< NODE, I >::allocNodeChildren ( NODE *  node)
protectedinherited

◆ bbxSet()

bool octomap::OccupancyOcTreeBase< OcTreeNode >::bbxSet ( ) const
inlineinherited

◆ begin()

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

Referenced by boundingBoxTest(), and main().

◆ begin_leafs()

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

Referenced by boundingBoxTest(), octomap::OcTreeStamped::degradeOutdatedNodes(), and main().

◆ 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
inlineinherited
Returns
beginning of the tree as leaf iterator in a bounding box

Referenced by boundingBoxTest(), and main().

◆ 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
inlineinherited
Returns
beginning of the tree as leaf iterator in a bounding box

◆ begin_tree()

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

Referenced by calcThresholdedNodes(), main(), printChanges(), and octomap::ColorOcTree::writeColorHistogram().

◆ calcMinMax()

template<class NODE , class I >
void octomap::OcTreeBaseImpl< NODE, I >::calcMinMax
protectedinherited

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

◆ calcNumNodes()

template<class NODE , class I >
size_t octomap::OcTreeBaseImpl< NODE, I >::calcNumNodes
inherited

Traverses the tree to calculate the total number of nodes.

Referenced by main(), and octomap::OccupancyOcTreeBase< NODE >::readBinaryData().

◆ calcNumNodesRecurs()

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

◆ castRay()

bool octomap::OccupancyOcTreeBase< OcTreeNode >::castRay ( const point3d origin,
const point3d direction,
point3d end,
bool  ignoreUnknownCells = false,
double  maxRange = -1.0 
) const
virtualinherited

Performs raycasting in 3d, similar to computeRay().

Can be called in parallel e.g. with OpenMP for a speedup.

A ray is cast from 'origin' with a given direction, the first non-free cell is returned in 'end' (as center coordinate). This could also be the origin node if it is occupied or unknown. castRay() returns true if an occupied node was hit by the raycast. If the raycast returns false you can search() the node at 'end' and see whether it's unknown space.

Parameters
[in]originstarting coordinate of ray
[in]directionA vector pointing in the direction of the raycast (NOT a point in space). Does not need to be normalized.
[out]endreturns the center of the last cell on the ray. If the function returns true, it is occupied.
[in]ignoreUnknownCellswhether unknown cells are ignored (= treated as free). If false (default), the raycast aborts when an unknown cell is hit and returns false.
[in]maxRangeMaximum range after which the raycast is aborted (<= 0: no limit, default)
Returns
true if an occupied cell was hit, false if the maximum range or octree bounds are reached, or if an unknown node was hit.

-------— see OcTreeBase::computeRayKeys --------—

◆ changedKeysBegin()

KeyBoolMap::const_iterator octomap::OccupancyOcTreeBase< OcTreeNode >::changedKeysBegin ( ) const
inlineinherited

Iterator to traverse all keys of changed nodes.

you need to enableChangeDetection() first. Here, an OcTreeKey always refers to a node at the lowest tree level (its size is the minimum tree resolution)

◆ changedKeysEnd()

KeyBoolMap::const_iterator octomap::OccupancyOcTreeBase< OcTreeNode >::changedKeysEnd ( ) const
inlineinherited

Iterator to traverse all keys of changed nodes.

◆ clear()

template<class NODE , class I >
void octomap::OcTreeBaseImpl< NODE, I >::clear
inherited

Deletes the complete tree structure.

Referenced by main().

◆ clearKeyRays()

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

◆ computeDiscreteUpdate()

void octomap::OccupancyOcTreeBase< OcTreeNode >::computeDiscreteUpdate ( const Pointcloud scan,
const octomap::point3d origin,
KeySet free_cells,
KeySet occupied_cells,
double  maxrange 
)
inherited

Helper for insertPointCloud().

Computes all octree nodes affected by the point cloud integration at once. Here, occupied nodes have a preference over free ones. This function first discretizes the scan with the octree grid, which results in fewer raycasts (=speedup) but a slightly different result than computeUpdate().

Parameters
scanpoint cloud measurement to be integrated
originorigin of the sensor for ray casting
free_cellskeys of nodes to be cleared
occupied_cellskeys of nodes to be marked occupied
maxrangemaximum range for raycasting (-1: unlimited)

◆ computeRay()

template<class NODE , class I >
bool octomap::OcTreeBaseImpl< NODE, I >::computeRay ( const point3d origin,
const point3d end,
std::vector< point3d > &  ray 
)
inherited

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

References octomap::OcTreeBaseImpl< NODE, INTERFACE >::end().

◆ computeRayKeys()

template<class NODE , class I >
bool octomap::OcTreeBaseImpl< NODE, I >::computeRayKeys ( const point3d origin,
const point3d end,
KeyRay ray 
) const
inherited

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

References octomap::KeyRay::addKey(), octomath::Vector3::norm(), OCTOMAP_WARNING_STR, octomap::KeyRay::reset(), octomap::KeyRay::size(), and octomap::KeyRay::sizeMax().

◆ computeUpdate()

void octomap::OccupancyOcTreeBase< OcTreeNode >::computeUpdate ( const Pointcloud scan,
const octomap::point3d origin,
KeySet free_cells,
KeySet occupied_cells,
double  maxrange 
)
inherited

Helper for insertPointCloud().

Computes all octree nodes affected by the point cloud integration at once. Here, occupied nodes have a preference over free ones.

Parameters
scanpoint cloud measurement to be integrated
originorigin of the sensor for ray casting
free_cellskeys of nodes to be cleared
occupied_cellskeys of nodes to be marked occupied
maxrangemaximum range for raycasting (-1: unlimited)

◆ coordToKey() [1/6]

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

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

References octomap::OcTreeBaseImpl< NODE, INTERFACE >::coordToKey().

◆ coordToKey() [2/6]

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

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

References octomap::OcTreeBaseImpl< NODE, INTERFACE >::coordToKey(), and octomap::OcTreeBaseImpl< NODE, INTERFACE >::tree_depth.

◆ coordToKey() [3/6]

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

◆ coordToKey() [4/6]

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

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

◆ coordToKey() [5/6]

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

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

References octomap::OcTreeBaseImpl< NODE, INTERFACE >::coordToKey().

◆ coordToKey() [6/6]

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

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

References octomap::OcTreeBaseImpl< NODE, INTERFACE >::coordToKey(), and octomap::OcTreeBaseImpl< NODE, INTERFACE >::tree_depth.

◆ coordToKeyChecked() [1/6]

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

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

Referenced by octomap::ColorOcTree::averageNodeColor(), boundingBoxTest(), octomap::ColorOcTree::integrateNodeColor(), main(), octomap::ColorOcTree::setNodeColor(), and octomap::CountingOcTree::updateNode().

◆ coordToKeyChecked() [2/6]

template<class NODE , class I >
bool octomap::OcTreeBaseImpl< NODE, I >::coordToKeyChecked ( const point3d coord,
unsigned  depth,
OcTreeKey key 
) const
inherited

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 I >
bool octomap::OcTreeBaseImpl< NODE, I >::coordToKeyChecked ( double  coordinate,
key_type key 
) const
inherited

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() [4/6]

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

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

◆ coordToKeyChecked() [5/6]

template<class NODE , class I >
bool octomap::OcTreeBaseImpl< NODE, I >::coordToKeyChecked ( double  x,
double  y,
double  z,
OcTreeKey key 
) const
inherited

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() [6/6]

template<class NODE , class I >
bool octomap::OcTreeBaseImpl< NODE, I >::coordToKeyChecked ( double  x,
double  y,
double  z,
unsigned  depth,
OcTreeKey key 
) const
inherited

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

◆ create()

OcTree * octomap::OcTree::create ( ) const
inline

virtual constructor: creates a new object of same type (Covariant return type requires an up-to-date compiler)

References octomap::OcTreeBaseImpl< NODE, INTERFACE >::resolution.

◆ createNodeChild()

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

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

Returns
ptr to newly create NODE

Referenced by main(), and octomap::CountingOcTree::updateNode().

◆ deleteNode() [1/3]

template<class NODE , class I >
bool octomap::OcTreeBaseImpl< NODE, I >::deleteNode ( const OcTreeKey key,
unsigned int  depth = 0 
)
inherited

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.

◆ deleteNode() [2/3]

template<class NODE , class I >
bool octomap::OcTreeBaseImpl< NODE, I >::deleteNode ( const point3d value,
unsigned int  depth = 0 
)
inherited

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 I >
bool octomap::OcTreeBaseImpl< NODE, I >::deleteNode ( double  x,
double  y,
double  z,
unsigned int  depth = 0 
)
inherited

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.

References OCTOMAP_ERROR_STR.

◆ deleteNodeChild()

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

Deletes the i-th child of the node.

Referenced by main(), and octomap::ColorOcTree::pruneNode().

◆ deleteNodeRecurs() [1/2]

template<class NODE , class I >
void octomap::OcTreeBaseImpl< NODE, I >::deleteNodeRecurs ( NODE *  node)
protectedinherited

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 I >
bool octomap::OcTreeBaseImpl< NODE, I >::deleteNodeRecurs ( NODE *  node,
unsigned int  depth,
unsigned int  max_depth,
const OcTreeKey key 
)
protectedinherited

recursive call of deleteNode()

References octomap::computeChildIdx().

◆ enableChangeDetection()

void octomap::OccupancyOcTreeBase< OcTreeNode >::enableChangeDetection ( bool  enable)
inlineinherited

track or ignore changes while inserting scans (default: ignore)

◆ end()

template<class NODE , class INTERFACE >
const iterator octomap::OcTreeBaseImpl< NODE, INTERFACE >::end ( ) const
inlineinherited

◆ end_leafs()

template<class NODE , class INTERFACE >
const leaf_iterator octomap::OcTreeBaseImpl< NODE, INTERFACE >::end_leafs ( ) const
inlineinherited

◆ end_leafs_bbx()

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

References octomap::OcTreeBaseImpl< NODE, INTERFACE >::leaf_iterator_bbx_end.

Referenced by boundingBoxTest(), and main().

◆ end_tree()

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

References octomap::OcTreeBaseImpl< NODE, INTERFACE >::tree_iterator_end.

Referenced by calcThresholdedNodes(), main(), printChanges(), and octomap::ColorOcTree::writeColorHistogram().

◆ expand()

template<class NODE , class I >
void octomap::OcTreeBaseImpl< NODE, I >::expand
virtualinherited

Expands all pruned nodes (reverse of prune())

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

Referenced by boundingBoxTest(), main(), and printChanges().

◆ expandNode()

template<class NODE , class I >
void octomap::OcTreeBaseImpl< NODE, I >::expandNode ( NODE *  node)
virtualinherited

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)

Referenced by main().

◆ expandRecurs()

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

recursive call of expand()

◆ getBBXBounds()

point3d octomap::OccupancyOcTreeBase< OcTreeNode >::getBBXBounds
inherited

◆ getBBXCenter()

point3d octomap::OccupancyOcTreeBase< OcTreeNode >::getBBXCenter
inherited

◆ getBBXMax()

point3d octomap::OccupancyOcTreeBase< OcTreeNode >::getBBXMax ( ) const
inlineinherited
Returns
the currently set maximum for bounding box queries, if set

◆ getBBXMin()

point3d octomap::OccupancyOcTreeBase< OcTreeNode >::getBBXMin ( ) const
inlineinherited
Returns
the currently set minimum for bounding box queries, if set

◆ getMetricMax() [1/2]

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

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

Referenced by boundingBoxTest().

◆ getMetricMax() [2/2]

template<class NODE , class I >
void octomap::OcTreeBaseImpl< NODE, I >::getMetricMax ( double &  x,
double &  y,
double &  z 
) const
inherited

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

◆ getMetricMin() [1/2]

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

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

Referenced by boundingBoxTest().

◆ getMetricMin() [2/2]

template<class NODE , class I >
void octomap::OcTreeBaseImpl< NODE, I >::getMetricMin ( double &  x,
double &  y,
double &  z 
) const
inherited

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

◆ getMetricSize() [1/2]

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

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

Referenced by main(), and outputStatistics().

◆ getMetricSize() [2/2]

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

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

◆ getNodeChild() [1/2]

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

◆ getNodeChild() [2/2]

template<class NODE , class I >
NODE * octomap::OcTreeBaseImpl< NODE, I >::getNodeChild ( NODE *  node,
unsigned int  childIdx 
) const
inherited

◆ getNodeSize()

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

◆ getNormals()

bool octomap::OccupancyOcTreeBase< OcTreeNode >::getNormals ( const point3d point,
std::vector< point3d > &  normals,
bool  unknownStatus = true 
) const
inherited

Performs a step of the marching cubes surface reconstruction algorithm to retrieve the normal of the triangles that fall in the cube formed by the voxels located at the vertex of a given voxel.

Parameters
[in]pointvoxel for which retrieve the normals
[out]normalsnormals of the triangles
[in]unknownStatusconsider unknown cells as free (false) or occupied (default, true).
Returns
True if the input voxel is known in the occupancy grid, and false if it is unknown.

◆ getNumLeafNodes()

template<class NODE , class I >
size_t octomap::OcTreeBaseImpl< NODE, I >::getNumLeafNodes
inherited

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

Referenced by main(), and outputStatistics().

◆ getNumLeafNodesRecurs()

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

◆ getRayIntersection()

bool octomap::OccupancyOcTreeBase< OcTreeNode >::getRayIntersection ( const point3d origin,
const point3d direction,
const point3d center,
point3d intersection,
double  delta = 0.0 
) const
virtualinherited

Retrieves the entry point of a ray into a voxel.

This is the closest intersection point of the ray originating from origin and a plane of the axis aligned cube.

Parameters
[in]originStarting point of ray
[in]directionA vector pointing in the direction of the raycast. Does not need to be normalized.
[in]centerThe center of the voxel where the ray terminated. This is the output of castRay.
[out]intersectionThe entry point of the ray into the voxel, on the voxel surface.
[in]deltaA small increment to avoid ambiguity of beeing exactly on a voxel surface. A positive value will get the point out of the hit voxel, while a negative valuewill get it inside.
Returns
Whether or not an intesection point has been found. Either, the ray never cross the voxel or the ray is exactly parallel to the only surface it intersect.

◆ getResolution()

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

◆ getRoot()

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

References octomap::OcTreeBaseImpl< NODE, INTERFACE >::root.

Referenced by main().

◆ getTreeDepth()

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

◆ getTreeType()

std::string octomap::OcTree::getTreeType ( ) const
inline

◆ getUnknownLeafCenters()

template<class NODE , class I >
void octomap::OcTreeBaseImpl< NODE, I >::getUnknownLeafCenters ( point3d_list node_centers,
point3d  pmin,
point3d  pmax,
unsigned int  depth = 0 
) const
inherited

return centers of leafs that do NOT exist (but could) in a given bounding box

References octomath::Vector3::x(), octomath::Vector3::y(), and octomath::Vector3::z().

◆ inBBX() [1/2]

bool octomap::OccupancyOcTreeBase< OcTreeNode >::inBBX ( const OcTreeKey key) const
inherited
Returns
true if key is in the currently set bounding box

◆ inBBX() [2/2]

bool octomap::OccupancyOcTreeBase< OcTreeNode >::inBBX ( const point3d p) const
inherited
Returns
true if point is in the currently set bounding box

◆ init()

template<class NODE , class I >
void octomap::OcTreeBaseImpl< NODE, I >::init
protectedinherited

initialize non-trivial members, helper for constructors

Referenced by octomap::OcTreeBaseImpl< NODE, INTERFACE >::OcTreeBaseImpl().

◆ insertPointCloud() [1/3]

void octomap::OccupancyOcTreeBase< OcTreeNode >::insertPointCloud ( const Pointcloud scan,
const octomap::point3d sensor_origin,
double  maxrange = -1.,
bool  lazy_eval = false,
bool  discretize = false 
)
virtualinherited

Integrate a Pointcloud (in global reference frame), parallelized with OpenMP.

Special care is taken that each voxel in the map is updated only once, and occupied nodes have a preference over free ones. This avoids holes in the floor from mutual deletion and is more efficient than the plain ray insertion in insertPointCloudRays().

Note
replaces insertScan()
Parameters
scanPointcloud (measurement endpoints), in global reference frame
sensor_originmeasurement origin in global reference frame
maxrangemaximum range for how long individual beams are inserted (default -1: complete beam)
lazy_evalwhether update of inner nodes is omitted after the update (default: false). This speeds up the insertion, but you need to call updateInnerOccupancy() when done.
discretizewhether the scan is discretized first into octree key cells (default: false). This reduces the number of raycasts using computeDiscreteUpdate(), resulting in a potential speedup.*

◆ insertPointCloud() [2/3]

void octomap::OccupancyOcTreeBase< OcTreeNode >::insertPointCloud ( const Pointcloud scan,
const point3d sensor_origin,
const pose6d frame_origin,
double  maxrange = -1.,
bool  lazy_eval = false,
bool  discretize = false 
)
virtualinherited

Integrate a 3d scan (transform scan before tree update), parallelized with OpenMP.

Special care is taken that each voxel in the map is updated only once, and occupied nodes have a preference over free ones. This avoids holes in the floor from mutual deletion and is more efficient than the plain ray insertion in insertPointCloudRays().

Note
replaces insertScan()
Parameters
scanPointcloud (measurement endpoints) relative to frame origin
sensor_originorigin of sensor relative to frame origin
frame_originorigin of reference frame, determines transform to be applied to cloud and sensor origin
maxrangemaximum range for how long individual beams are inserted (default -1: complete beam)
lazy_evalwhether update of inner nodes is omitted after the update (default: false). This speeds up the insertion, but you need to call updateInnerOccupancy() when done.
discretizewhether the scan is discretized first into octree key cells (default: false). This reduces the number of raycasts using computeDiscreteUpdate(), resulting in a potential speedup.*

◆ insertPointCloud() [3/3]

void octomap::OccupancyOcTreeBase< OcTreeNode >::insertPointCloud ( const ScanNode scan,
double  maxrange = -1.,
bool  lazy_eval = false,
bool  discretize = false 
)
virtualinherited

Insert a 3d scan (given as a ScanNode) into the tree, parallelized with OpenMP.

Note
replaces insertScan
Parameters
scanScanNode contains Pointcloud data and frame/sensor origin
maxrangemaximum range for how long individual beams are inserted (default -1: complete beam)
lazy_evalwhether the tree is left 'dirty' after the update (default: false). This speeds up the insertion by not updating inner nodes, but you need to call updateInnerOccupancy() when done.
discretizewhether the scan is discretized first into octree key cells (default: false). This reduces the number of raycasts using computeDiscreteUpdate(), resulting in a potential speedup.

◆ insertPointCloudRays()

void octomap::OccupancyOcTreeBase< OcTreeNode >::insertPointCloudRays ( const Pointcloud scan,
const point3d sensor_origin,
double  maxrange = -1.,
bool  lazy_eval = false 
)
virtualinherited

Integrate a Pointcloud (in global reference frame), parallelized with OpenMP.

This function simply inserts all rays of the point clouds as batch operation. Discretization effects can lead to the deletion of occupied space, it is usually recommended to use insertPointCloud() instead.

Parameters
scanPointcloud (measurement endpoints), in global reference frame
sensor_originmeasurement origin in global reference frame
maxrangemaximum range for how long individual beams are inserted (default -1: complete beam)
lazy_evalwhether update of inner nodes is omitted after the update (default: false). This speeds up the insertion, but you need to call updateInnerOccupancy() when done.

◆ insertRay()

bool octomap::OccupancyOcTreeBase< OcTreeNode >::insertRay ( const point3d origin,
const point3d end,
double  maxrange = -1.0,
bool  lazy_eval = false 
)
virtualinherited

Insert one ray between origin and end into the tree.

integrateMissOnRay() is called for the ray, the end point is updated as occupied. It is usually more efficient to insert complete pointcloudsm with insertPointCloud() or insertPointCloudRays().

Parameters
originorigin of sensor in global coordinates
endendpoint of measurement in global coordinates
maxrangemaximum range after which the raycast should be aborted
lazy_evalwhether update of inner nodes is omitted after the update (default: false). This speeds up the insertion, but you need to call updateInnerOccupancy() when done.
Returns
success of operation

◆ integrateHit()

void octomap::OccupancyOcTreeBase< OcTreeNode >::integrateHit ( OcTreeNode occupancyNode) const
virtualinherited

integrate a "hit" measurement according to the tree's sensor model

◆ integrateMiss()

void octomap::OccupancyOcTreeBase< OcTreeNode >::integrateMiss ( OcTreeNode occupancyNode) const
virtualinherited

integrate a "miss" measurement according to the tree's sensor model

◆ integrateMissOnRay()

bool octomap::OccupancyOcTreeBase< OcTreeNode >::integrateMissOnRay ( const point3d origin,
const point3d end,
bool  lazy_eval = false 
)
inlineprotectedinherited

Traces a ray from origin to end and updates all voxels on the way as free.

The volume containing "end" is not updated.

◆ isChangeDetectionEnabled()

bool octomap::OccupancyOcTreeBase< OcTreeNode >::isChangeDetectionEnabled ( ) const
inlineinherited

◆ isNodeCollapsible()

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

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

◆ keyToCoord() [1/4]

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

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

References octomap::OcTreeBaseImpl< NODE, INTERFACE >::keyToCoord().

◆ keyToCoord() [2/4]

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

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

References octomap::OcTreeBaseImpl< NODE, INTERFACE >::keyToCoord().

◆ keyToCoord() [3/4]

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

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

References octomap::OcTreeBaseImpl< NODE, INTERFACE >::resolution, and octomap::OcTreeBaseImpl< NODE, INTERFACE >::tree_max_val.

◆ keyToCoord() [4/4]

template<class NODE , class I >
double octomap::OcTreeBaseImpl< NODE, I >::keyToCoord ( key_type  key,
unsigned  depth 
) const
inherited

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

Referenced by octomap::CountingOcTree::getCentersMinHitsRecurs(), octomap::OcTreeBaseImpl< NODE, INTERFACE >::keyToCoord(), and main().

◆ memoryFullGrid()

template<class NODE , class I >
unsigned long long octomap::OcTreeBaseImpl< NODE, I >::memoryFullGrid
inherited
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!

Referenced by main(), and outputStatistics().

◆ memoryUsage()

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

Referenced by main(), and outputStatistics().

◆ memoryUsageNode()

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

◆ nodeChildExists()

template<class NODE , class I >
bool octomap::OcTreeBaseImpl< NODE, I >::nodeChildExists ( const NODE *  node,
unsigned int  childIdx 
) const
inherited

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

Referenced by octomap::CountingOcTree::getCentersMinHitsRecurs(), getLeafNodesRecurs(), getVoxelsRecurs(), octomap::ColorOcTree::isNodeCollapsible(), main(), octomap::ColorOcTree::updateInnerOccupancyRecurs(), and octomap::CountingOcTree::updateNode().

◆ nodeHasChildren()

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

Safe test if node has any children.

Replaces node->hasChildren(...)

Returns
true if node has at least one child

Referenced by boundingBoxTest(), octomap::CountingOcTree::getCentersMinHitsRecurs(), getLeafNodesRecurs(), getVoxelsRecurs(), octomap::ColorOcTree::isNodeCollapsible(), main(), and octomap::ColorOcTree::updateInnerOccupancyRecurs().

◆ nodeToMaxLikelihood() [1/2]

void octomap::OccupancyOcTreeBase< OcTreeNode >::nodeToMaxLikelihood ( OcTreeNode occupancyNode) const
virtualinherited

converts the node to the maximum likelihood value according to the tree's parameter for "occupancy"

◆ nodeToMaxLikelihood() [2/2]

void octomap::OccupancyOcTreeBase< OcTreeNode >::nodeToMaxLikelihood ( OcTreeNode occupancyNode) const
virtualinherited

converts the node to the maximum likelihood value according to the tree's parameter for "occupancy"

◆ numChangesDetected()

size_t octomap::OccupancyOcTreeBase< OcTreeNode >::numChangesDetected ( ) const
inlineinherited

Number of changes since last reset.

◆ operator==()

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

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

References octomap::OcTreeBaseImpl< NODE, INTERFACE >::tree_depth, and octomap::OcTreeBaseImpl< NODE, INTERFACE >::tree_max_val.

◆ prune()

template<class NODE , class I >
void octomap::OcTreeBaseImpl< NODE, I >::prune
virtualinherited

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.

Referenced by main(), and printChanges().

◆ pruneNode()

template<class NODE , class I >
bool octomap::OcTreeBaseImpl< NODE, I >::pruneNode ( NODE *  node)
virtualinherited

Prunes a node when it is collapsible.

Returns
true if pruning was successful

Referenced by main().

◆ pruneRecurs()

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

recursive call of prune()

◆ readBinaryData()

std::istream & octomap::OccupancyOcTreeBase< OcTreeNode >::readBinaryData ( std::istream &  s)
inherited

Reads only the data (=complete tree structure) from the input stream.

The tree needs to be constructed with the proper header information beforehand, see readBinary().

◆ readBinaryNode()

std::istream & octomap::OccupancyOcTreeBase< OcTreeNode >::readBinaryNode ( std::istream &  s,
OcTreeNode node 
)
inherited

Read node from binary stream (max-likelihood value), recursively continue with all children.

This will set the log_odds_occupancy value of all leaves to either free or occupied.

◆ readData()

template<class NODE , class I >
std::istream & octomap::OcTreeBaseImpl< NODE, I >::readData ( std::istream &  s)
inherited

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.

References OCTOMAP_ERROR_STR, and OCTOMAP_WARNING_STR.

Referenced by main().

◆ readNodesRecurs()

template<class NODE , class I >
std::istream & octomap::OcTreeBaseImpl< NODE, I >::readNodesRecurs ( NODE *  node,
std::istream &  s 
)
protectedinherited

recursive call of readData()

◆ resetChangeDetection()

void octomap::OccupancyOcTreeBase< OcTreeNode >::resetChangeDetection ( )
inlineinherited

Reset the set of changed keys. Call this after you obtained all changed nodes.

◆ search() [1/3]

template<class NODE , class I >
NODE * octomap::OcTreeBaseImpl< NODE, I >::search ( const OcTreeKey key,
unsigned int  depth = 0 
) const
inherited

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

◆ search() [2/3]

template<class NODE , class I >
NODE * octomap::OcTreeBaseImpl< NODE, I >::search ( const point3d value,
unsigned int  depth = 0 
) const
inherited

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

References OCTOMAP_ERROR_STR.

◆ search() [3/3]

template<class NODE , class I >
NODE * octomap::OcTreeBaseImpl< NODE, I >::search ( double  x,
double  y,
double  z,
unsigned int  depth = 0 
) const
inherited

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

Referenced by octomap::ColorOcTree::averageNodeColor(), boundingBoxTest(), octomap::ColorOcTree::integrateNodeColor(), main(), printChanges(), and octomap::ColorOcTree::setNodeColor().

◆ setBBXMax()

void octomap::OccupancyOcTreeBase< OcTreeNode >::setBBXMax ( const point3d max)
inherited

sets the maximum for a query bounding box to use

◆ setBBXMin()

void octomap::OccupancyOcTreeBase< OcTreeNode >::setBBXMin ( const point3d min)
inherited

sets the minimum for a query bounding box to use

◆ setNodeValue() [1/3]

OcTreeNode * octomap::OccupancyOcTreeBase< OcTreeNode >::setNodeValue ( const OcTreeKey key,
float  log_odds_value,
bool  lazy_eval = false 
)
virtualinherited

Set log_odds value of voxel to log_odds_value.

This only works if key is at the lowest octree level

Parameters
keyOcTreeKey of the NODE that is to be updated
log_odds_valuevalue to be set as the log_odds value of the node
lazy_evalwhether update of inner nodes is omitted after the update (default: false). This speeds up the insertion, but you need to call updateInnerOccupancy() when done.
Returns
pointer to the updated NODE

◆ setNodeValue() [2/3]

OcTreeNode * octomap::OccupancyOcTreeBase< OcTreeNode >::setNodeValue ( const point3d value,
float  log_odds_value,
bool  lazy_eval = false 
)
virtualinherited

Set log_odds value of voxel to log_odds_value.

Looks up the OcTreeKey corresponding to the coordinate and then calls setNodeValue() with it.

Parameters
value3d coordinate of the NODE that is to be updated
log_odds_valuevalue to be set as the log_odds value of the node
lazy_evalwhether update of inner nodes is omitted after the update (default: false). This speeds up the insertion, but you need to call updateInnerOccupancy() when done.
Returns
pointer to the updated NODE

◆ setNodeValue() [3/3]

OcTreeNode * octomap::OccupancyOcTreeBase< OcTreeNode >::setNodeValue ( double  x,
double  y,
double  z,
float  log_odds_value,
bool  lazy_eval = false 
)
virtualinherited

Set log_odds value of voxel to log_odds_value.

Looks up the OcTreeKey corresponding to the coordinate and then calls setNodeValue() with it.

Parameters
x
y
z
log_odds_valuevalue to be set as the log_odds value of the node
lazy_evalwhether update of inner nodes is omitted after the update (default: false). This speeds up the insertion, but you need to call updateInnerOccupancy() when done.
Returns
pointer to the updated NODE

◆ setNodeValueRecurs()

OcTreeNode * octomap::OccupancyOcTreeBase< OcTreeNode >::setNodeValueRecurs ( OcTreeNode node,
bool  node_just_created,
const OcTreeKey key,
unsigned int  depth,
const float &  log_odds_value,
bool  lazy_eval = false 
)
protectedinherited

◆ setResolution()

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

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

Referenced by main().

◆ size()

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

References octomap::OcTreeBaseImpl< NODE, INTERFACE >::tree_size.

Referenced by main(), and outputStatistics().

◆ swapContent()

template<class NODE , class INTERFACE >
void octomap::OcTreeBaseImpl< NODE, I >::swapContent ( OcTreeBaseImpl< NODE, INTERFACE > &  rhs)
inherited

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

References octomap::OcTreeBaseImpl< NODE, INTERFACE >::root, and octomap::OcTreeBaseImpl< NODE, INTERFACE >::tree_size.

Referenced by main().

◆ toMaxLikelihood()

void octomap::OccupancyOcTreeBase< OcTreeNode >::toMaxLikelihood
virtualinherited

Creates the maximum likelihood map by calling toMaxLikelihood on all tree nodes, setting their occupancy to the corresponding occupancy thresholds.

This enables a very efficient compression if you call prune() afterwards.

◆ toMaxLikelihoodRecurs()

void octomap::OccupancyOcTreeBase< OcTreeNode >::toMaxLikelihoodRecurs ( OcTreeNode node,
unsigned int  depth,
unsigned int  max_depth 
)
protectedinherited

◆ updateInnerOccupancy()

void octomap::OccupancyOcTreeBase< OcTreeNode >::updateInnerOccupancy
inherited

Updates the occupancy of all inner nodes to reflect their children's occupancy.

If you performed batch-updates with lazy evaluation enabled, you must call this before any queries to ensure correct multi-resolution behavior.

◆ updateInnerOccupancyRecurs()

void octomap::OccupancyOcTreeBase< OcTreeNode >::updateInnerOccupancyRecurs ( OcTreeNode node,
unsigned int  depth 
)
protectedinherited

◆ updateNode() [1/6]

OcTreeNode * octomap::OccupancyOcTreeBase< OcTreeNode >::updateNode ( const OcTreeKey key,
bool  occupied,
bool  lazy_eval = false 
)
virtualinherited

Integrate occupancy measurement.

Parameters
keyOcTreeKey of the NODE that is to be updated
occupiedtrue if the node was measured occupied, else false
lazy_evalwhether update of inner nodes is omitted after the update (default: false). This speeds up the insertion, but you need to call updateInnerOccupancy() when done.
Returns
pointer to the updated NODE

◆ updateNode() [2/6]

OcTreeNode * octomap::OccupancyOcTreeBase< OcTreeNode >::updateNode ( const OcTreeKey key,
float  log_odds_update,
bool  lazy_eval = false 
)
virtualinherited

Manipulate log_odds value of a voxel by changing it by log_odds_update (relative).

This only works if key is at the lowest octree level

Parameters
keyOcTreeKey of the NODE that is to be updated
log_odds_updatevalue to be added (+) to log_odds value of node
lazy_evalwhether update of inner nodes is omitted after the update (default: false). This speeds up the insertion, but you need to call updateInnerOccupancy() when done.
Returns
pointer to the updated NODE

◆ updateNode() [3/6]

OcTreeNode * octomap::OccupancyOcTreeBase< OcTreeNode >::updateNode ( const point3d value,
bool  occupied,
bool  lazy_eval = false 
)
virtualinherited

Integrate occupancy measurement.

Looks up the OcTreeKey corresponding to the coordinate and then calls udpateNode() with it.

Parameters
value3d coordinate of the NODE that is to be updated
occupiedtrue if the node was measured occupied, else false
lazy_evalwhether update of inner nodes is omitted after the update (default: false). This speeds up the insertion, but you need to call updateInnerOccupancy() when done.
Returns
pointer to the updated NODE

◆ updateNode() [4/6]

OcTreeNode * octomap::OccupancyOcTreeBase< OcTreeNode >::updateNode ( const point3d value,
float  log_odds_update,
bool  lazy_eval = false 
)
virtualinherited

Manipulate log_odds value of a voxel by changing it by log_odds_update (relative).

Looks up the OcTreeKey corresponding to the coordinate and then calls updateNode() with it.

Parameters
value3d coordinate of the NODE that is to be updated
log_odds_updatevalue to be added (+) to log_odds value of node
lazy_evalwhether update of inner nodes is omitted after the update (default: false). This speeds up the insertion, but you need to call updateInnerOccupancy() when done.
Returns
pointer to the updated NODE

◆ updateNode() [5/6]

OcTreeNode * octomap::OccupancyOcTreeBase< OcTreeNode >::updateNode ( double  x,
double  y,
double  z,
bool  occupied,
bool  lazy_eval = false 
)
virtualinherited

Integrate occupancy measurement.

Looks up the OcTreeKey corresponding to the coordinate and then calls udpateNode() with it.

Parameters
x
y
z
occupiedtrue if the node was measured occupied, else false
lazy_evalwhether update of inner nodes is omitted after the update (default: false). This speeds up the insertion, but you need to call updateInnerOccupancy() when done.
Returns
pointer to the updated NODE

◆ updateNode() [6/6]

OcTreeNode * octomap::OccupancyOcTreeBase< OcTreeNode >::updateNode ( double  x,
double  y,
double  z,
float  log_odds_update,
bool  lazy_eval = false 
)
virtualinherited

Manipulate log_odds value of a voxel by changing it by log_odds_update (relative).

Looks up the OcTreeKey corresponding to the coordinate and then calls updateNode() with it.

Parameters
x
y
z
log_odds_updatevalue to be added (+) to log_odds value of node
lazy_evalwhether update of inner nodes is omitted after the update (default: false). This speeds up the insertion, but you need to call updateInnerOccupancy() when done.
Returns
pointer to the updated NODE

◆ updateNodeLogOdds()

void octomap::OccupancyOcTreeBase< OcTreeNode >::updateNodeLogOdds ( OcTreeNode occupancyNode,
const float &  update 
) const
virtualinherited

update logodds value of node by adding to the current value.

◆ updateNodeRecurs()

OcTreeNode * octomap::OccupancyOcTreeBase< OcTreeNode >::updateNodeRecurs ( OcTreeNode node,
bool  node_just_created,
const OcTreeKey key,
unsigned int  depth,
const float &  log_odds_update,
bool  lazy_eval = false 
)
protectedinherited

◆ useBBXLimit()

void octomap::OccupancyOcTreeBase< OcTreeNode >::useBBXLimit ( bool  enable)
inlineinherited

use or ignore BBX limit (default: ignore)

◆ volume()

template<class NODE , class I >
double octomap::OcTreeBaseImpl< NODE, I >::volume
inherited

◆ writeBinaryData()

std::ostream & octomap::OccupancyOcTreeBase< OcTreeNode >::writeBinaryData ( std::ostream &  s) const
inherited

Writes the data of the tree (without header) to the stream, recursively calling writeBinaryNode (starting with root)

◆ writeBinaryNode()

std::ostream & octomap::OccupancyOcTreeBase< OcTreeNode >::writeBinaryNode ( std::ostream &  s,
const OcTreeNode node 
) const
inherited

Write node to binary stream (max-likelihood value), recursively continue with all children.

This will discard the log_odds_occupancy value, writing all leaves as either free or occupied.

Parameters
s
nodeOcTreeNode to write out, will recurse to all children
Returns

◆ writeData()

template<class NODE , class I >
std::ostream & octomap::OcTreeBaseImpl< NODE, I >::writeData ( std::ostream &  s) const
inherited

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 I >
std::ostream & octomap::OcTreeBaseImpl< NODE, I >::writeNodesRecurs ( const NODE *  node,
std::ostream &  s 
) const
protectedinherited

recursive call of writeData()

Field Documentation

◆ bbx_max

point3d octomap::OccupancyOcTreeBase< OcTreeNode >::bbx_max
protectedinherited

◆ bbx_max_key

OcTreeKey octomap::OccupancyOcTreeBase< OcTreeNode >::bbx_max_key
protectedinherited

◆ bbx_min

point3d octomap::OccupancyOcTreeBase< OcTreeNode >::bbx_min
protectedinherited

◆ bbx_min_key

OcTreeKey octomap::OccupancyOcTreeBase< OcTreeNode >::bbx_min_key
protectedinherited

◆ changed_keys

KeyBoolMap octomap::OccupancyOcTreeBase< OcTreeNode >::changed_keys
protectedinherited

Set of leaf keys (lowest level) which changed since last resetChangeDetection.

◆ keyrays

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

data structure for ray casting, array for multithreading

Referenced by octomap::OcTreeBaseImpl< NODE, INTERFACE >::clearKeyRays().

◆ leaf_iterator_bbx_end

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

◆ leaf_iterator_end

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

◆ max_value

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

max in x, y, z

◆ min_value

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

min in x, y, z contains the size of a voxel at level i (0: root node). tree_depth+1 levels (incl. 0)

◆ ocTreeMemberInit

OcTree::StaticMemberInitializer octomap::OcTree::ocTreeMemberInit
staticprotected

to ensure static initialization (only once)

Referenced by OcTree().

◆ resolution

◆ resolution_factor

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

◆ root

◆ size_changed

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

◆ sizeLookupTable

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

◆ tree_center

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

◆ tree_depth

◆ tree_iterator_end

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

◆ tree_max_val

◆ tree_size

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

number of nodes in tree flag to denote whether the octree extent changed (for lazy min/max eval)

Referenced by octomap::OcTreeBaseImpl< NODE, INTERFACE >::size(), octomap::OcTreeBaseImpl< NODE, INTERFACE >::swapContent(), and octomap::CountingOcTree::updateNode().

◆ use_bbx_limit

bool octomap::OccupancyOcTreeBase< OcTreeNode >::use_bbx_limit
protectedinherited

use bounding box for queries (needs to be set)?

◆ use_change_detection

bool octomap::OccupancyOcTreeBase< OcTreeNode >::use_change_detection
protectedinherited

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