Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
octomap::OccupancyOcTreeBase< NODE > Class Template Reference

#include <OccupancyOcTreeBase.h>

Inheritance diagram for octomap::OccupancyOcTreeBase< NODE >:
Inheritance graph
[legend]

Public Member Functions

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

Protected Member Functions

bool integrateMissOnRay (const point3d &origin, const point3d &end, bool lazy_eval=false)
 
 OccupancyOcTreeBase (double resolution, unsigned int tree_depth, unsigned int tree_max_val)
 
NODE * setNodeValueRecurs (NODE *node, bool node_just_created, const OcTreeKey &key, unsigned int depth, const float &log_odds_value, bool lazy_eval=false)
 
void toMaxLikelihoodRecurs (NODE *node, unsigned int depth, unsigned int max_depth)
 
void updateInnerOccupancyRecurs (NODE *node, unsigned int depth)
 
NODE * updateNodeRecurs (NODE *node, bool node_just_created, const OcTreeKey &key, unsigned int depth, const float &log_odds_update, bool lazy_eval=false)
 
- Protected Member Functions inherited from octomap::OcTreeBaseImpl< NODE, AbstractOccupancyOcTree >
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 Member Functions inherited from octomap::AbstractOccupancyOcTree
bool readBinaryLegacyHeader (std::istream &s, unsigned int &size, double &res)
 Try to read the old binary format for conversion, will be removed in the future. More...
 

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. More...
 
bool use_bbx_limit
 use bounding box for queries (needs to be set)? More...
 
bool use_change_detection
 
- Protected Attributes inherited from octomap::OcTreeBaseImpl< NODE, AbstractOccupancyOcTree >
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
 
- Protected Attributes inherited from octomap::AbstractOccupancyOcTree
float clamping_thres_max
 
float clamping_thres_min
 
float occ_prob_thres_log
 
float prob_hit_log
 
float prob_miss_log
 

Additional Inherited Members

- Public Types inherited from octomap::OcTreeBaseImpl< NODE, AbstractOccupancyOcTree >
typedef leaf_iterator iterator
 
typedef NODE NodeType
 Make the templated NODE type available from the outside. More...
 
- Static Public Member Functions inherited from octomap::AbstractOcTree
static AbstractOcTreecreateTree (const std::string id, double res)
 
static AbstractOcTreeread (const std::string &filename)
 
static AbstractOcTreeread (std::istream &s)
 
- Static Protected Member Functions inherited from octomap::AbstractOcTree
static bool readHeader (std::istream &s, std::string &id, unsigned &size, double &res)
 
static void registerTreeType (AbstractOcTree *tree)
 
- Static Protected Attributes inherited from octomap::AbstractOccupancyOcTree
static const std::string binaryFileHeader = "# Octomap OcTree binary file"
 
- Static Protected Attributes inherited from octomap::AbstractOcTree
static const std::string fileHeader = "# Octomap OcTree file"
 

Detailed Description

template<class NODE>
class octomap::OccupancyOcTreeBase< NODE >

Base implementation for Occupancy Octrees (e.g. for mapping). AbstractOccupancyOcTree serves as a common base interface for all these classes. Each class used as NODE type needs to be derived from OccupancyOcTreeNode.

This tree implementation has a maximum depth of 16. At a resolution of 1 cm, values have to be < +/- 327.68 meters (2^15)

This limitation enables the use of an efficient key generation method which uses the binary representation of the data.

Note
The tree does not save individual points.
Template Parameters
NODENode class to be used in tree (usually derived from OcTreeDataNode)

Definition at line 69 of file OccupancyOcTreeBase.h.

Constructor & Destructor Documentation

◆ OccupancyOcTreeBase() [1/3]

template<class NODE >
octomap::OccupancyOcTreeBase< NODE >::OccupancyOcTreeBase ( double  resolution)

Default constructor, sets resolution of leafs.

◆ ~OccupancyOcTreeBase()

template<class NODE >
virtual octomap::OccupancyOcTreeBase< NODE >::~OccupancyOcTreeBase ( )
virtual

◆ OccupancyOcTreeBase() [2/3]

template<class NODE >
octomap::OccupancyOcTreeBase< NODE >::OccupancyOcTreeBase ( const OccupancyOcTreeBase< NODE > &  rhs)

Copy constructor.

◆ OccupancyOcTreeBase() [3/3]

template<class NODE >
octomap::OccupancyOcTreeBase< NODE >::OccupancyOcTreeBase ( 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

◆ bbxSet()

template<class NODE >
bool octomap::OccupancyOcTreeBase< NODE >::bbxSet ( ) const
inline

Definition at line 335 of file OccupancyOcTreeBase.h.

◆ castRay()

template<class NODE >
virtual bool octomap::OccupancyOcTreeBase< NODE >::castRay ( const point3d origin,
const point3d direction,
point3d end,
bool  ignoreUnknownCells = false,
double  maxRange = -1.0 
) const
virtual

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.

◆ changedKeysBegin()

template<class NODE >
KeyBoolMap::const_iterator octomap::OccupancyOcTreeBase< NODE >::changedKeysBegin ( ) const
inline

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)

Definition at line 363 of file OccupancyOcTreeBase.h.

◆ changedKeysEnd()

template<class NODE >
KeyBoolMap::const_iterator octomap::OccupancyOcTreeBase< NODE >::changedKeysEnd ( ) const
inline

Iterator to traverse all keys of changed nodes.

Definition at line 366 of file OccupancyOcTreeBase.h.

◆ computeDiscreteUpdate()

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

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)

◆ computeUpdate()

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

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)

◆ enableChangeDetection()

template<class NODE >
void octomap::OccupancyOcTreeBase< NODE >::enableChangeDetection ( bool  enable)
inline

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

Definition at line 353 of file OccupancyOcTreeBase.h.

◆ getBBXBounds()

template<class NODE >
point3d octomap::OccupancyOcTreeBase< NODE >::getBBXBounds ( ) const

◆ getBBXCenter()

template<class NODE >
point3d octomap::OccupancyOcTreeBase< NODE >::getBBXCenter ( ) const

◆ getBBXMax()

template<class NODE >
point3d octomap::OccupancyOcTreeBase< NODE >::getBBXMax ( ) const
inline
Returns
the currently set maximum for bounding box queries, if set

Definition at line 343 of file OccupancyOcTreeBase.h.

◆ getBBXMin()

template<class NODE >
point3d octomap::OccupancyOcTreeBase< NODE >::getBBXMin ( ) const
inline
Returns
the currently set minimum for bounding box queries, if set

Definition at line 341 of file OccupancyOcTreeBase.h.

◆ getNormals()

template<class NODE >
bool octomap::OccupancyOcTreeBase< NODE >::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.

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.

◆ getRayIntersection()

template<class NODE >
virtual bool octomap::OccupancyOcTreeBase< NODE >::getRayIntersection ( const point3d origin,
const point3d direction,
const point3d center,
point3d intersection,
double  delta = 0.0 
) const
virtual

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.

◆ inBBX() [1/2]

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

◆ inBBX() [2/2]

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

◆ insertPointCloud() [1/3]

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

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]

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

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]

template<class NODE >
virtual void octomap::OccupancyOcTreeBase< NODE >::insertPointCloud ( const ScanNode scan,
double  maxrange = -1.,
bool  lazy_eval = false,
bool  discretize = false 
)
virtual

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

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

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

template<class NODE >
virtual bool octomap::OccupancyOcTreeBase< NODE >::insertRay ( const point3d origin,
const point3d end,
double  maxrange = -1.0,
bool  lazy_eval = false 
)
virtual

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

template<class NODE >
virtual void octomap::OccupancyOcTreeBase< NODE >::integrateHit ( NODE *  occupancyNode) const
virtual

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

◆ integrateMiss()

template<class NODE >
virtual void octomap::OccupancyOcTreeBase< NODE >::integrateMiss ( NODE *  occupancyNode) const
virtual

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

◆ integrateMissOnRay()

template<class NODE >
bool octomap::OccupancyOcTreeBase< NODE >::integrateMissOnRay ( const point3d origin,
const point3d end,
bool  lazy_eval = false 
)
inlineprotected

Traces a ray from origin to end and updates all voxels on the way as free. The volume containing "end" is not updated.

◆ isChangeDetectionEnabled()

template<class NODE >
bool octomap::OccupancyOcTreeBase< NODE >::isChangeDetectionEnabled ( ) const
inline

Definition at line 354 of file OccupancyOcTreeBase.h.

◆ nodeToMaxLikelihood() [1/2]

template<class NODE >
virtual void octomap::OccupancyOcTreeBase< NODE >::nodeToMaxLikelihood ( NODE &  occupancyNode) const
virtual

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

◆ nodeToMaxLikelihood() [2/2]

template<class NODE >
virtual void octomap::OccupancyOcTreeBase< NODE >::nodeToMaxLikelihood ( NODE *  occupancyNode) const
virtual

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

◆ numChangesDetected()

template<class NODE >
size_t octomap::OccupancyOcTreeBase< NODE >::numChangesDetected ( ) const
inline

Number of changes since last reset.

Definition at line 369 of file OccupancyOcTreeBase.h.

◆ readBinaryData()

template<class NODE >
std::istream& octomap::OccupancyOcTreeBase< NODE >::readBinaryData ( std::istream &  s)
virtual

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().

Implements octomap::AbstractOccupancyOcTree.

◆ readBinaryNode()

template<class NODE >
std::istream& octomap::OccupancyOcTreeBase< NODE >::readBinaryNode ( std::istream &  s,
NODE *  node 
)

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.

◆ resetChangeDetection()

template<class NODE >
void octomap::OccupancyOcTreeBase< NODE >::resetChangeDetection ( )
inline

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

Definition at line 356 of file OccupancyOcTreeBase.h.

◆ setBBXMax()

template<class NODE >
void octomap::OccupancyOcTreeBase< NODE >::setBBXMax ( const point3d max)

sets the maximum for a query bounding box to use

◆ setBBXMin()

template<class NODE >
void octomap::OccupancyOcTreeBase< NODE >::setBBXMin ( const point3d min)

sets the minimum for a query bounding box to use

◆ setNodeValue() [1/3]

template<class NODE >
virtual NODE* octomap::OccupancyOcTreeBase< NODE >::setNodeValue ( const OcTreeKey key,
float  log_odds_value,
bool  lazy_eval = false 
)
virtual

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]

template<class NODE >
virtual NODE* octomap::OccupancyOcTreeBase< NODE >::setNodeValue ( const point3d value,
float  log_odds_value,
bool  lazy_eval = false 
)
virtual

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]

template<class NODE >
virtual NODE* octomap::OccupancyOcTreeBase< NODE >::setNodeValue ( double  x,
double  y,
double  z,
float  log_odds_value,
bool  lazy_eval = false 
)
virtual

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

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

◆ toMaxLikelihood()

template<class NODE >
virtual void octomap::OccupancyOcTreeBase< NODE >::toMaxLikelihood ( )
virtual

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.

Implements octomap::AbstractOccupancyOcTree.

◆ toMaxLikelihoodRecurs()

template<class NODE >
void octomap::OccupancyOcTreeBase< NODE >::toMaxLikelihoodRecurs ( NODE *  node,
unsigned int  depth,
unsigned int  max_depth 
)
protected

◆ updateInnerOccupancy()

template<class NODE >
void octomap::OccupancyOcTreeBase< NODE >::updateInnerOccupancy ( )

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

template<class NODE >
void octomap::OccupancyOcTreeBase< NODE >::updateInnerOccupancyRecurs ( NODE *  node,
unsigned int  depth 
)
protected

◆ updateNode() [1/6]

template<class NODE >
virtual NODE* octomap::OccupancyOcTreeBase< NODE >::updateNode ( const OcTreeKey key,
bool  occupied,
bool  lazy_eval = false 
)
virtual

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

Implements octomap::AbstractOccupancyOcTree.

◆ updateNode() [2/6]

template<class NODE >
virtual NODE* octomap::OccupancyOcTreeBase< NODE >::updateNode ( const OcTreeKey key,
float  log_odds_update,
bool  lazy_eval = false 
)
virtual

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

Implements octomap::AbstractOccupancyOcTree.

◆ updateNode() [3/6]

template<class NODE >
virtual NODE* octomap::OccupancyOcTreeBase< NODE >::updateNode ( const point3d value,
bool  occupied,
bool  lazy_eval = false 
)
virtual

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

Implements octomap::AbstractOccupancyOcTree.

◆ updateNode() [4/6]

template<class NODE >
virtual NODE* octomap::OccupancyOcTreeBase< NODE >::updateNode ( const point3d value,
float  log_odds_update,
bool  lazy_eval = false 
)
virtual

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

Implements octomap::AbstractOccupancyOcTree.

◆ updateNode() [5/6]

template<class NODE >
virtual NODE* octomap::OccupancyOcTreeBase< NODE >::updateNode ( double  x,
double  y,
double  z,
bool  occupied,
bool  lazy_eval = false 
)
virtual

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]

template<class NODE >
virtual NODE* octomap::OccupancyOcTreeBase< NODE >::updateNode ( double  x,
double  y,
double  z,
float  log_odds_update,
bool  lazy_eval = false 
)
virtual

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

template<class NODE >
virtual void octomap::OccupancyOcTreeBase< NODE >::updateNodeLogOdds ( NODE *  occupancyNode,
const float &  update 
) const
virtual

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

Reimplemented in octomap::OcTreeStamped.

◆ updateNodeRecurs()

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

◆ useBBXLimit()

template<class NODE >
void octomap::OccupancyOcTreeBase< NODE >::useBBXLimit ( bool  enable)
inline

use or ignore BBX limit (default: ignore)

Definition at line 334 of file OccupancyOcTreeBase.h.

◆ writeBinaryData()

template<class NODE >
std::ostream& octomap::OccupancyOcTreeBase< NODE >::writeBinaryData ( std::ostream &  s) const
virtual

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

Implements octomap::AbstractOccupancyOcTree.

◆ writeBinaryNode()

template<class NODE >
std::ostream& octomap::OccupancyOcTreeBase< NODE >::writeBinaryNode ( std::ostream &  s,
const NODE *  node 
) const

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

Member Data Documentation

◆ bbx_max

template<class NODE >
point3d octomap::OccupancyOcTreeBase< NODE >::bbx_max
protected

Definition at line 493 of file OccupancyOcTreeBase.h.

◆ bbx_max_key

template<class NODE >
OcTreeKey octomap::OccupancyOcTreeBase< NODE >::bbx_max_key
protected

Definition at line 495 of file OccupancyOcTreeBase.h.

◆ bbx_min

template<class NODE >
point3d octomap::OccupancyOcTreeBase< NODE >::bbx_min
protected

Definition at line 492 of file OccupancyOcTreeBase.h.

◆ bbx_min_key

template<class NODE >
OcTreeKey octomap::OccupancyOcTreeBase< NODE >::bbx_min_key
protected

Definition at line 494 of file OccupancyOcTreeBase.h.

◆ changed_keys

template<class NODE >
KeyBoolMap octomap::OccupancyOcTreeBase< NODE >::changed_keys
protected

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

Definition at line 499 of file OccupancyOcTreeBase.h.

◆ use_bbx_limit

template<class NODE >
bool octomap::OccupancyOcTreeBase< NODE >::use_bbx_limit
protected

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

Definition at line 491 of file OccupancyOcTreeBase.h.

◆ use_change_detection

template<class NODE >
bool octomap::OccupancyOcTreeBase< NODE >::use_change_detection
protected

Definition at line 497 of file OccupancyOcTreeBase.h.


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


octomap
Author(s): Kai M. Wurm , Armin Hornung
autogenerated on Wed Apr 3 2024 02:40:59