9 #ifndef OCTOMAP_OCTREE_DATA_NODE_H
10 #define OCTOMAP_OCTREE_DATA_NODE_H
142 std::istream&
readValue(std::istream &s);
152 std::ostream&
writeValue(std::ostream &s)
const;
172 #include "mrpt/otherlibs/octomap/OcTreeDataNode.hxx"
bool operator==(const OcTreeDataNode &rhs) const
Equals operator, compares if the stored value is identical.
OctoMap: A probabilistic, flexible, and compact 3D mapping library for robotic systems.
OcTreeDataNode< T > ** children
pointer to array of children, may be NULL
std::istream & readValue(std::istream &s)
Read node from binary stream (incl.
bool collapsible() const
A node is collapsible if all children exist, don't have children of their own and have the same occup...
void setValue(T v)
sets value to be stored in the node
T value
stored data (payload)
std::ostream & writeValue(std::ostream &s) const
Write node to binary stream (incl float value), recursively continue with all children.
bool pruneNode()
Prunes a node when it is collapsible.
Basic node in the OcTree that can hold arbitrary data of type T in value.
bool createChild(unsigned int i)
initialize i-th child, allocate children array if needed
bool childExists(unsigned int i) const
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 ...
T DataType
Make the templated data type available from the outside.
OcTreeDataNode< T > * getChild(unsigned int i)