All Classes Namespaces Files Functions Variables Typedefs Enumerations Properties Friends Defines
Public Member Functions | Public Attributes
octomap::OcTreeNodePCL Class Reference

#include <OcTreeNodePCL.h>

List of all members.

Public Member Functions

virtual bool createChild (unsigned int i)
std::vector< int > get3DPointInliers ()
point3d getCentroid () const
virtual OcTreeNodePCLgetChild (unsigned int i)
virtual const OcTreeNodePCLgetChild (unsigned int i) const
int getLabel () const
double getResolution () const
 OcTreeNodePCL ()
std::istream & readBinary (std::istream &s)
void set3DPointInliers (int inlier_index)
void setCentroid (point3d c)
void setLabel (int l)
void setResolution (double res)
std::ostream & writeBinary (std::ostream &s) const
virtual ~OcTreeNodePCL ()

Public Attributes

point3d centroid
std::vector< int > inliers
int label
double resolution

Detailed Description

Node class storing a label as additional information

Definition at line 19 of file OcTreeNodePCL.h.


Constructor & Destructor Documentation

Definition at line 16 of file OcTreeNodePCL.cpp.

Definition at line 22 of file OcTreeNodePCL.cpp.


Member Function Documentation

bool octomap::OcTreeNodePCL::createChild ( unsigned int  i) [virtual]

Definition at line 32 of file OcTreeNodePCL.cpp.

Returns:
Leaf Node inliers

Definition at line 97 of file OcTreeNodePCL.cpp.

Returns:
centroid of node

Definition at line 77 of file OcTreeNodePCL.cpp.

OcTreeNodePCL * octomap::OcTreeNodePCL::getChild ( unsigned int  i) [virtual]

Definition at line 43 of file OcTreeNodePCL.cpp.

const OcTreeNodePCL * octomap::OcTreeNodePCL::getChild ( unsigned int  i) const [virtual]

Definition at line 50 of file OcTreeNodePCL.cpp.

Returns:
Label of node

Definition at line 67 of file OcTreeNodePCL.cpp.

Returns:
resolution of node

Definition at line 87 of file OcTreeNodePCL.cpp.

std::istream & octomap::OcTreeNodePCL::readBinary ( std::istream &  s)

Read node from binary stream (max-likelihood value), recursively continue with all children.

This will set the log_odds_occupancy value of all leaves to either free or occupied.

Parameters:
s
Returns:

Definition at line 106 of file OcTreeNodePCL.cpp.

void octomap::OcTreeNodePCL::set3DPointInliers ( int  inlier_index)

set a Leaf Node inliers

Definition at line 92 of file OcTreeNodePCL.cpp.

set a centroid

Definition at line 72 of file OcTreeNodePCL.cpp.

set a label

Definition at line 62 of file OcTreeNodePCL.cpp.

set a resolution

Definition at line 82 of file OcTreeNodePCL.cpp.

std::ostream & octomap::OcTreeNodePCL::writeBinary ( std::ostream &  s) const

Write node to binary stream (max-likelihood value), recursively continue with all children.

This will discard the log_odds_occupancy value, writing all leaves as either free or occupied.

Parameters:
s
Returns:

Definition at line 174 of file OcTreeNodePCL.cpp.


Member Data Documentation

Definition at line 24 of file OcTreeNodePCL.h.

Definition at line 26 of file OcTreeNodePCL.h.

Definition at line 23 of file OcTreeNodePCL.h.

Definition at line 25 of file OcTreeNodePCL.h.


The documentation for this class was generated from the following files:
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Properties Friends Defines


pcl_to_octree
Author(s): Hozefa Indorewala, Dejan Pangercic
autogenerated on Thu May 23 2013 08:28:50