Public Member Functions | Protected Member Functions | Protected Attributes | Static Protected Attributes | List of all members
octomap::AbstractOccupancyOcTree Class Referenceabstract

#include <AbstractOccupancyOcTree.h>

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

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 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)
 
virtual std::istream & readBinaryData (std::istream &s)=0
 Reads the actual data, implemented in OccupancyOcTreeBase::readBinaryData() More...
 
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...
 
virtual void toMaxLikelihood ()=0
 
virtual OcTreeNodeupdateNode (const OcTreeKey &key, bool occupied, bool lazy_eval=false)=0
 
virtual OcTreeNodeupdateNode (const OcTreeKey &key, float log_odds_update, bool lazy_eval=false)=0
 
virtual OcTreeNodeupdateNode (const point3d &value, bool occupied, bool lazy_eval=false)=0
 
virtual OcTreeNodeupdateNode (const point3d &value, float log_odds_update, 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() More...
 
virtual ~AbstractOccupancyOcTree ()
 
- Public Member Functions inherited from octomap::AbstractOcTree
 AbstractOcTree ()
 
virtual void clear ()=0
 
virtual AbstractOcTreecreate () const =0
 virtual constructor: creates a new object of same type More...
 
virtual void expand ()=0
 
virtual void getMetricMax (double &x, double &y, double &z) const =0
 
virtual void getMetricMax (double &x, double &y, double &z)=0
 
virtual void getMetricMin (double &x, double &y, double &z) const =0
 
virtual void getMetricMin (double &x, double &y, double &z)=0
 
virtual void getMetricSize (double &x, double &y, double &z)=0
 
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 void prune ()=0
 
virtual std::istream & readData (std::istream &s)=0
 
virtual void setResolution (double res)=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 std::ostream & writeData (std::ostream &s) const =0
 
virtual ~AbstractOcTree ()
 

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

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"
 
- Static Protected Attributes inherited from octomap::AbstractOcTree
static const std::string fileHeader = "# Octomap OcTree file"
 

Additional Inherited Members

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

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

◆ AbstractOccupancyOcTree()

octomap::AbstractOccupancyOcTree::AbstractOccupancyOcTree ( )

Definition at line 40 of file AbstractOccupancyOcTree.cpp.

◆ ~AbstractOccupancyOcTree()

virtual octomap::AbstractOccupancyOcTree::~AbstractOccupancyOcTree ( )
inlinevirtual

Definition at line 55 of file AbstractOccupancyOcTree.h.

Member Function Documentation

◆ getClampingThresMax()

double octomap::AbstractOccupancyOcTree::getClampingThresMax ( ) const
inline
Returns
maximum threshold for occupancy clamping in the sensor model (probability)

Definition at line 217 of file AbstractOccupancyOcTree.h.

◆ getClampingThresMaxLog()

float octomap::AbstractOccupancyOcTree::getClampingThresMaxLog ( ) const
inline
Returns
maximum threshold for occupancy clamping in the sensor model (logodds)

Definition at line 219 of file AbstractOccupancyOcTree.h.

◆ getClampingThresMin()

double octomap::AbstractOccupancyOcTree::getClampingThresMin ( ) const
inline
Returns
minimum threshold for occupancy clamping in the sensor model (probability)

Definition at line 213 of file AbstractOccupancyOcTree.h.

◆ getClampingThresMinLog()

float octomap::AbstractOccupancyOcTree::getClampingThresMinLog ( ) const
inline
Returns
minimum threshold for occupancy clamping in the sensor model (logodds)

Definition at line 215 of file AbstractOccupancyOcTree.h.

◆ getOccupancyThres()

double octomap::AbstractOccupancyOcTree::getOccupancyThres ( ) const
inline
Returns
threshold (probability) for occupancy - sensor model

Definition at line 199 of file AbstractOccupancyOcTree.h.

◆ getOccupancyThresLog()

float octomap::AbstractOccupancyOcTree::getOccupancyThresLog ( ) const
inline
Returns
threshold (logodds) for occupancy - sensor model

Definition at line 201 of file AbstractOccupancyOcTree.h.

◆ getProbHit()

double octomap::AbstractOccupancyOcTree::getProbHit ( ) const
inline
Returns
probability for a "hit" in the sensor model (probability)

Definition at line 204 of file AbstractOccupancyOcTree.h.

◆ getProbHitLog()

float octomap::AbstractOccupancyOcTree::getProbHitLog ( ) const
inline
Returns
probability for a "hit" in the sensor model (logodds)

Definition at line 206 of file AbstractOccupancyOcTree.h.

◆ getProbMiss()

double octomap::AbstractOccupancyOcTree::getProbMiss ( ) const
inline
Returns
probability for a "miss" in the sensor model (probability)

Definition at line 208 of file AbstractOccupancyOcTree.h.

◆ getProbMissLog()

float octomap::AbstractOccupancyOcTree::getProbMissLog ( ) const
inline
Returns
probability for a "miss" in the sensor model (logodds)

Definition at line 210 of file AbstractOccupancyOcTree.h.

◆ isNodeAtThreshold() [1/2]

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.

◆ isNodeAtThreshold() [2/2]

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.

◆ isNodeOccupied() [1/2]

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.

◆ isNodeOccupied() [2/2]

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.

◆ readBinary() [1/2]

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.

◆ readBinary() [2/2]

bool octomap::AbstractOccupancyOcTree::readBinary ( std::istream &  s)

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.

◆ readBinaryData()

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

◆ readBinaryLegacyHeader()

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.

◆ setClampingThresMax()

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

sets the maximum threshold for occupancy clamping (sensor model)

Definition at line 196 of file AbstractOccupancyOcTree.h.

◆ setClampingThresMin()

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

sets the minimum threshold for occupancy clamping (sensor model)

Definition at line 194 of file AbstractOccupancyOcTree.h.

◆ setOccupancyThres()

void octomap::AbstractOccupancyOcTree::setOccupancyThres ( double  prob)
inline

sets the threshold for occupancy (sensor model)

Definition at line 188 of file AbstractOccupancyOcTree.h.

◆ setProbHit()

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.

◆ setProbMiss()

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.

◆ toMaxLikelihood()

virtual void octomap::AbstractOccupancyOcTree::toMaxLikelihood ( )
pure virtual

◆ updateNode() [1/4]

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 >, octomap::OccupancyOcTreeBase< ColorOcTreeNode >, octomap::OccupancyOcTreeBase< OcTreeNode >, and octomap::OccupancyOcTreeBase< OcTreeNodeStamped >.

◆ updateNode() [2/4]

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 >, octomap::OccupancyOcTreeBase< ColorOcTreeNode >, octomap::OccupancyOcTreeBase< OcTreeNode >, and octomap::OccupancyOcTreeBase< OcTreeNodeStamped >.

◆ updateNode() [3/4]

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 >, octomap::OccupancyOcTreeBase< ColorOcTreeNode >, octomap::OccupancyOcTreeBase< OcTreeNode >, and octomap::OccupancyOcTreeBase< OcTreeNodeStamped >.

◆ updateNode() [4/4]

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 >, octomap::OccupancyOcTreeBase< ColorOcTreeNode >, octomap::OccupancyOcTreeBase< OcTreeNode >, and octomap::OccupancyOcTreeBase< OcTreeNodeStamped >.

◆ writeBinary() [1/2]

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.

◆ writeBinary() [2/2]

bool octomap::AbstractOccupancyOcTree::writeBinary ( std::ostream &  s)

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.

◆ writeBinaryConst() [1/2]

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.

◆ writeBinaryConst() [2/2]

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.

◆ writeBinaryData()

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

Member Data Documentation

◆ binaryFileHeader

const std::string octomap::AbstractOccupancyOcTree::binaryFileHeader = "# Octomap OcTree binary file"
staticprotected

Definition at line 235 of file AbstractOccupancyOcTree.h.

◆ clamping_thres_max

float octomap::AbstractOccupancyOcTree::clamping_thres_max
protected

Definition at line 230 of file AbstractOccupancyOcTree.h.

◆ clamping_thres_min

float octomap::AbstractOccupancyOcTree::clamping_thres_min
protected

Definition at line 229 of file AbstractOccupancyOcTree.h.

◆ occ_prob_thres_log

float octomap::AbstractOccupancyOcTree::occ_prob_thres_log
protected

Definition at line 233 of file AbstractOccupancyOcTree.h.

◆ prob_hit_log

float octomap::AbstractOccupancyOcTree::prob_hit_log
protected

Definition at line 231 of file AbstractOccupancyOcTree.h.

◆ prob_miss_log

float octomap::AbstractOccupancyOcTree::prob_miss_log
protected

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 Wed Apr 3 2024 02:40:59