|
octomap
1.9.7
|
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. More... | |
Public Member Functions | |
| void | addValue (const float &p) |
| adds p to the node's logOdds value (with no boundary / threshold checking!) More... | |
| void | copyData (const OcTreeDataNode &from) |
| Copy the payload (data in "value") from rhs into this node Opposed to copy ctor, this does not clone the children as well. More... | |
| float | getLogOdds () const |
| float | getMaxChildLogOdds () const |
| double | getMeanChildLogOdds () const |
| double | getOccupancy () const |
| float | getValue () const |
| OCTOMAP_DEPRECATED (bool childExists(unsigned int i) const) | |
| Test whether the i-th child exists. More... | |
| OCTOMAP_DEPRECATED (bool hasChildren() const) | |
| OcTreeNode () | |
| bool | operator== (const OcTreeDataNode &rhs) const |
| Equals operator, compares if the stored value is identical. More... | |
| std::istream & | readData (std::istream &s) |
| Read node payload (data only) from binary stream. More... | |
| void | setLogOdds (float l) |
| sets log odds occupancy of node More... | |
| void | setValue (float v) |
| sets value to be stored in the node More... | |
| void | updateOccupancyChildren () |
| update this node's occupancy according to its children's maximum occupancy More... | |
| std::ostream & | writeData (std::ostream &s) const |
| Write node payload (data only) to binary stream. More... | |
| ~OcTreeNode () | |
Protected Member Functions | |
| void | allocChildren () |
Protected Attributes | |
| AbstractOcTreeNode ** | children |
| pointer to array of children, may be NULL More... | |
| float | value |
| stored data (payload) More... | |
Nodes to be used in OcTree.
They represent 3d occupancy grid cells. "value" stores their log-odds occupancy.
Note: If you derive a class (directly or indirectly) from OcTreeNode or OcTreeDataNode, you have to implement (at least) the following functions: createChild(), getChild(), getChild() const, expandNode() to avoid slicing errors and memory-related bugs. See ColorOcTreeNode in ColorOcTree.h for an example.
|
inherited |
Make the templated data type available from the outside.
| 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!)
References octomap::OcTreeDataNode< float >::value.
|
protectedinherited |
|
inherited |
Copy the payload (data in "value") from rhs into this node Opposed to copy ctor, this does not clone the children as well.
|
inline |
References octomap::OcTreeDataNode< float >::value.
Referenced by getMaxChildLogOdds(), octomap::AbstractOccupancyOcTree::isNodeAtThreshold(), octomap::AbstractOccupancyOcTree::isNodeOccupied(), and main().
| float octomap::OcTreeNode::getMaxChildLogOdds | ( | ) | const |
References octomap::OcTreeDataNode< float >::children, and getLogOdds().
Referenced by octomap::OcTreeNodeStamped::updateOccupancyChildren(), and updateOccupancyChildren().
| double octomap::OcTreeNode::getMeanChildLogOdds | ( | ) | const |
References octomap::OcTreeDataNode< float >::children, and getOccupancy().
|
inline |
References octomap::probability(), and octomap::OcTreeDataNode< float >::value.
Referenced by getMeanChildLogOdds(), octomap::ColorOcTree::integrateNodeColor(), main(), and print_query_info().
|
inlineinherited |
|
inherited |
Test whether the i-th child exists.
|
inherited |
|
inherited |
Equals operator, compares if the stored value is identical.
|
inherited |
Read node payload (data only) from binary stream.
|
inline |
sets log odds occupancy of node
References octomap::OcTreeDataNode< float >::value.
Referenced by octomap::OcTreeNodeStamped::updateOccupancyChildren(), and updateOccupancyChildren().
|
inlineinherited |
sets value to be stored in the node
|
inline |
update this node's occupancy according to its children's maximum occupancy
References getMaxChildLogOdds(), and setLogOdds().
Referenced by octomap::ColorOcTree::updateInnerOccupancyRecurs().
|
inherited |
Write node payload (data only) to binary stream.
|
protectedinherited |
pointer to array of children, may be NULL
|
protectedinherited |
stored data (payload)