octomap 1.5.0
octomap::ColorOcTreeNode Class Reference
Inheritance diagram for octomap::ColorOcTreeNode:
Collaboration diagram for octomap::ColorOcTreeNode:

Data Structures

class  Color

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.
 ColorOcTreeNode (const ColorOcTreeNode &rhs)
 ColorOcTreeNode ()
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.
ColorOcTreeNode::Color getAverageChildColor () const
ColorOcTreeNodegetChild (unsigned int i)
const ColorOcTreeNodegetChild (unsigned int i) const
Color getColor () const
ColorgetColor ()
float getLogOdds () const
float getMaxChildLogOdds () const
double getMeanChildLogOdds () const
double getOccupancy () const
float getValue () const
bool hasChildren () const
bool isColorSet () const
bool operator== (const OcTreeDataNode &rhs) const
 Equals operator, compares if the stored value is identical.
bool operator== (const ColorOcTreeNode &rhs) const
bool pruneNode ()
 Prunes a node when it is collapsible.
std::istream & readValue (std::istream &s)
 Read node from binary stream (incl.
void setColor (Color c)
void setColor (unsigned char r, unsigned char g, unsigned char b)
void setLogOdds (float l)
 sets log odds occupancy of node
void setValue (floatv)
 sets value to be stored in the node
void updateColorChildren ()
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.

Protected Member Functions

void allocChildren ()

Protected Attributes

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

Member Typedef Documentation

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

Make the templated data type available from the outside.


Constructor & Destructor Documentation

octomap::ColorOcTreeNode::ColorOcTreeNode ( ) [inline]

Referenced by createChild().

octomap::ColorOcTreeNode::ColorOcTreeNode ( const ColorOcTreeNode rhs) [inline]

Member Function Documentation

void octomap::OcTreeNode::addValue ( const float &  p) [inherited]

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 pruneNode().

bool octomap::ColorOcTreeNode::createChild ( unsigned int  i) [inline]

initialize i-th child, allocate children array if needed

Reimplemented from octomap::OcTreeNode.

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

Referenced by expandNode(), and readValue().

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

Deletes the i-th child of the node.

void octomap::ColorOcTreeNode::expandNode ( )

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 from octomap::OcTreeDataNode< float >.

References octomap::OcTreeDataNode< float >::children, color, createChild(), getChild(), octomap::OcTreeDataNode< float >::hasChildren(), setColor(), octomap::OcTreeDataNode< T >::setValue(), and octomap::OcTreeDataNode< float >::value.

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

Reimplemented from octomap::OcTreeNode.

Referenced by expandNode(), getAverageChildColor(), getChild(), pruneNode(), readValue(), octomap::ColorOcTree::updateInnerOccupancyRecurs(), and writeValue().

const ColorOcTreeNode* octomap::ColorOcTreeNode::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::OcTreeNode.

References getChild().

Color& octomap::ColorOcTreeNode::getColor ( ) [inline]

References color.

Color octomap::ColorOcTreeNode::getColor ( ) const [inline]
float octomap::OcTreeNode::getLogOdds ( ) const [inline, inherited]
float octomap::OcTreeNode::getMaxChildLogOdds ( ) const [inherited]
double octomap::OcTreeNode::getMeanChildLogOdds ( ) const [inherited]
Returns:
mean of all children's occupancy probabilities, in log odds

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

double octomap::OcTreeNode::getOccupancy ( ) const [inline, inherited]
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 expandNode().

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

Equals operator, compares if the stored value is identical.

bool octomap::ColorOcTreeNode::pruneNode ( )
std::istream & octomap::ColorOcTreeNode::readValue ( std::istream &  s)

Read node from binary stream (incl.

float value), recursively continue with all children.

Parameters:
s
Returns:

Reimplemented from octomap::OcTreeDataNode< float >.

References octomap::OcTreeDataNode< float >::children, color, createChild(), getChild(), readValue(), and octomap::OcTreeDataNode< float >::value.

Referenced by readValue().

void octomap::ColorOcTreeNode::setColor ( Color  c) [inline]
void octomap::ColorOcTreeNode::setColor ( unsigned char  r,
unsigned char  g,
unsigned char  b 
) [inline]

References color.

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

sets value to be stored in the node

void octomap::ColorOcTreeNode::updateColorChildren ( )
void octomap::OcTreeNode::updateOccupancyChildren ( ) [inline, inherited]

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

Reimplemented in octomap::OcTreeNodeStamped.

References octomap::OcTreeNode::getMaxChildLogOdds(), and octomap::OcTreeNode::setLogOdds().

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

std::ostream & octomap::ColorOcTreeNode::writeValue ( std::ostream &  s) const

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 from octomap::OcTreeDataNode< float >.

References octomap::OcTreeDataNode< float >::childExists(), octomap::OcTreeDataNode< float >::children, color, getChild(), octomap::OcTreeDataNode< float >::value, and writeValue().

Referenced by writeValue().


Field Documentation

OcTreeDataNode<float >** octomap::OcTreeDataNode< float >::children [protected, inherited]

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