Public Member Functions | Protected Member Functions | Protected Attributes
octomap::OccupancyOcTreeBase< NODE > Class Template Reference

#include <OccupancyOcTreeBase.h>

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

List of all members.

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 ()
KeyBoolMap::const_iterator changedKeysEnd ()
 Iterator to traverse all keys of changed nodes.
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)
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 point3d &p) const
bool inBBX (const OcTreeKey &key) 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
virtual void integrateMiss (NODE *occupancyNode) const
 integrate a "miss" measurement according to the tree's sensor model
virtual void nodeToMaxLikelihood (NODE *occupancyNode) const
 converts the node to the maximum likelihood value according to the tree's parameter for "occupancy"
virtual void nodeToMaxLikelihood (NODE &occupancyNode) const
 converts the node to the maximum likelihood value according to the tree's parameter for "occupancy"
 OccupancyOcTreeBase (double resolution)
 Default constructor, sets resolution of leafs.
 OccupancyOcTreeBase (const OccupancyOcTreeBase< NODE > &rhs)
 Copy constructor.
 OCTOMAP_DEPRECATED (virtual void insertScan(const Pointcloud &scan, const octomap::point3d &sensor_origin, double maxrange=-1., bool pruning=true, bool lazy_eval=false))
 OCTOMAP_DEPRECATED (virtual void insertScan(const Pointcloud &scan, const point3d &sensor_origin, const pose6d &frame_origin, double maxrange=-1., bool pruning=true, bool lazy_eval=false))
 OCTOMAP_DEPRECATED (virtual void insertScan(const ScanNode &scan, double maxrange=-1., bool pruning=true, bool lazy_eval=false))
 OCTOMAP_DEPRECATED (virtual void insertScanNaive(const Pointcloud &scan, const point3d &sensor_origin, double maxrange, bool lazy_eval=false))
std::istream & readBinaryData (std::istream &s)
std::istream & readBinaryNode (std::istream &s, NODE *node) const
void resetChangeDetection ()
 Reset the set of changed keys. Call this after you obtained all changed nodes.
void setBBXMax (point3d &max)
 sets the maximum for a query bounding box to use
void setBBXMin (point3d &min)
 sets the minimum for a query bounding box to use
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, float log_odds_update, 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, float log_odds_update, bool lazy_eval=false)
virtual NODE * updateNode (const OcTreeKey &key, bool occupied, bool lazy_eval=false)
virtual NODE * updateNode (const point3d &value, bool occupied, bool lazy_eval=false)
virtual NODE * updateNode (double x, double y, double z, bool occupied, bool lazy_eval=false)
virtual void updateNodeLogOdds (NODE *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)
std::ostream & writeBinaryData (std::ostream &s) const
std::ostream & writeBinaryNode (std::ostream &s, const NODE *node) const
virtual ~OccupancyOcTreeBase ()

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 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.
bool use_bbx_limit
 use bounding box for queries (needs to be set)?
bool use_change_detection

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

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

Default constructor, sets resolution of leafs.

template<class NODE>
virtual octomap::OccupancyOcTreeBase< NODE >::~OccupancyOcTreeBase ( ) [virtual]
template<class NODE>
octomap::OccupancyOcTreeBase< NODE >::OccupancyOcTreeBase ( const OccupancyOcTreeBase< NODE > &  rhs)

Copy constructor.

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

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

Definition at line 359 of file OccupancyOcTreeBase.h.

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.
template<class NODE>
KeyBoolMap::const_iterator octomap::OccupancyOcTreeBase< NODE >::changedKeysBegin ( ) [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 386 of file OccupancyOcTreeBase.h.

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

Iterator to traverse all keys of changed nodes.

Definition at line 389 of file OccupancyOcTreeBase.h.

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)
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)
template<class NODE>
void octomap::OccupancyOcTreeBase< NODE >::enableChangeDetection ( bool  enable) [inline]

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

Definition at line 377 of file OccupancyOcTreeBase.h.

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

Definition at line 367 of file OccupancyOcTreeBase.h.

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

Definition at line 365 of file OccupancyOcTreeBase.h.

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 retreive the normal of the triangles that fall in the cube formed by the voxels located at the vertex of a given voxel.

Parameters:
[in]voxelfor which retreive the normals
[out]trianglesnormals
[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.
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.
template<class NODE>
bool octomap::OccupancyOcTreeBase< NODE >::inBBX ( const point3d p) const
Returns:
true if point is in the currently set bounding box
template<class NODE>
bool octomap::OccupancyOcTreeBase< NODE >::inBBX ( const OcTreeKey key) const
Returns:
true if key is in the currently set bounding box
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.*
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.*
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.
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.
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
template<class NODE>
virtual void octomap::OccupancyOcTreeBase< NODE >::integrateHit ( NODE *  occupancyNode) const [virtual]

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

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

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

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

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

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"

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"

template<class NODE>
octomap::OccupancyOcTreeBase< NODE >::OCTOMAP_DEPRECATED ( virtual void   insertScanconst Pointcloud &scan, const octomap::point3d &sensor_origin,double maxrange=-1., bool pruning=true, bool lazy_eval=false) [inline]
Note:
Deprecated, use insertPointCloud() instead. pruning is now done automatically.

Definition at line 135 of file OccupancyOcTreeBase.h.

template<class NODE>
octomap::OccupancyOcTreeBase< NODE >::OCTOMAP_DEPRECATED ( virtual void   insertScanconst Pointcloud &scan, const point3d &sensor_origin,const pose6d &frame_origin, double maxrange=-1., bool pruning=true, bool lazy_eval=false) [inline]
Note:
Deprecated, use insertPointCloud() instead. pruning is now done automatically.

Definition at line 142 of file OccupancyOcTreeBase.h.

template<class NODE>
octomap::OccupancyOcTreeBase< NODE >::OCTOMAP_DEPRECATED ( virtual void   insertScanconst ScanNode &scan, double maxrange=-1., bool pruning=true, bool lazy_eval=false) [inline]
Note:
Deprecated, use insertPointCloud() instead. pruning is now done automatically.

Definition at line 149 of file OccupancyOcTreeBase.h.

template<class NODE>
octomap::OccupancyOcTreeBase< NODE >::OCTOMAP_DEPRECATED ( virtual void   insertScanNaiveconst Pointcloud &scan, const point3d &sensor_origin, double maxrange, bool lazy_eval=false) [inline]
Note:
Deprecated, use insertPointCloudRays instead. pruning is now done automatically.

Definition at line 154 of file OccupancyOcTreeBase.h.

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.

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

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.

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 379 of file OccupancyOcTreeBase.h.

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

sets the maximum for a query bounding box to use

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

sets the minimum for a query bounding box to use

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_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
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_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
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_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
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]
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.

template<class NODE>
void octomap::OccupancyOcTreeBase< NODE >::toMaxLikelihoodRecurs ( NODE *  node,
unsigned int  depth,
unsigned int  max_depth 
) [protected]
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.

Reimplemented in octomap::ColorOcTree.

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

Reimplemented in octomap::ColorOcTree.

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.

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.

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

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.

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

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]
template<class NODE>
void octomap::OccupancyOcTreeBase< NODE >::useBBXLimit ( bool  enable) [inline]

use or ignore BBX limit (default: ignore)

Definition at line 358 of file OccupancyOcTreeBase.h.

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.

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

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

Definition at line 513 of file OccupancyOcTreeBase.h.

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

Definition at line 515 of file OccupancyOcTreeBase.h.

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

Definition at line 512 of file OccupancyOcTreeBase.h.

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

Definition at line 514 of file OccupancyOcTreeBase.h.

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

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

Definition at line 519 of file OccupancyOcTreeBase.h.

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

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

Definition at line 511 of file OccupancyOcTreeBase.h.

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

Definition at line 517 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 Thu Feb 11 2016 23:50:59