#include <OcTreeNode.h>

Public Member Functions | |
| void | addValue (const float &p) |
| adds p to the node's logOdds value (with no boundary / threshold checking!) More... | |
| float | getLogOdds () const |
| float | getMaxChildLogOdds () const |
| double | getMeanChildLogOdds () const |
| double | getOccupancy () const |
| OcTreeNode () | |
| void | setLogOdds (float l) |
| sets log odds occupancy of node More... | |
| void | updateOccupancyChildren () |
| update this node's occupancy according to its children's maximum occupancy More... | |
| ~OcTreeNode () | |
Public Member Functions inherited from octomap::OcTreeDataNode< float > | |
| void | copyData (const OcTreeDataNode &from) |
| float | getValue () const |
| OCTOMAP_DEPRECATED (bool childExists(unsigned int i) const) | |
| OCTOMAP_DEPRECATED (bool hasChildren() const) | |
| OcTreeDataNode () | |
| OcTreeDataNode (const OcTreeDataNode &rhs) | |
| OcTreeDataNode (float initVal) | |
| 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 | setValue (float v) |
| sets value to be stored in the node More... | |
| std::ostream & | writeData (std::ostream &s) const |
| Write node payload (data only) to binary stream. More... | |
| ~OcTreeDataNode () | |
Additional Inherited Members | |
Public Types inherited from octomap::OcTreeDataNode< float > | |
| typedef float | DataType |
| Make the templated data type available from the outside. More... | |
Protected Member Functions inherited from octomap::OcTreeDataNode< float > | |
| void | allocChildren () |
Protected Attributes inherited from octomap::OcTreeDataNode< float > | |
| AbstractOcTreeNode ** | children |
| 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.
Definition at line 55 of file OcTreeNode.h.
| octomap::OcTreeNode::OcTreeNode | ( | ) |
Definition at line 45 of file OcTreeNode.cpp.
| octomap::OcTreeNode::~OcTreeNode | ( | ) |
Definition at line 50 of file OcTreeNode.cpp.
| void octomap::OcTreeNode::addValue | ( | const float & | p | ) |
adds p to the node's logOdds value (with no boundary / threshold checking!)
Definition at line 91 of file OcTreeNode.cpp.
|
inline |
Definition at line 68 of file OcTreeNode.h.
| float octomap::OcTreeNode::getMaxChildLogOdds | ( | ) | const |
Definition at line 76 of file OcTreeNode.cpp.
| double octomap::OcTreeNode::getMeanChildLogOdds | ( | ) | const |
Definition at line 58 of file OcTreeNode.cpp.
|
inline |
Definition at line 65 of file OcTreeNode.h.
|
inline |
sets log odds occupancy of node
Definition at line 70 of file OcTreeNode.h.
|
inline |
update this node's occupancy according to its children's maximum occupancy
Definition at line 83 of file OcTreeNode.h.