octomap 1.5.0
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.

Public Member Functions

void addValue (const float &p)
 adds p to the node's logOdds value (with no boundary / threshold checking!)
bool childExists (unsigned int i) const
bool collapsible () const
 A node is collapsible if all children exist, don't have children of their own and have the same occupancy value.
bool createChild (unsigned int i)
 initialize i-th child, allocate children array if needed
void deleteChild (unsigned int i)
 Deletes the i-th child of the node.
void expandNode ()
 Expands a node (reverse of pruning): All children are created and their occupancy probability is set to the node's value.
OcTreeNodegetChild (unsigned int i)
const OcTreeNodegetChild (unsigned int i) const
float getLogOdds () const
float getMaxChildLogOdds () const
double getMeanChildLogOdds () const
double getOccupancy () const
float getValue () const
bool hasChildren () const
 OcTreeNode ()
bool operator== (const OcTreeDataNode &rhs) const
 Equals operator, compares if the stored value is identical.
bool pruneNode ()
 Prunes a node when it is collapsible.
std::istream & readValue (std::istream &s)
 Read node from binary stream (incl.
void setLogOdds (float l)
 sets log odds occupancy of node
void setValue (floatv)
 sets value to be stored in the node
void updateOccupancyChildren ()
 update this node's occupancy according to its children's maximum occupancy
std::ostream & writeValue (std::ostream &s) const
 Write node to binary stream (incl float value), recursively continue with all children.
 ~OcTreeNode ()

Protected Member Functions

void allocChildren ()

Protected Attributes

OcTreeDataNode< float > ** children
 pointer to array of children, may be NULL
float value
 stored data (payload)

Detailed Description

Nodes to be used in OcTree.

They represent 3d occupancy grid cells. "value" stores their log-odds occupancy.

Hint: If a class is derived from OcTreeNode, you have to implement (at least) createChild, getChild, and getChild const. See OcTreeNodeLabeled for an example.


Member Typedef Documentation

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

Make the templated data type available from the outside.


Constructor & Destructor Documentation

octomap::OcTreeNode::OcTreeNode ( )

Referenced by createChild().

octomap::OcTreeNode::~OcTreeNode ( )

Member Function Documentation

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.

void octomap::OcTreeDataNode< float >::allocChildren ( ) [protected, inherited]
bool octomap::OcTreeDataNode< float >::childExists ( unsigned int  i) const [inherited]
bool octomap::OcTreeDataNode< float >::collapsible ( ) const [inherited]

A node is collapsible if all children exist, don't have children of their own and have the same occupancy value.

Referenced by octomap::ColorOcTreeNode::pruneNode().

bool octomap::OcTreeNode::createChild ( unsigned int  i)

initialize i-th child, allocate children array if needed

Reimplemented from octomap::OcTreeDataNode< float >.

Reimplemented in octomap::ColorOcTreeNode, and octomap::OcTreeNodeStamped.

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

void octomap::OcTreeDataNode< float >::deleteChild ( unsigned int  i) [inherited]

Deletes the i-th child of the node.

void octomap::OcTreeDataNode< float >::expandNode ( ) [inherited]

Expands a node (reverse of pruning): All children are created and their occupancy probability is set to the node's value.

You need to verify that this is indeed a pruned node (i.e. not a leaf at the lowest level)

Reimplemented in octomap::ColorOcTreeNode.

OcTreeNode* octomap::OcTreeNode::getChild ( unsigned int  i) [inline]
Returns:
a pointer to the i-th child of the node. The child needs to exist.

Reimplemented from octomap::OcTreeDataNode< float >.

Reimplemented in octomap::ColorOcTreeNode, and octomap::OcTreeNodeStamped.

Referenced by getChild(), getLeafNodesRecurs(), getMaxChildLogOdds(), getMeanChildLogOdds(), and getVoxelsRecurs().

const OcTreeNode* octomap::OcTreeNode::getChild ( unsigned int  i) const [inline]
Returns:
a const pointer to the i-th child of the node. The child needs to exist.

Reimplemented from octomap::OcTreeDataNode< float >.

Reimplemented in octomap::ColorOcTreeNode, and octomap::OcTreeNodeStamped.

References getChild().

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

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

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

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

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

double octomap::OcTreeNode::getOccupancy ( ) const [inline]
float octomap::OcTreeDataNode< float >::getValue ( ) const [inline, inherited]
Returns:
value stored in the node
bool octomap::OcTreeDataNode< float >::hasChildren ( ) const [inherited]
Returns:
true if the node has at least one child

Referenced by octomap::ColorOcTreeNode::expandNode().

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

Equals operator, compares if the stored value is identical.

bool octomap::OcTreeDataNode< float >::pruneNode ( ) [inherited]

Prunes a node when it is collapsible.

Returns:
true if pruning was successful

Reimplemented in octomap::ColorOcTreeNode.

std::istream& octomap::OcTreeDataNode< float >::readValue ( std::istream &  s) [inherited]

Read node from binary stream (incl.

float value), recursively continue with all children.

Parameters:
s
Returns:

Reimplemented in octomap::ColorOcTreeNode.

void octomap::OcTreeNode::setLogOdds ( float  l) [inline]
void octomap::OcTreeDataNode< float >::setValue ( float  v) [inline, inherited]

sets value to be stored in the node

void octomap::OcTreeNode::updateOccupancyChildren ( ) [inline]

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

Reimplemented in octomap::OcTreeNodeStamped.

References getMaxChildLogOdds(), and setLogOdds().

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

std::ostream& octomap::OcTreeDataNode< float >::writeValue ( std::ostream &  s) const [inherited]

Write node to binary stream (incl float value), recursively continue with all children.

This preserves the complete state of the node.

Parameters:
s
Returns:

Reimplemented in octomap::ColorOcTreeNode.


Field Documentation


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