Class OcTreeNode
Defined in File OcTreeNode.h
Inheritance Relationships
Base Type
public octomap::OcTreeDataNode< float >
(Template Class OcTreeDataNode)
Derived Types
public octomap::ColorOcTreeNode
(Class ColorOcTreeNode)public octomap::OcTreeNodeStamped
(Class OcTreeNodeStamped)
Class Documentation
-
class OcTreeNode : public octomap::OcTreeDataNode<float>
Nodes to be used in OcTree. They represent 3d occupancy grid cells. “value” stores their log-odds occupancy.
Note: If you derive a class (directly or indirectly) from OcTreeNode or OcTreeDataNode, you have to implement (at least) the following functions: createChild(), getChild(), getChild() const, expandNode() to avoid slicing errors and memory-related bugs. See ColorOcTreeNode in ColorOcTree.h for an example.
Subclassed by octomap::ColorOcTreeNode, octomap::OcTreeNodeStamped
Public Functions
-
OcTreeNode()
-
~OcTreeNode()
-
inline double getOccupancy() const
- Returns:
occupancy probability of node
-
inline float getLogOdds() const
- Returns:
log odds representation of occupancy probability of node
-
inline void setLogOdds(float l)
sets log odds occupancy of node
-
double getMeanChildLogOdds() const
- Returns:
mean of all children’s occupancy probabilities, in log odds
-
float getMaxChildLogOdds() const
- Returns:
maximum of children’s occupancy probabilities, in log odds
-
inline void updateOccupancyChildren()
update this node’s occupancy according to its children’s maximum occupancy
-
void addValue(const float &p)
adds p to the node’s logOdds value (with no boundary / threshold checking!)
-
OcTreeNode()