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.
Definition at line 67 of file OcTreeNode.h.
#include <mrpt/otherlibs/octomap/OcTreeNode.h>
Public Types | |
typedef float | DataType |
Make the templated data type available from the outside. More... | |
Public Member Functions | |
OcTreeNode () | |
~OcTreeNode () | |
bool | createChild (unsigned int i) |
OcTreeNode * | getChild (unsigned int i) |
const OcTreeNode * | getChild (unsigned int i) const |
double | getOccupancy () const |
float | getLogOdds () const |
void | setLogOdds (float l) |
sets log odds occupancy of node More... | |
double | getMeanChildLogOdds () const |
float | getMaxChildLogOdds () const |
void | updateOccupancyChildren () |
update this node's occupancy according to its children's maximum occupancy More... | |
void | addValue (const float &p) |
adds p to the node's logOdds value (with no boundary / threshold checking!) More... | |
bool | operator== (const OcTreeDataNode &rhs) const |
Equals operator, compares if the stored value is identical. More... | |
bool | childExists (unsigned int i) const |
bool | hasChildren () 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. More... | |
void | deleteChild (unsigned int i) |
Deletes the i-th child of the node. More... | |
bool | pruneNode () |
Prunes a node when it is collapsible. More... | |
void | expandNode () |
Expands a node (reverse of pruning): All children are created and their occupancy probability is set to the node's value. More... | |
float | getValue () const |
void | setValue (floatv) |
sets value to be stored in the node More... | |
std::istream & | readValue (std::istream &s) |
Read node from binary stream (incl. More... | |
std::ostream & | writeValue (std::ostream &s) const |
Write node to binary stream (incl float value), recursively continue with all children. More... | |
Protected Member Functions | |
void | allocChildren () |
Protected Attributes | |
OcTreeDataNode< float > ** | children |
pointer to array of children, may be NULL More... | |
float | value |
stored data (payload) More... | |
|
inherited |
Make the templated data type available from the outside.
Definition at line 156 of file OcTreeDataNode.h.
octomap::OcTreeNode::OcTreeNode | ( | ) |
octomap::OcTreeNode::~OcTreeNode | ( | ) |
void octomap::OcTreeNode::addValue | ( | const float & | p | ) |
adds p to the node's logOdds value (with no boundary / threshold checking!)
|
protectedinherited |
Referenced by octomap::OcTreeNodeStamped::createChild(), and octomap::ColorOcTreeNode::createChild().
|
inherited |
|
inherited |
A node is collapsible if all children exist, don't have children of their own and have the same occupancy value.
bool octomap::OcTreeNode::createChild | ( | unsigned int | i | ) |
|
inherited |
Deletes the i-th child of the node.
|
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)
|
inline |
Definition at line 76 of file OcTreeNode.h.
References octomap::OcTreeDataNode< T >::getChild().
Referenced by octomap::OcTreeNodeStamped::getChild(), and octomap::ColorOcTreeNode::getChild().
|
inline |
Definition at line 79 of file OcTreeNode.h.
References octomap::OcTreeDataNode< T >::getChild().
|
inline |
Definition at line 89 of file OcTreeNode.h.
Referenced by octomap::AbstractOccupancyOcTree::isNodeAtThreshold(), and octomap::AbstractOccupancyOcTree::isNodeOccupied().
float octomap::OcTreeNode::getMaxChildLogOdds | ( | ) | const |
Referenced by octomap::OcTreeNodeStamped::updateOccupancyChildren().
double octomap::OcTreeNode::getMeanChildLogOdds | ( | ) | const |
|
inline |
Definition at line 86 of file OcTreeNode.h.
References octomap::probability().
|
inlineinherited |
Definition at line 129 of file OcTreeDataNode.h.
|
inherited |
|
inherited |
Equals operator, compares if the stored value is identical.
|
inherited |
Prunes a node when it is collapsible.
|
inherited |
Read node from binary stream (incl.
float value), recursively continue with all children.
s |
|
inline |
sets log odds occupancy of node
Definition at line 91 of file OcTreeNode.h.
Referenced by octomap::OcTreeNodeStamped::updateOccupancyChildren().
|
inlineinherited |
sets value to be stored in the node
Definition at line 131 of file OcTreeDataNode.h.
|
inline |
update this node's occupancy according to its children's maximum occupancy
Definition at line 104 of file OcTreeNode.h.
|
inherited |
Write node to binary stream (incl float value), recursively continue with all children.
This preserves the complete state of the node.
s |
|
protectedinherited |
pointer to array of children, may be NULL
Definition at line 163 of file OcTreeDataNode.h.
Referenced by octomap::OcTreeNodeStamped::createChild(), and octomap::ColorOcTreeNode::createChild().
|
protectedinherited |
stored data (payload)
Definition at line 165 of file OcTreeDataNode.h.
Referenced by octomap::OcTreeNodeStamped::operator==(), and octomap::ColorOcTreeNode::operator==().
Page generated by Doxygen 1.8.11 for MRPT 1.4.0 SVN:Unversioned directory at Mon May 30 18:20:32 UTC 2016 |