octomap  1.9.7
octomap::OcTreeNode Class Reference

Nodes to be used in OcTree. More...

+ Inheritance diagram for octomap::OcTreeNode:
+ Collaboration diagram for octomap::OcTreeNode:

Public Types

typedef float DataType
 Make the templated data type available from the outside. More...
 

Public Member Functions

void addValue (const float &p)
 adds p to the node's logOdds value (with no boundary / threshold checking!) More...
 
void copyData (const OcTreeDataNode &from)
 Copy the payload (data in "value") from rhs into this node Opposed to copy ctor, this does not clone the children as well. More...
 
float getLogOdds () const
 
float getMaxChildLogOdds () const
 
double getMeanChildLogOdds () const
 
double getOccupancy () const
 
float getValue () const
 
 OCTOMAP_DEPRECATED (bool childExists(unsigned int i) const)
 Test whether the i-th child exists. More...
 
 OCTOMAP_DEPRECATED (bool hasChildren() const)
 
 OcTreeNode ()
 
bool operator== (const OcTreeDataNode &rhs) const
 Equals operator, compares if the stored value is identical. More...
 
std::istream & readData (std::istream &s)
 Read node payload (data only) from binary stream. More...
 
void setLogOdds (float l)
 sets log odds occupancy of node More...
 
void setValue (float v)
 sets value to be stored in the node More...
 
void updateOccupancyChildren ()
 update this node's occupancy according to its children's maximum occupancy More...
 
std::ostream & writeData (std::ostream &s) const
 Write node payload (data only) to binary stream. More...
 
 ~OcTreeNode ()
 

Protected Member Functions

void allocChildren ()
 

Protected Attributes

AbstractOcTreeNode ** children
 pointer to array of children, may be NULL More...
 
float value
 stored data (payload) More...
 

Detailed Description

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.

Member Typedef Documentation

◆ DataType

typedef float octomap::OcTreeDataNode< float >::DataType
inherited

Make the templated data type available from the outside.

Constructor & Destructor Documentation

◆ OcTreeNode()

octomap::OcTreeNode::OcTreeNode ( )

◆ ~OcTreeNode()

octomap::OcTreeNode::~OcTreeNode ( )

Member Function Documentation

◆ addValue()

void octomap::OcTreeNode::addValue ( const float &  p)

adds p to the node's logOdds value (with no boundary / threshold checking!)

References octomap::OcTreeDataNode< float >::value.

◆ allocChildren()

void octomap::OcTreeDataNode< float >::allocChildren
protectedinherited

◆ copyData()

void octomap::OcTreeDataNode< float >::copyData ( const OcTreeDataNode< float > &  from)
inherited

Copy the payload (data in "value") from rhs into this node Opposed to copy ctor, this does not clone the children as well.

◆ getLogOdds()

float octomap::OcTreeNode::getLogOdds ( ) const
inline

◆ getMaxChildLogOdds()

float octomap::OcTreeNode::getMaxChildLogOdds ( ) const
Returns
maximum of children's occupancy probabilities, in log odds

References octomap::OcTreeDataNode< float >::children, and getLogOdds().

Referenced by octomap::OcTreeNodeStamped::updateOccupancyChildren(), and updateOccupancyChildren().

◆ getMeanChildLogOdds()

double octomap::OcTreeNode::getMeanChildLogOdds ( ) const
Returns
mean of all children's occupancy probabilities, in log odds

References octomap::OcTreeDataNode< float >::children, and getOccupancy().

◆ getOccupancy()

double octomap::OcTreeNode::getOccupancy ( ) const
inline

◆ getValue()

float octomap::OcTreeDataNode< float >::getValue ( ) const
inlineinherited
Returns
value stored in the node

◆ OCTOMAP_DEPRECATED() [1/2]

octomap::OcTreeDataNode< float >::OCTOMAP_DEPRECATED ( bool childExists(unsigned int i) const  )
inherited

Test whether the i-th child exists.

Returns
true if the i-th child exists

◆ OCTOMAP_DEPRECATED() [2/2]

octomap::OcTreeDataNode< float >::OCTOMAP_DEPRECATED ( bool hasChildren() const  )
inherited
Returns
true if the node has at least one child

◆ operator==()

bool octomap::OcTreeDataNode< float >::operator== ( const OcTreeDataNode< float > &  rhs) const
inherited

Equals operator, compares if the stored value is identical.

◆ readData()

std::istream & octomap::OcTreeDataNode< float >::readData ( std::istream &  s)
inherited

Read node payload (data only) from binary stream.

◆ setLogOdds()

void octomap::OcTreeNode::setLogOdds ( float  l)
inline

◆ setValue()

void octomap::OcTreeDataNode< float >::setValue ( v)
inlineinherited

sets value to be stored in the node

◆ updateOccupancyChildren()

void octomap::OcTreeNode::updateOccupancyChildren ( )
inline

update this node's occupancy according to its children's maximum occupancy

References getMaxChildLogOdds(), and setLogOdds().

Referenced by octomap::ColorOcTree::updateInnerOccupancyRecurs().

◆ writeData()

std::ostream & octomap::OcTreeDataNode< float >::writeData ( std::ostream &  s) const
inherited

Write node payload (data only) to binary stream.

Field Documentation

◆ children

AbstractOcTreeNode** octomap::OcTreeDataNode< float >::children
protectedinherited

pointer to array of children, may be NULL

Note
The tree class manages this pointer, the array, and the memory for it! The children of a node are always enforced to be the same type as the node

◆ value

float octomap::OcTreeDataNode< float >::value
protectedinherited

stored data (payload)


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