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

#include <OcTreePCL.h>

List of all members.

Public Member Functions

void calcNumThresholdedNodes (unsigned int &num_thresholded, unsigned int &num_other) const
octomap::OcTreeNodePCLgetOcTreeNodePCL (point3d c) const
 return OcTreeNodePCL given centroid c
void insertOcTreeNodePCL (octomap::OcTreeNodePCL *)
 inserts new OcTreeNodePCL into octree_node_list
void insertScan (const ScanNode &scan, double maxrange=-1., bool pruning=true)
unsigned int memoryUsage () const
 OcTreePCL (double _resolution)
std::istream & readBinary (std::istream &s)
 binary file format: treetype | resolution | num nodes | [binary nodes]
void readBinary (const std::string &filename)
 Reads OcTree from a binary file. Existing nodes are deleted.
void toMaxLikelihood ()
std::ostream & writeBinary (std::ostream &s)
void writeBinary (const std::string &filename)
std::ostream & writeBinaryConst (std::ostream &s) const
void writeBinaryConst (const std::string &filename) const

Public Attributes

std::vector
< octomap::OcTreeNodePCL * > 
octree_node_list

Static Public Attributes

static const int TREETYPE = 3

Protected Member Functions

void calcNumThresholdedNodesRecurs (OcTreeNodePCL *node, unsigned int &num_thresholded, unsigned int &num_other) const
void insertScanUniform (const ScanNode &scan, double maxrange=-1.)
 Helper for insertScan (internal use)
void toMaxLikelihoodRecurs (OcTreeNodePCL *node, unsigned int depth, unsigned int max_depth)
 recursive call of toMaxLikelihood()

Detailed Description

octomap main map data structure, stores 3D occupancy grid map in an OcTree. Basic functionality is implemented in OcTreeBase.

Definition at line 14 of file OcTreePCL.h.


Constructor & Destructor Documentation

octomap::OcTreePCL::OcTreePCL ( double  _resolution)

Creates a new (empty) OcTree of a given resolution

Parameters:
_resolution

Definition at line 21 of file OcTreePCL.cpp.


Member Function Documentation

void octomap::OcTreePCL::calcNumThresholdedNodes ( unsigned int num_thresholded,
unsigned int num_other 
) const

Definition at line 79 of file OcTreePCL.cpp.

void octomap::OcTreePCL::calcNumThresholdedNodesRecurs ( OcTreeNodePCL node,
unsigned int num_thresholded,
unsigned int num_other 
) const [protected]

Definition at line 299 of file OcTreePCL.cpp.

return OcTreeNodePCL given centroid c

Definition at line 320 of file OcTreePCL.cpp.

inserts new OcTreeNodePCL into octree_node_list

Definition at line 315 of file OcTreePCL.cpp.

void octomap::OcTreePCL::insertScan ( const ScanNode &  scan,
double  maxrange = -1.,
bool  pruning = true 
)

Insert a 3d scan (given as a ScanNode) into the tree. By default, the tree is pruned after insertion (small run-time overhead, but decreases size)

Parameters:
scan
maxrangemaximum range for how long individual beams are inserted (default -1: complete beam)
pruningwhether the tree is (losslessly) pruned after insertion (default: true)

Definition at line 29 of file OcTreePCL.cpp.

void octomap::OcTreePCL::insertScanUniform ( const ScanNode &  scan,
double  maxrange = -1. 
) [protected]

Helper for insertScan (internal use)

Definition at line 205 of file OcTreePCL.cpp.

Returns:
Memory usage of the OcTree in bytes.

Definition at line 70 of file OcTreePCL.cpp.

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

binary file format: treetype | resolution | num nodes | [binary nodes]

Reads an OcTree from an input stream. Existing nodes are deleted.

Definition at line 101 of file OcTreePCL.cpp.

Reads OcTree from a binary file. Existing nodes are deleted.

Definition at line 87 of file OcTreePCL.cpp.

Creates the maximum likelihood map by calling toMaxLikelihood on all tree nodes, setting their occupancy to the corresponding occupancy thresholds.

Definition at line 56 of file OcTreePCL.cpp.

void octomap::OcTreePCL::toMaxLikelihoodRecurs ( OcTreeNodePCL node,
unsigned int  depth,
unsigned int  max_depth 
) [protected]

recursive call of toMaxLikelihood()

Definition at line 283 of file OcTreePCL.cpp.

std::ostream & octomap::OcTreePCL::writeBinary ( std::ostream &  s)

Writes OcTree to a binary stream. The OcTree is first converted to the maximum likelihood estimate and pruned for maximum compression.

Definition at line 171 of file OcTreePCL.cpp.

Writes OcTree to a binary file using writeBinary(). The OcTree is first converted to the maximum likelihood estimate and pruned.

Definition at line 146 of file OcTreePCL.cpp.

std::ostream & octomap::OcTreePCL::writeBinaryConst ( std::ostream &  s) const

Writes the maximum likelihood OcTree to a binary stream (const variant). Files will be smaller when the tree is pruned first.

Definition at line 181 of file OcTreePCL.cpp.

Writes OcTree to a binary file using writeBinaryConst(). The OcTree is not changed, in particular not pruned first.

Definition at line 158 of file OcTreePCL.cpp.


Member Data Documentation

Definition at line 18 of file OcTreePCL.h.

const int octomap::OcTreePCL::TREETYPE = 3 [static]

Definition at line 17 of file OcTreePCL.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 Sun Oct 6 2013 12:03:29