octomap  1.8.0
 All Data Structures Namespaces Files Functions Variables Typedefs Friends Macros Pages
octomap::OcTreeNodeStamped Class Reference
+ Inheritance diagram for octomap::OcTreeNodeStamped:
+ Collaboration diagram for octomap::OcTreeNodeStamped:

Public Types

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

Public Member Functions

void addValue (const float &p)
 adds p to the node's logOdds value (with no boundary / threshold checking!) More...
 
void copyData (const OcTreeNodeStamped &from)
 
void copyData (const OcTreeDataNode &from)
 Copy the payload (data in "value") from rhs into this node Opposed to copy ctor, this does not clone the children as well. More...
 
float getLogOdds () const
 
float getMaxChildLogOdds () const
 
double getMeanChildLogOdds () const
 
double getOccupancy () const
 
unsigned int getTimestamp () const
 
float getValue () const
 
 OCTOMAP_DEPRECATED (bool childExists(unsigned int i) const)
 Test whether the i-th child exists. More...
 
 OCTOMAP_DEPRECATED (bool hasChildren() const)
 
 OcTreeNodeStamped ()
 
 OcTreeNodeStamped (const OcTreeNodeStamped &rhs)
 
bool operator== (const OcTreeNodeStamped &rhs) const
 
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 setLogOdds (float l)
 sets log odds occupancy of node More...
 
void setTimestamp (unsigned int timestamp)
 
void setValue (floatv)
 sets value to be stored in the node More...
 
void updateOccupancyChildren ()
 
void updateTimestamp ()
 
std::ostream & writeData (std::ostream &s) const
 Write node payload (data only) to binary stream. More...
 

Protected Member Functions

void allocChildren ()
 

Protected Attributes

AbstractOcTreeNode ** children
 pointer to array of children, may be NULL More...
 
unsigned int timestamp
 
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.

Constructor & Destructor Documentation

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

Member Function Documentation

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

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

References octomap::OcTreeDataNode< float >::value.

void octomap::OcTreeDataNode< float >::allocChildren ( )
protectedinherited
void octomap::OcTreeNodeStamped::copyData ( const OcTreeNodeStamped from)
inline
void octomap::OcTreeDataNode< float >::copyData ( const OcTreeDataNode< float > &  from)
inherited

Copy the payload (data in "value") from rhs into this node Opposed to copy ctor, this does not clone the children as well.

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

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

References octomap::OcTreeDataNode< float >::children, and octomap::OcTreeNode::getLogOdds().

Referenced by updateOccupancyChildren(), and octomap::OcTreeNode::updateOccupancyChildren().

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

References octomap::OcTreeDataNode< float >::children, and octomap::OcTreeNode::getOccupancy().

double octomap::OcTreeNode::getOccupancy ( ) const
inlineinherited
unsigned int octomap::OcTreeNodeStamped::getTimestamp ( ) const
inline
float octomap::OcTreeDataNode< float >::getValue ( ) const
inlineinherited
Returns
value stored in the node
octomap::OcTreeDataNode< float >::OCTOMAP_DEPRECATED ( bool childExists(unsigned int i)  const)
inherited

Test whether the i-th child exists.

octomap::OcTreeDataNode< float >::OCTOMAP_DEPRECATED ( bool hasChildren()  const)
inherited
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.

std::istream& octomap::OcTreeDataNode< float >::readData ( std::istream &  s)
inherited

Read node payload (data only) from binary stream.

void octomap::OcTreeNode::setLogOdds ( float  l)
inlineinherited
void octomap::OcTreeNodeStamped::setTimestamp ( unsigned int  timestamp)
inline

References timestamp.

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

sets value to be stored in the node

void octomap::OcTreeNodeStamped::updateOccupancyChildren ( )
inline
void octomap::OcTreeNodeStamped::updateTimestamp ( )
inline
std::ostream& octomap::OcTreeDataNode< float >::writeData ( std::ostream &  s) const
inherited

Write node payload (data only) to binary stream.

Field Documentation

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

pointer to array of children, may be NULL

Note
The tree class manages this pointer, the array, and the memory for it! The children of a node are always enforced to be the same type as the node

Referenced by octomap::ColorOcTreeNode::getAverageChildColor(), octomap::OcTreeNode::getMaxChildLogOdds(), and octomap::OcTreeNode::getMeanChildLogOdds().

unsigned int octomap::OcTreeNodeStamped::timestamp
protected

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