Class AbstractOccupancyOcTree
Defined in File AbstractOccupancyOcTree.h
Inheritance Relationships
Base Type
public octomap::AbstractOcTree
(Class AbstractOcTree)
Derived Type
public octomap::OcTreeBaseImpl< NODE, AbstractOccupancyOcTree >
(Template Class OcTreeBaseImpl)
Class Documentation
-
class AbstractOccupancyOcTree : public octomap::AbstractOcTree
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.
Subclassed by octomap::OcTreeBaseImpl< NODE, AbstractOccupancyOcTree >
Public Functions
-
AbstractOccupancyOcTree()
-
inline virtual ~AbstractOccupancyOcTree()
-
bool 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
-
bool 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
-
bool 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
-
bool 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
-
virtual std::ostream &writeBinaryData(std::ostream &s) const = 0
Writes the actual data, implemented in OccupancyOcTreeBase::writeBinaryData()
-
bool 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
-
bool 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
-
virtual std::istream &readBinaryData(std::istream &s) = 0
Reads the actual data, implemented in OccupancyOcTreeBase::readBinaryData()
-
inline bool isNodeOccupied(const OcTreeNode *occupancyNode) const
queries whether a node is occupied according to the tree’s parameter for “occupancy”
-
inline bool isNodeOccupied(const OcTreeNode &occupancyNode) const
queries whether a node is occupied according to the tree’s parameter for “occupancy”
-
inline bool isNodeAtThreshold(const OcTreeNode *occupancyNode) const
queries whether a node is at the clamping threshold according to the tree’s parameter
-
inline bool isNodeAtThreshold(const OcTreeNode &occupancyNode) const
queries whether a node is at the clamping threshold according to the tree’s parameter
-
virtual OcTreeNode *updateNode(const OcTreeKey &key, float log_odds_update, bool lazy_eval = false) = 0
Manipulate log_odds value of voxel directly
- Parameters:
key – of the NODE that is to be updated
log_odds_update – value to be added (+) to log_odds value of node
lazy_eval – whether 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
-
virtual OcTreeNode *updateNode(const point3d &value, float log_odds_update, bool lazy_eval = false) = 0
Manipulate log_odds value of voxel directly. Looks up the OcTreeKey corresponding to the coordinate and then calls udpateNode() with it.
- Parameters:
value – 3d coordinate of the NODE that is to be updated
log_odds_update – value to be added (+) to log_odds value of node
lazy_eval – whether 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
-
virtual OcTreeNode *updateNode(const OcTreeKey &key, bool occupied, bool lazy_eval = false) = 0
Integrate occupancy measurement.
- Parameters:
key – of the NODE that is to be updated
occupied – true if the node was measured occupied, else false
lazy_eval – whether 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
-
virtual OcTreeNode *updateNode(const point3d &value, bool occupied, bool lazy_eval = false) = 0
Integrate occupancy measurement. Looks up the OcTreeKey corresponding to the coordinate and then calls udpateNode() with it.
- Parameters:
value – 3d coordinate of the NODE that is to be updated
occupied – true if the node was measured occupied, else false
lazy_eval – whether 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
-
virtual void toMaxLikelihood() = 0
-
inline void setOccupancyThres(double prob)
sets the threshold for occupancy (sensor model)
-
inline void setProbHit(double prob)
sets the probability for a “hit” (will be converted to logodds) - sensor model
-
inline void setProbMiss(double prob)
sets the probability for a “miss” (will be converted to logodds) - sensor model
-
inline void setClampingThresMin(double thresProb)
sets the minimum threshold for occupancy clamping (sensor model)
-
inline void setClampingThresMax(double thresProb)
sets the maximum threshold for occupancy clamping (sensor model)
-
inline double getOccupancyThres() const
- Returns:
threshold (probability) for occupancy - sensor model
-
inline float getOccupancyThresLog() const
- Returns:
threshold (logodds) for occupancy - sensor model
-
inline double getProbHit() const
- Returns:
probability for a “hit” in the sensor model (probability)
-
inline float getProbHitLog() const
- Returns:
probability for a “hit” in the sensor model (logodds)
-
inline double getProbMiss() const
- Returns:
probability for a “miss” in the sensor model (probability)
-
inline float getProbMissLog() const
- Returns:
probability for a “miss” in the sensor model (logodds)
-
inline double getClampingThresMin() const
- Returns:
minimum threshold for occupancy clamping in the sensor model (probability)
-
inline float getClampingThresMinLog() const
- Returns:
minimum threshold for occupancy clamping in the sensor model (logodds)
-
inline double getClampingThresMax() const
- Returns:
maximum threshold for occupancy clamping in the sensor model (probability)
-
inline float getClampingThresMaxLog() const
- Returns:
maximum threshold for occupancy clamping in the sensor model (logodds)
Protected 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_min
-
float clamping_thres_max
-
float prob_hit_log
-
float prob_miss_log
-
float occ_prob_thres_log
Protected Static Attributes
-
static const std::string binaryFileHeader
-
AbstractOccupancyOcTree()