octomap 1.5.0
|
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 |
ColorOcTreeNode * | getChild (unsigned int i) |
const ColorOcTreeNode * | getChild (unsigned int i) const |
Color | getColor () const |
Color & | getColor () |
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) |
typedef float octomap::OcTreeDataNode< float >::DataType [inherited] |
Make the templated data type available from the outside.
octomap::ColorOcTreeNode::ColorOcTreeNode | ( | ) | [inline] |
Referenced by createChild().
octomap::ColorOcTreeNode::ColorOcTreeNode | ( | const ColorOcTreeNode & | rhs | ) | [inline] |
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] |
Referenced by octomap::OcTreeNode::createChild(), octomap::OcTreeNodeStamped::createChild(), and createChild().
bool octomap::OcTreeDataNode< float >::childExists | ( | unsigned int | i | ) | const [inherited] |
Referenced by getAverageChildColor(), octomap::OcTreeNode::getMaxChildLogOdds(), octomap::OcTreeNode::getMeanChildLogOdds(), and writeValue().
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::Color octomap::ColorOcTreeNode::getAverageChildColor | ( | ) | const |
ColorOcTreeNode* octomap::ColorOcTreeNode::getChild | ( | unsigned int | i | ) | [inline] |
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] |
Reimplemented from octomap::OcTreeNode.
References getChild().
Color octomap::ColorOcTreeNode::getColor | ( | ) | const [inline] |
References color.
Referenced by octomap::ColorOcTree::averageNodeColor(), getAverageChildColor(), octomap::ColorOcTree::integrateNodeColor(), main(), and print_query_info().
float octomap::OcTreeNode::getLogOdds | ( | ) | const [inline, inherited] |
References octomap::OcTreeDataNode< float >::value.
Referenced by octomap::OcTreeNode::getMaxChildLogOdds(), octomap::AbstractOccupancyOcTree::isNodeAtThreshold(), octomap::AbstractOccupancyOcTree::isNodeOccupied(), main(), and pruneNode().
float octomap::OcTreeNode::getMaxChildLogOdds | ( | ) | const [inherited] |
References octomap::OcTreeDataNode< float >::childExists(), octomap::OcTreeNode::getChild(), and octomap::OcTreeNode::getLogOdds().
Referenced by octomap::OcTreeNodeStamped::updateOccupancyChildren(), and octomap::OcTreeNode::updateOccupancyChildren().
double octomap::OcTreeNode::getMeanChildLogOdds | ( | ) | const [inherited] |
References octomap::OcTreeDataNode< float >::childExists(), octomap::OcTreeNode::getChild(), and octomap::OcTreeNode::getOccupancy().
double octomap::OcTreeNode::getOccupancy | ( | ) | const [inline, inherited] |
References octomap::probability(), and octomap::OcTreeDataNode< float >::value.
Referenced by octomap::OcTreeNode::getMeanChildLogOdds(), octomap::ColorOcTree::integrateNodeColor(), and print_query_info().
float octomap::OcTreeDataNode< float >::getValue | ( | ) | const [inline, inherited] |
bool octomap::OcTreeDataNode< float >::hasChildren | ( | ) | const [inherited] |
Referenced by expandNode().
bool octomap::ColorOcTreeNode::isColorSet | ( | ) | const [inline] |
bool octomap::ColorOcTreeNode::operator== | ( | const ColorOcTreeNode & | rhs | ) | const [inline] |
References color, octomap::OcTreeDataNode< float >::value, and octomap::OcTreeDataNode< T >::value.
bool octomap::OcTreeDataNode< float >::operator== | ( | const OcTreeDataNode< float > & | rhs | ) | const [inherited] |
Equals operator, compares if the stored value is identical.
bool octomap::ColorOcTreeNode::pruneNode | ( | ) |
Prunes a node when it is collapsible.
Reimplemented from octomap::OcTreeDataNode< float >.
References octomap::OcTreeDataNode< float >::children, octomap::OcTreeDataNode< float >::collapsible(), color, getAverageChildColor(), getChild(), octomap::OcTreeNode::getLogOdds(), isColorSet(), and octomap::OcTreeNode::setLogOdds().
std::istream & octomap::ColorOcTreeNode::readValue | ( | std::istream & | s | ) |
Read node from binary stream (incl.
float value), recursively continue with all children.
s |
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] |
References color.
Referenced by octomap::ColorOcTree::averageNodeColor(), expandNode(), octomap::ColorOcTree::integrateNodeColor(), main(), and octomap::ColorOcTree::setNodeColor().
void octomap::ColorOcTreeNode::setColor | ( | unsigned char | r, |
unsigned char | g, | ||
unsigned char | b | ||
) | [inline] |
References color.
void octomap::OcTreeNode::setLogOdds | ( | float | l | ) | [inline, inherited] |
sets log odds occupancy of node
References octomap::OcTreeDataNode< float >::value.
Referenced by pruneNode(), octomap::OcTreeNodeStamped::updateOccupancyChildren(), and octomap::OcTreeNode::updateOccupancyChildren().
void octomap::OcTreeDataNode< float >::setValue | ( | float | v | ) | [inline, inherited] |
sets value to be stored in the node
void octomap::ColorOcTreeNode::updateColorChildren | ( | ) |
References color, and getAverageChildColor().
Referenced by octomap::ColorOcTree::updateInnerOccupancyRecurs().
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.
s |
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().
OcTreeDataNode<float >** octomap::OcTreeDataNode< float >::children [protected, inherited] |
pointer to array of children, may be NULL
Referenced by octomap::OcTreeNode::createChild(), octomap::OcTreeNodeStamped::createChild(), createChild(), expandNode(), pruneNode(), readValue(), and writeValue().
Color octomap::ColorOcTreeNode::color [protected] |
Referenced by expandNode(), getColor(), isColorSet(), operator==(), pruneNode(), readValue(), setColor(), updateColorChildren(), and writeValue().
float octomap::OcTreeDataNode< float >::value [protected, inherited] |
stored data (payload)
Referenced by octomap::OcTreeNode::addValue(), expandNode(), octomap::OcTreeNode::getLogOdds(), octomap::OcTreeNode::getOccupancy(), octomap::OcTreeNodeStamped::operator==(), operator==(), readValue(), octomap::OcTreeNode::setLogOdds(), and writeValue().