Public Member Functions | Protected Member Functions | Protected Attributes | Static Protected Attributes
octomap::AbstractOccupancyOcTree Class Reference

#include <AbstractOccupancyOcTree.h>

Inheritance diagram for octomap::AbstractOccupancyOcTree:
Inheritance graph
[legend]

List of all members.

Public Member Functions

 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
bool isNodeAtThreshold (const OcTreeNode &occupancyNode) const
 queries whether a node is at the clamping threshold according to the tree's parameter
bool isNodeOccupied (const OcTreeNode *occupancyNode) const
 queries whether a node is occupied according to the tree's parameter for "occupancy"
bool isNodeOccupied (const OcTreeNode &occupancyNode) const
 queries whether a node is occupied according to the tree's parameter for "occupancy"
bool readBinary (std::istream &s)
bool readBinary (const std::string &filename)
virtual std::istream & readBinaryData (std::istream &s)=0
 Reads the actual data, implemented in OccupancyOcTreeBase::readBinaryData()
void setClampingThresMax (double thresProb)
 sets the maximum threshold for occupancy clamping (sensor model)
void setClampingThresMin (double thresProb)
 sets the minimum threshold for occupancy clamping (sensor model)
void setOccupancyThres (double prob)
 sets the threshold for occupancy (sensor model)
void setProbHit (double prob)
 sets the probability for a "hit" (will be converted to logodds) - sensor model
void setProbMiss (double prob)
 sets the probability for a "miss" (will be converted to logodds) - sensor model
virtual void toMaxLikelihood ()=0
virtual OcTreeNodeupdateNode (const OcTreeKey &key, float log_odds_update, bool lazy_eval=false)=0
virtual OcTreeNodeupdateNode (const point3d &value, float log_odds_update, bool lazy_eval=false)=0
virtual OcTreeNodeupdateNode (const OcTreeKey &key, bool occupied, bool lazy_eval=false)=0
virtual OcTreeNodeupdateNode (const point3d &value, bool occupied, bool lazy_eval=false)=0
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 std::ostream & writeBinaryData (std::ostream &s) const =0
 Writes the actual data, implemented in OccupancyOcTreeBase::writeBinaryData()
virtual ~AbstractOccupancyOcTree ()

Protected Member Functions

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.

Protected Attributes

float clamping_thres_max
float clamping_thres_min
float occ_prob_thres_log
float prob_hit_log
float prob_miss_log

Static Protected Attributes

static const std::string binaryFileHeader = "# Octomap OcTree binary file"

Detailed Description

Interface class for all octree types that store occupancy. This serves as a common base class e.g. for polymorphism and contains common code for reading and writing binary trees.

Definition at line 52 of file AbstractOccupancyOcTree.h.


Constructor & Destructor Documentation

Definition at line 40 of file AbstractOccupancyOcTree.cpp.

Definition at line 55 of file AbstractOccupancyOcTree.h.


Member Function Documentation

Returns:
maximum threshold for occupancy clamping in the sensor model (probability)

Definition at line 217 of file AbstractOccupancyOcTree.h.

Returns:
maximum threshold for occupancy clamping in the sensor model (logodds)

Definition at line 219 of file AbstractOccupancyOcTree.h.

Returns:
minimum threshold for occupancy clamping in the sensor model (probability)

Definition at line 213 of file AbstractOccupancyOcTree.h.

Returns:
minimum threshold for occupancy clamping in the sensor model (logodds)

Definition at line 215 of file AbstractOccupancyOcTree.h.

Returns:
threshold (probability) for occupancy - sensor model

Definition at line 199 of file AbstractOccupancyOcTree.h.

Returns:
threshold (logodds) for occupancy - sensor model

Definition at line 201 of file AbstractOccupancyOcTree.h.

Returns:
probability for a "hit" in the sensor model (probability)

Definition at line 204 of file AbstractOccupancyOcTree.h.

Returns:
probability for a "hit" in the sensor model (logodds)

Definition at line 206 of file AbstractOccupancyOcTree.h.

Returns:
probability for a "miss" in the sensor model (probability)

Definition at line 208 of file AbstractOccupancyOcTree.h.

Returns:
probability for a "miss" in the sensor model (logodds)

Definition at line 210 of file AbstractOccupancyOcTree.h.

bool octomap::AbstractOccupancyOcTree::isNodeAtThreshold ( const OcTreeNode occupancyNode) const [inline]

queries whether a node is at the clamping threshold according to the tree's parameter

Definition at line 124 of file AbstractOccupancyOcTree.h.

bool octomap::AbstractOccupancyOcTree::isNodeAtThreshold ( const OcTreeNode occupancyNode) const [inline]

queries whether a node is at the clamping threshold according to the tree's parameter

Definition at line 130 of file AbstractOccupancyOcTree.h.

bool octomap::AbstractOccupancyOcTree::isNodeOccupied ( const OcTreeNode occupancyNode) const [inline]

queries whether a node is occupied according to the tree's parameter for "occupancy"

Definition at line 114 of file AbstractOccupancyOcTree.h.

bool octomap::AbstractOccupancyOcTree::isNodeOccupied ( const OcTreeNode occupancyNode) const [inline]

queries whether a node is occupied according to the tree's parameter for "occupancy"

Definition at line 119 of file AbstractOccupancyOcTree.h.

Reads an OcTree from an input stream. Existing nodes of the tree are deleted before the tree is read.

Returns:
success of operation

Definition at line 135 of file AbstractOccupancyOcTree.cpp.

bool octomap::AbstractOccupancyOcTree::readBinary ( const std::string &  filename)

Reads OcTree from a binary file. Existing nodes of the tree are deleted before the tree is read.

Returns:
success of operation

Definition at line 126 of file AbstractOccupancyOcTree.cpp.

virtual std::istream& octomap::AbstractOccupancyOcTree::readBinaryData ( std::istream &  s) [pure virtual]

Reads the actual data, implemented in OccupancyOcTreeBase::readBinaryData()

Implemented in octomap::OccupancyOcTreeBase< NODE >.

bool octomap::AbstractOccupancyOcTree::readBinaryLegacyHeader ( std::istream &  s,
unsigned int &  size,
double &  res 
) [protected]

Try to read the old binary format for conversion, will be removed in the future.

Definition at line 98 of file AbstractOccupancyOcTree.cpp.

void octomap::AbstractOccupancyOcTree::setClampingThresMax ( double  thresProb) [inline]

sets the maximum threshold for occupancy clamping (sensor model)

Definition at line 196 of file AbstractOccupancyOcTree.h.

void octomap::AbstractOccupancyOcTree::setClampingThresMin ( double  thresProb) [inline]

sets the minimum threshold for occupancy clamping (sensor model)

Definition at line 194 of file AbstractOccupancyOcTree.h.

sets the threshold for occupancy (sensor model)

Definition at line 188 of file AbstractOccupancyOcTree.h.

void octomap::AbstractOccupancyOcTree::setProbHit ( double  prob) [inline]

sets the probability for a "hit" (will be converted to logodds) - sensor model

Definition at line 190 of file AbstractOccupancyOcTree.h.

void octomap::AbstractOccupancyOcTree::setProbMiss ( double  prob) [inline]

sets the probability for a "miss" (will be converted to logodds) - sensor model

Definition at line 192 of file AbstractOccupancyOcTree.h.

virtual void octomap::AbstractOccupancyOcTree::toMaxLikelihood ( ) [pure virtual]
virtual OcTreeNode* octomap::AbstractOccupancyOcTree::updateNode ( const OcTreeKey key,
float  log_odds_update,
bool  lazy_eval = false 
) [pure virtual]

Manipulate log_odds value of voxel directly

Parameters:
keyof 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

Implemented in octomap::OccupancyOcTreeBase< NODE >.

virtual OcTreeNode* octomap::AbstractOccupancyOcTree::updateNode ( const point3d value,
float  log_odds_update,
bool  lazy_eval = false 
) [pure virtual]

Manipulate log_odds value of voxel directly. 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
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

Implemented in octomap::OccupancyOcTreeBase< NODE >.

virtual OcTreeNode* octomap::AbstractOccupancyOcTree::updateNode ( const OcTreeKey key,
bool  occupied,
bool  lazy_eval = false 
) [pure virtual]

Integrate occupancy measurement.

Parameters:
keyof 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

Implemented in octomap::OccupancyOcTreeBase< NODE >.

virtual OcTreeNode* octomap::AbstractOccupancyOcTree::updateNode ( const point3d value,
bool  occupied,
bool  lazy_eval = false 
) [pure 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

Implemented in octomap::OccupancyOcTreeBase< NODE >.

bool octomap::AbstractOccupancyOcTree::writeBinary ( const std::string &  filename)

Writes OcTree to a binary file using writeBinary(). The OcTree is first converted to the maximum likelihood estimate and pruned.

Returns:
success of operation

Definition at line 50 of file AbstractOccupancyOcTree.cpp.

Writes compressed maximum likelihood OcTree to a binary stream. The OcTree is first converted to the maximum likelihood estimate and pruned for maximum compression.

Returns:
success of operation

Definition at line 72 of file AbstractOccupancyOcTree.cpp.

bool octomap::AbstractOccupancyOcTree::writeBinaryConst ( const std::string &  filename) const

Writes OcTree to a binary file using writeBinaryConst(). The OcTree is not changed, in particular not pruned first. Files will be smaller when the tree is pruned first or by using writeBinary() instead.

Returns:
success of operation

Definition at line 60 of file AbstractOccupancyOcTree.cpp.

bool octomap::AbstractOccupancyOcTree::writeBinaryConst ( std::ostream &  s) const

Writes the maximum likelihood OcTree to a binary stream (const variant). Files will be smaller when the tree is pruned first or by using writeBinary() instead.

Returns:
success of operation

Definition at line 79 of file AbstractOccupancyOcTree.cpp.

virtual std::ostream& octomap::AbstractOccupancyOcTree::writeBinaryData ( std::ostream &  s) const [pure virtual]

Writes the actual data, implemented in OccupancyOcTreeBase::writeBinaryData()

Implemented in octomap::OccupancyOcTreeBase< NODE >.


Member Data Documentation

const std::string octomap::AbstractOccupancyOcTree::binaryFileHeader = "# Octomap OcTree binary file" [static, protected]

Definition at line 235 of file AbstractOccupancyOcTree.h.

Definition at line 230 of file AbstractOccupancyOcTree.h.

Definition at line 229 of file AbstractOccupancyOcTree.h.

Definition at line 233 of file AbstractOccupancyOcTree.h.

Definition at line 231 of file AbstractOccupancyOcTree.h.

Definition at line 232 of file AbstractOccupancyOcTree.h.


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


octomap
Author(s): Kai M. Wurm , Armin Hornung
autogenerated on Thu Aug 27 2015 14:13:14