Main MRPT website > C++ reference for MRPT 1.4.0
List of all members | Public Types | Public Member Functions | Protected Member Functions | Protected Attributes
octomap::OcTreeNodeStamped Class Reference

Detailed Description

Definition at line 58 of file OcTreeStamped.h.

#include <mrpt/otherlibs/octomap/OcTreeStamped.h>

Inheritance diagram for octomap::OcTreeNodeStamped:
Inheritance graph

Public Types

typedef float DataType
 Make the templated data type available from the outside. More...
 

Public Member Functions

 OcTreeNodeStamped ()
 
 OcTreeNodeStamped (const OcTreeNodeStamped &rhs)
 
bool operator== (const OcTreeNodeStamped &rhs) const
 
OcTreeNodeStampedgetChild (unsigned int i)
 
const OcTreeNodeStampedgetChild (unsigned int i) const
 
bool createChild (unsigned int i)
 
unsigned int getTimestamp () const
 
void updateTimestamp ()
 
void setTimestamp (unsigned int timestamp)
 
void updateOccupancyChildren ()
 
double getOccupancy () const
 
float getLogOdds () const
 
void setLogOdds (float l)
 sets log odds occupancy of node More...
 
double getMeanChildLogOdds () const
 
float getMaxChildLogOdds () const
 
void addValue (const float &p)
 adds p to the node's logOdds value (with no boundary / threshold checking!) More...
 
bool operator== (const OcTreeDataNode &rhs) const
 Equals operator, compares if the stored value is identical. More...
 
bool childExists (unsigned int i) const
 
bool hasChildren () const
 
bool collapsible () const
 A node is collapsible if all children exist, don't have children of their own and have the same occupancy value. More...
 
void deleteChild (unsigned int i)
 Deletes the i-th child of the node. More...
 
bool pruneNode ()
 Prunes a node when it is collapsible. More...
 
void expandNode ()
 Expands a node (reverse of pruning): All children are created and their occupancy probability is set to the node's value. More...
 
float getValue () const
 
void setValue (floatv)
 sets value to be stored in the node More...
 
std::istream & readValue (std::istream &s)
 Read node from binary stream (incl. More...
 
std::ostream & writeValue (std::ostream &s) const
 Write node to binary stream (incl float value), recursively continue with all children. More...
 

Protected Member Functions

void allocChildren ()
 

Protected Attributes

unsigned int timestamp
 
OcTreeDataNode< float > ** children
 pointer to array of children, may be NULL More...
 
float value
 stored data (payload) More...
 

Member Typedef Documentation

typedef float octomap::OcTreeDataNode< float >::DataType
inherited

Make the templated data type available from the outside.

Definition at line 156 of file OcTreeDataNode.h.

Constructor & Destructor Documentation

octomap::OcTreeNodeStamped::OcTreeNodeStamped ( )
inline

Definition at line 61 of file OcTreeStamped.h.

Referenced by createChild().

octomap::OcTreeNodeStamped::OcTreeNodeStamped ( const OcTreeNodeStamped rhs)
inline

Definition at line 63 of file OcTreeStamped.h.

Member Function Documentation

void octomap::OcTreeNode::addValue ( const float &  p)
inherited

adds p to the node's logOdds value (with no boundary / threshold checking!)

void octomap::OcTreeDataNode< float >::allocChildren ( )
protectedinherited
bool octomap::OcTreeDataNode< float >::childExists ( unsigned int  i) const
inherited
Returns
true if the i-th child exists
bool octomap::OcTreeDataNode< float >::collapsible ( ) const
inherited

A node is collapsible if all children exist, don't have children of their own and have the same occupancy value.

bool octomap::OcTreeNodeStamped::createChild ( unsigned int  i)
inline
void octomap::OcTreeDataNode< float >::deleteChild ( unsigned int  i)
inherited

Deletes the i-th child of the node.

void octomap::OcTreeDataNode< float >::expandNode ( )
inherited

Expands a node (reverse of pruning): All children are created and their occupancy probability is set to the node's value.

You need to verify that this is indeed a pruned node (i.e. not a leaf at the lowest level)

OcTreeNodeStamped* octomap::OcTreeNodeStamped::getChild ( unsigned int  i)
inline

Definition at line 70 of file OcTreeStamped.h.

References octomap::OcTreeNode::getChild().

const OcTreeNodeStamped* octomap::OcTreeNodeStamped::getChild ( unsigned int  i) const
inline

Definition at line 73 of file OcTreeStamped.h.

References octomap::OcTreeNode::getChild().

float octomap::OcTreeNode::getLogOdds ( ) const
inlineinherited
Returns
log odds representation of occupancy probability of node

Definition at line 89 of file OcTreeNode.h.

Referenced by octomap::AbstractOccupancyOcTree::isNodeAtThreshold(), and octomap::AbstractOccupancyOcTree::isNodeOccupied().

float octomap::OcTreeNode::getMaxChildLogOdds ( ) const
inherited
Returns
maximum of children's occupancy probabilities, in log odds

Referenced by updateOccupancyChildren().

double octomap::OcTreeNode::getMeanChildLogOdds ( ) const
inherited
Returns
mean of all children's occupancy probabilities, in log odds
double octomap::OcTreeNode::getOccupancy ( ) const
inlineinherited
Returns
occupancy probability of node

Definition at line 86 of file OcTreeNode.h.

References octomap::probability().

unsigned int octomap::OcTreeNodeStamped::getTimestamp ( ) const
inline

Definition at line 84 of file OcTreeStamped.h.

References timestamp.

float octomap::OcTreeDataNode< float >::getValue ( ) const
inlineinherited
Returns
value stored in the node

Definition at line 129 of file OcTreeDataNode.h.

bool octomap::OcTreeDataNode< float >::hasChildren ( ) const
inherited
Returns
true if the node has at least one child
bool octomap::OcTreeNodeStamped::operator== ( const OcTreeNodeStamped rhs) const
inline
bool octomap::OcTreeDataNode< float >::operator== ( const OcTreeDataNode< float > &  rhs) const
inherited

Equals operator, compares if the stored value is identical.

bool octomap::OcTreeDataNode< float >::pruneNode ( )
inherited

Prunes a node when it is collapsible.

Returns
true if pruning was successful
std::istream& octomap::OcTreeDataNode< float >::readValue ( std::istream &  s)
inherited

Read node from binary stream (incl.

float value), recursively continue with all children.

Parameters
s
Returns
void octomap::OcTreeNode::setLogOdds ( float  l)
inlineinherited

sets log odds occupancy of node

Definition at line 91 of file OcTreeNode.h.

Referenced by updateOccupancyChildren().

void octomap::OcTreeNodeStamped::setTimestamp ( unsigned int  timestamp)
inline

Definition at line 86 of file OcTreeStamped.h.

References timestamp.

void octomap::OcTreeDataNode< float >::setValue ( float  v)
inlineinherited

sets value to be stored in the node

Definition at line 131 of file OcTreeDataNode.h.

void octomap::OcTreeNodeStamped::updateOccupancyChildren ( )
inline
void octomap::OcTreeNodeStamped::updateTimestamp ( )
inline

Definition at line 85 of file OcTreeStamped.h.

References timestamp.

Referenced by updateOccupancyChildren().

std::ostream& octomap::OcTreeDataNode< float >::writeValue ( std::ostream &  s) const
inherited

Write node to binary stream (incl float value), recursively continue with all children.

This preserves the complete state of the node.

Parameters
s
Returns

Member Data Documentation

OcTreeDataNode<float >** octomap::OcTreeDataNode< float >::children
protectedinherited

pointer to array of children, may be NULL

Definition at line 163 of file OcTreeDataNode.h.

Referenced by createChild(), and octomap::ColorOcTreeNode::createChild().

unsigned int octomap::OcTreeNodeStamped::timestamp
protected

Definition at line 95 of file OcTreeStamped.h.

Referenced by getTimestamp(), operator==(), setTimestamp(), and updateTimestamp().

float octomap::OcTreeDataNode< float >::value
protectedinherited

stored data (payload)

Definition at line 165 of file OcTreeDataNode.h.

Referenced by operator==(), and octomap::ColorOcTreeNode::operator==().




Page generated by Doxygen 1.8.11 for MRPT 1.4.0 SVN: at Mon Aug 15 11:50:21 UTC 2016