Go to the documentation of this file.
34 #ifndef OCTOMAP_ABSTRACT_OCCUPANCY_OCTREE_H
35 #define OCTOMAP_ABSTRACT_OCCUPANCY_OCTREE_H
115 return (occupancyNode->
getLogOdds() >= this->occ_prob_thres_log);
120 return (occupancyNode.
getLogOdds() >= this->occ_prob_thres_log);
125 return (occupancyNode->
getLogOdds() >= this->clamping_thres_max
126 || occupancyNode->
getLogOdds() <= this->clamping_thres_min);
131 return (occupancyNode.
getLogOdds() >= this->clamping_thres_max
132 || occupancyNode.
getLogOdds() <= this->clamping_thres_min);
void setProbMiss(double prob)
sets the probability for a "miss" (will be converted to logodds) - sensor model
Definition: AbstractOccupancyOcTree.h:192
bool writeBinaryConst(const std::string &filename) const
Writes OcTree to a binary file using writeBinaryConst().
Definition: AbstractOccupancyOcTree.cpp:60
virtual std::ostream & writeBinaryData(std::ostream &s) const =0
Writes the actual data, implemented in OccupancyOcTreeBase::writeBinaryData()
float getClampingThresMinLog() const
Definition: AbstractOccupancyOcTree.h:215
double getClampingThresMin() const
Definition: AbstractOccupancyOcTree.h:213
static const std::string binaryFileHeader
Definition: AbstractOccupancyOcTree.h:235
void setOccupancyThres(double prob)
sets the threshold for occupancy (sensor model)
Definition: AbstractOccupancyOcTree.h:188
double getOccupancyThres() const
Definition: AbstractOccupancyOcTree.h:199
AbstractOccupancyOcTree()
Definition: AbstractOccupancyOcTree.cpp:40
float clamping_thres_max
Definition: AbstractOccupancyOcTree.h:230
double probability(double logodds)
compute probability from logodds:
Definition: octomap_utils.h:47
float getLogOdds() const
Definition: OcTreeNode.h:68
bool readBinary(std::istream &s)
Reads an OcTree from an input stream.
Definition: AbstractOccupancyOcTree.cpp:135
virtual std::istream & readBinaryData(std::istream &s)=0
Reads the actual data, implemented in OccupancyOcTreeBase::readBinaryData()
This class represents a three-dimensional vector.
Definition: Vector3.h:50
float getOccupancyThresLog() const
Definition: AbstractOccupancyOcTree.h:201
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.
Definition: AbstractOccupancyOcTree.cpp:98
bool isNodeOccupied(const OcTreeNode *occupancyNode) const
queries whether a node is occupied according to the tree's parameter for "occupancy"
Definition: AbstractOccupancyOcTree.h:114
Nodes to be used in OcTree.
Definition: OcTreeNode.h:55
virtual ~AbstractOccupancyOcTree()
Definition: AbstractOccupancyOcTree.h:55
This abstract class is an interface to all octrees and provides a factory design pattern for readin a...
Definition: AbstractOcTree.h:50
void setClampingThresMin(double thresProb)
sets the minimum threshold for occupancy clamping (sensor model)
Definition: AbstractOccupancyOcTree.h:194
double getClampingThresMax() const
Definition: AbstractOccupancyOcTree.h:217
bool isNodeAtThreshold(const OcTreeNode *occupancyNode) const
queries whether a node is at the clamping threshold according to the tree's parameter
Definition: AbstractOccupancyOcTree.h:124
float occ_prob_thres_log
Definition: AbstractOccupancyOcTree.h:233
OcTreeKey is a container class for internal key addressing.
Definition: OcTreeKey.h:70
void setClampingThresMax(double thresProb)
sets the maximum threshold for occupancy clamping (sensor model)
Definition: AbstractOccupancyOcTree.h:196
void setProbHit(double prob)
sets the probability for a "hit" (will be converted to logodds) - sensor model
Definition: AbstractOccupancyOcTree.h:190
float getProbHitLog() const
Definition: AbstractOccupancyOcTree.h:206
double getProbHit() const
Definition: AbstractOccupancyOcTree.h:204
bool isNodeOccupied(const OcTreeNode &occupancyNode) const
queries whether a node is occupied according to the tree's parameter for "occupancy"
Definition: AbstractOccupancyOcTree.h:119
virtual size_t size() const =0
bool isNodeAtThreshold(const OcTreeNode &occupancyNode) const
queries whether a node is at the clamping threshold according to the tree's parameter
Definition: AbstractOccupancyOcTree.h:130
double getProbMiss() const
Definition: AbstractOccupancyOcTree.h:208
float logodds(double probability)
compute log-odds from probability:
Definition: octomap_utils.h:42
Interface class for all octree types that store occupancy.
Definition: AbstractOccupancyOcTree.h:52
float prob_hit_log
Definition: AbstractOccupancyOcTree.h:231
float clamping_thres_min
Definition: AbstractOccupancyOcTree.h:229
float getProbMissLog() const
Definition: AbstractOccupancyOcTree.h:210
Tables used by the Marching Cubes Algorithm The tables are from Paul Bourke's web page http://paulbou...
virtual void toMaxLikelihood()=0
virtual OcTreeNode * updateNode(const OcTreeKey &key, float log_odds_update, bool lazy_eval=false)=0
Manipulate log_odds value of voxel directly.
float getClampingThresMaxLog() const
Definition: AbstractOccupancyOcTree.h:219
float prob_miss_log
Definition: AbstractOccupancyOcTree.h:232
bool writeBinary(const std::string &filename)
Writes OcTree to a binary file using writeBinary().
Definition: AbstractOccupancyOcTree.cpp:50