#include <OcTreeNode.h>
Public Member Functions | |
void | addValue (const float &p) |
adds p to the node's logOdds value (with no boundary / threshold checking!) | |
bool | createChild (unsigned int i) |
initialize i-th child, allocate children array if needed | |
OcTreeNode * | getChild (unsigned int i) |
const OcTreeNode * | getChild (unsigned int i) const |
float | getLogOdds () const |
float | getMaxChildLogOdds () const |
double | getMeanChildLogOdds () const |
double | getOccupancy () const |
OcTreeNode () | |
void | setLogOdds (float l) |
sets log odds occupancy of node | |
void | updateOccupancyChildren () |
update this node's occupancy according to its children's maximum occupancy | |
~OcTreeNode () |
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 52 of file OcTreeNode.h.
Definition at line 44 of file OcTreeNode.cpp.
Definition at line 49 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 94 of file OcTreeNode.cpp.
bool octomap::OcTreeNode::createChild | ( | unsigned int | i | ) |
initialize i-th child, allocate children array if needed
Reimplemented from octomap::OcTreeDataNode< float >.
Reimplemented in octomap::ColorOcTreeNode, and octomap::OcTreeNodeStamped.
Definition at line 54 of file OcTreeNode.cpp.
OcTreeNode* octomap::OcTreeNode::getChild | ( | unsigned int | i | ) | [inline] |
Reimplemented from octomap::OcTreeDataNode< float >.
Reimplemented in octomap::ColorOcTreeNode, and octomap::OcTreeNodeStamped.
Definition at line 61 of file OcTreeNode.h.
const OcTreeNode* octomap::OcTreeNode::getChild | ( | unsigned int | i | ) | const [inline] |
Reimplemented from octomap::OcTreeDataNode< float >.
Reimplemented in octomap::ColorOcTreeNode, and octomap::OcTreeNodeStamped.
Definition at line 64 of file OcTreeNode.h.
float octomap::OcTreeNode::getLogOdds | ( | ) | const [inline] |
Definition at line 74 of file OcTreeNode.h.
float octomap::OcTreeNode::getMaxChildLogOdds | ( | ) | const |
Definition at line 82 of file OcTreeNode.cpp.
double octomap::OcTreeNode::getMeanChildLogOdds | ( | ) | const |
Definition at line 67 of file OcTreeNode.cpp.
double octomap::OcTreeNode::getOccupancy | ( | ) | const [inline] |
Definition at line 71 of file OcTreeNode.h.
void octomap::OcTreeNode::setLogOdds | ( | float | l | ) | [inline] |
sets log odds occupancy of node
Definition at line 76 of file OcTreeNode.h.
void octomap::OcTreeNode::updateOccupancyChildren | ( | ) | [inline] |
update this node's occupancy according to its children's maximum occupancy
Reimplemented in octomap::OcTreeNodeStamped.
Definition at line 89 of file OcTreeNode.h.