octomap 1.5.0
|
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. | |
const OcTreeNodeStamped * | getChild (unsigned int i) const |
OcTreeNodeStamped * | getChild (unsigned int i) |
float | getLogOdds () const |
float | getMaxChildLogOdds () const |
double | getMeanChildLogOdds () const |
double | getOccupancy () const |
unsigned int | getTimestamp () const |
float | getValue () const |
bool | hasChildren () const |
OcTreeNodeStamped (const OcTreeNodeStamped &rhs) | |
OcTreeNodeStamped () | |
bool | operator== (const OcTreeDataNode &rhs) const |
Equals operator, compares if the stored value is identical. | |
bool | operator== (const OcTreeNodeStamped &rhs) const |
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 | setTimestamp (unsigned int timestamp) |
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 | |
void | updateTimestamp () |
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 | |
unsigned int | timestamp |
float | value |
stored data (payload) |
typedef float octomap::OcTreeDataNode< float >::DataType [inherited] |
Make the templated data type available from the outside.
octomap::OcTreeNodeStamped::OcTreeNodeStamped | ( | ) | [inline] |
Referenced by createChild().
octomap::OcTreeNodeStamped::OcTreeNodeStamped | ( | const OcTreeNodeStamped & | 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(), createChild(), and octomap::ColorOcTreeNode::createChild().
bool octomap::OcTreeDataNode< float >::childExists | ( | unsigned int | i | ) | const [inherited] |
Referenced by octomap::ColorOcTreeNode::getAverageChildColor(), octomap::OcTreeNode::getMaxChildLogOdds(), octomap::OcTreeNode::getMeanChildLogOdds(), and octomap::ColorOcTreeNode::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 octomap::ColorOcTreeNode::pruneNode().
bool octomap::OcTreeNodeStamped::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 OcTreeNodeStamped().
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.
OcTreeNodeStamped* octomap::OcTreeNodeStamped::getChild | ( | unsigned int | i | ) | [inline] |
Reimplemented from octomap::OcTreeNode.
Referenced by getChild().
const OcTreeNodeStamped* octomap::OcTreeNodeStamped::getChild | ( | unsigned int | i | ) | const [inline] |
Reimplemented from octomap::OcTreeNode.
References getChild().
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 octomap::ColorOcTreeNode::pruneNode().
float octomap::OcTreeNode::getMaxChildLogOdds | ( | ) | const [inherited] |
References octomap::OcTreeDataNode< float >::childExists(), octomap::OcTreeNode::getChild(), and octomap::OcTreeNode::getLogOdds().
Referenced by 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().
unsigned int octomap::OcTreeNodeStamped::getTimestamp | ( | ) | const [inline] |
float octomap::OcTreeDataNode< float >::getValue | ( | ) | const [inline, inherited] |
bool octomap::OcTreeDataNode< float >::hasChildren | ( | ) | const [inherited] |
Referenced by octomap::ColorOcTreeNode::expandNode().
bool octomap::OcTreeNodeStamped::operator== | ( | const OcTreeNodeStamped & | 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::OcTreeDataNode< float >::pruneNode | ( | ) | [inherited] |
Prunes a node when it is collapsible.
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.
s |
Reimplemented in octomap::ColorOcTreeNode.
void octomap::OcTreeNode::setLogOdds | ( | float | l | ) | [inline, inherited] |
sets log odds occupancy of node
References octomap::OcTreeDataNode< float >::value.
Referenced by octomap::ColorOcTreeNode::pruneNode(), updateOccupancyChildren(), and octomap::OcTreeNode::updateOccupancyChildren().
void octomap::OcTreeNodeStamped::setTimestamp | ( | unsigned int | timestamp | ) | [inline] |
References timestamp.
void octomap::OcTreeDataNode< float >::setValue | ( | float | v | ) | [inline, inherited] |
sets value to be stored in the node
void octomap::OcTreeNodeStamped::updateOccupancyChildren | ( | ) | [inline] |
update this node's occupancy according to its children's maximum occupancy
Reimplemented from octomap::OcTreeNode.
References octomap::OcTreeNode::getMaxChildLogOdds(), octomap::OcTreeNode::setLogOdds(), and updateTimestamp().
void octomap::OcTreeNodeStamped::updateTimestamp | ( | ) | [inline] |
References timestamp.
Referenced by octomap::OcTreeStamped::updateNodeLogOdds(), and updateOccupancyChildren().
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.
s |
Reimplemented in octomap::ColorOcTreeNode.
OcTreeDataNode<float >** octomap::OcTreeDataNode< float >::children [protected, inherited] |
pointer to array of children, may be NULL
Referenced by octomap::OcTreeNode::createChild(), createChild(), octomap::ColorOcTreeNode::createChild(), octomap::ColorOcTreeNode::expandNode(), octomap::ColorOcTreeNode::pruneNode(), octomap::ColorOcTreeNode::readValue(), and octomap::ColorOcTreeNode::writeValue().
unsigned int octomap::OcTreeNodeStamped::timestamp [protected] |
Referenced by getTimestamp(), operator==(), setTimestamp(), and updateTimestamp().
float octomap::OcTreeDataNode< float >::value [protected, inherited] |
stored data (payload)
Referenced by octomap::OcTreeNode::addValue(), octomap::ColorOcTreeNode::expandNode(), octomap::OcTreeNode::getLogOdds(), octomap::OcTreeNode::getOccupancy(), operator==(), octomap::ColorOcTreeNode::operator==(), octomap::ColorOcTreeNode::readValue(), octomap::OcTreeNode::setLogOdds(), and octomap::ColorOcTreeNode::writeValue().