$search

srs_env_model::EMOcTree Class Reference

#include <octonode.h>

List of all members.

Classes

class  StaticMemberInitializer

Public Types

typedef EModelTreeNode tNode
 Used node type.
typedef octomap::point3d tPoint
 Used point type.
typedef pcl::PointCloud
< pcl::PointXYZRGB > 
typePointCloud

Public Member Functions

EModelTreeNodeaverageNodeColor (const float &x, const float &y, const float &z, const unsigned char &r, const unsigned char &g, const unsigned char &b, const unsigned char &a)
EModelTreeNodeaverageNodeColor (const octomap::OcTreeKey &key, const unsigned char &r, const unsigned char &g, const unsigned char &b, const unsigned char &a)
EMOcTreecreate () const
void degradeOutdatedNodes (unsigned int time_thres)
 EMOcTree (std::string _filename)
 EMOcTree (double _resolution)
unsigned int getLastUpdateTime ()
std::string getTreeType () const
void insertColoredScan (const typePointCloud &coloredScan, const octomap::point3d &sensor_origin, double maxrange=-1., bool pruning=true, bool lazy_eval=false)
void integrateMissNoTime (EModelTreeNode *node) const
EModelTreeNodeintegrateNodeColor (const float &x, const float &y, const float &z, const unsigned char &r, const unsigned char &g, const unsigned char &b, const unsigned char &a)
EModelTreeNodeintegrateNodeColor (const octomap::OcTreeKey &key, const unsigned char &r, const unsigned char &g, const unsigned char &b, const unsigned char &a)
EModelTreeNodesetNodeColor (const float &x, const float &y, const float &z, const unsigned char &r, const unsigned char &g, const unsigned char &b, const unsigned char &a)
EModelTreeNodesetNodeColor (const octomap::OcTreeKey &key, const unsigned char &r, const unsigned char &g, const unsigned char &b, const unsigned char &a)
void updateInnerOccupancy ()
virtual void updateNodeLogOdds (EModelTreeNode *node, const float &update) const
virtual ~EMOcTree ()

Protected Member Functions

void updateInnerOccupancyRecurs (EModelTreeNode *node, unsigned int depth)

Static Protected Attributes

static StaticMemberInitializer ocEMOcTreeMemberInit
 to ensure static initialization (only once)

Detailed Description

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

Definition at line 147 of file octonode.h.


Member Typedef Documentation

Used node type.

Definition at line 154 of file octonode.h.

typedef octomap::point3d srs_env_model::EMOcTree::tPoint

Used point type.

Definition at line 151 of file octonode.h.

typedef pcl::PointCloud<pcl::PointXYZRGB> srs_env_model::EMOcTree::typePointCloud

Definition at line 156 of file octonode.h.


Constructor & Destructor Documentation

srs_env_model::EMOcTree::EMOcTree ( double  _resolution  ) 

Creates a new (empty) OcTree of a given resolution

Parameters:
_resolution 

Definition at line 212 of file octonode.cpp.

srs_env_model::EMOcTree::EMOcTree ( std::string  _filename  ) 

Reads an OcTree from a binary file

Parameters:
_filename 

Definition at line 223 of file octonode.cpp.

virtual srs_env_model::EMOcTree::~EMOcTree (  )  [inline, virtual]

Destructor

Definition at line 176 of file octonode.h.


Member Function Documentation

EModelTreeNode* srs_env_model::EMOcTree::averageNodeColor ( const float &  x,
const float &  y,
const float &  z,
const unsigned char &  r,
const unsigned char &  g,
const unsigned char &  b,
const unsigned char &  a 
) [inline]

Definition at line 212 of file octonode.h.

srs_env_model::EModelTreeNode * srs_env_model::EMOcTree::averageNodeColor ( const octomap::OcTreeKey &  key,
const unsigned char &  r,
const unsigned char &  g,
const unsigned char &  b,
const unsigned char &  a 
)

Definition at line 241 of file octonode.cpp.

EMOcTree* srs_env_model::EMOcTree::create (  )  const [inline]

virtual constructor: creates a new object of same type (Covariant return type requires an up-to-date compiler)

Definition at line 182 of file octonode.h.

void srs_env_model::EMOcTree::degradeOutdatedNodes ( unsigned int  time_thres  ) 

Definition at line 321 of file octonode.cpp.

unsigned int srs_env_model::EMOcTree::getLastUpdateTime (  ) 
Returns:
timestamp of last update

Definition at line 315 of file octonode.cpp.

std::string srs_env_model::EMOcTree::getTreeType (  )  const [inline]

Get tree type as a string.

Definition at line 189 of file octonode.h.

void srs_env_model::EMOcTree::insertColoredScan ( const typePointCloud coloredScan,
const octomap::point3d &  sensor_origin,
double  maxrange = -1.,
bool  pruning = true,
bool  lazy_eval = false 
)

Definition at line 343 of file octonode.cpp.

void srs_env_model::EMOcTree::integrateMissNoTime ( EModelTreeNode node  )  const

Definition at line 339 of file octonode.cpp.

EModelTreeNode* srs_env_model::EMOcTree::integrateNodeColor ( const float &  x,
const float &  y,
const float &  z,
const unsigned char &  r,
const unsigned char &  g,
const unsigned char &  b,
const unsigned char &  a 
) [inline]

Definition at line 227 of file octonode.h.

srs_env_model::EModelTreeNode * srs_env_model::EMOcTree::integrateNodeColor ( const octomap::OcTreeKey &  key,
const unsigned char &  r,
const unsigned char &  g,
const unsigned char &  b,
const unsigned char &  a 
)

Definition at line 264 of file octonode.cpp.

EModelTreeNode* srs_env_model::EMOcTree::setNodeColor ( const float &  x,
const float &  y,
const float &  z,
const unsigned char &  r,
const unsigned char &  g,
const unsigned char &  b,
const unsigned char &  a 
) [inline]

Definition at line 198 of file octonode.h.

srs_env_model::EModelTreeNode * srs_env_model::EMOcTree::setNodeColor ( const octomap::OcTreeKey &  key,
const unsigned char &  r,
const unsigned char &  g,
const unsigned char &  b,
const unsigned char &  a 
)

Definition at line 231 of file octonode.cpp.

void srs_env_model::EMOcTree::updateInnerOccupancy (  ) 

Definition at line 294 of file octonode.cpp.

void srs_env_model::EMOcTree::updateInnerOccupancyRecurs ( EModelTreeNode node,
unsigned int  depth 
) [protected]

Definition at line 298 of file octonode.cpp.

void srs_env_model::EMOcTree::updateNodeLogOdds ( EModelTreeNode node,
const float &  update 
) const [virtual]

Definition at line 333 of file octonode.cpp.


Member Data Documentation

to ensure static initialization (only once)

Definition at line 271 of file octonode.h.


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


srs_env_model
Author(s): Vit Stancl (stancl@fit.vutbr.cz), Tomas Lokaj, Jan Gorig, Michal Spanel (spanel@fit.vutbr.cz)
autogenerated on Tue Mar 5 14:34:12 2013