Public Member Functions
octomap::OcTreeNode Class Reference

#include <OcTreeNode.h>

Inheritance diagram for octomap::OcTreeNode:
Inheritance graph
[legend]

List of all members.

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
OcTreeNodegetChild (unsigned int i)
const OcTreeNodegetChild (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 ()

Detailed Description

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.


Constructor & Destructor Documentation

Definition at line 44 of file OcTreeNode.cpp.

Definition at line 49 of file OcTreeNode.cpp.


Member Function Documentation

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]
Returns:
a pointer to the i-th child of the node. The child needs to exist.

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]
Returns:
a const pointer to the i-th child of the node. The child needs to exist.

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]
Returns:
log odds representation of occupancy probability of node

Definition at line 74 of file OcTreeNode.h.

Returns:
maximum of children's occupancy probabilities, in log odds

Definition at line 82 of file OcTreeNode.cpp.

Returns:
mean of all children's occupancy probabilities, in log odds

Definition at line 67 of file OcTreeNode.cpp.

double octomap::OcTreeNode::getOccupancy ( ) const [inline]
Returns:
occupancy probability of node

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.

update this node's occupancy according to its children's maximum occupancy

Reimplemented in octomap::OcTreeNodeStamped.

Definition at line 89 of file OcTreeNode.h.


The documentation for this class was generated from the following files:


octomap
Author(s): Kai M. Wurm , Armin Hornung
autogenerated on Thu Aug 27 2015 14:13:14