Classes | Public Member Functions | Protected Member Functions | Static Protected Attributes | List of all members
rtabmap::RtabmapColorOcTree Class Reference

#include <OctoMap.h>

Inheritance diagram for rtabmap::RtabmapColorOcTree:
Inheritance graph
[legend]

Classes

class  StaticMemberInitializer
 

Public Member Functions

RtabmapColorOcTreeNodeaverageNodeColor (const octomap::OcTreeKey &key, uint8_t r, uint8_t g, uint8_t b)
 
RtabmapColorOcTreeNodeaverageNodeColor (float x, float y, float z, uint8_t r, uint8_t g, uint8_t b)
 
RtabmapColorOcTreecreate () const
 
std::string getTreeType () const
 
RtabmapColorOcTreeNodeintegrateNodeColor (const octomap::OcTreeKey &key, uint8_t r, uint8_t g, uint8_t b)
 
RtabmapColorOcTreeNodeintegrateNodeColor (float x, float y, float z, uint8_t r, uint8_t g, uint8_t b)
 
virtual bool isNodeCollapsible (const RtabmapColorOcTreeNode *node) const
 
virtual bool pruneNode (RtabmapColorOcTreeNode *node)
 
 RtabmapColorOcTree (double resolution)
 Default constructor, sets resolution of leafs. More...
 
RtabmapColorOcTreeNodesetNodeColor (const octomap::OcTreeKey &key, uint8_t r, uint8_t g, uint8_t b)
 
RtabmapColorOcTreeNodesetNodeColor (float x, float y, float z, uint8_t r, uint8_t g, uint8_t b)
 
void updateInnerOccupancy ()
 
- Public Member Functions inherited from octomap::OccupancyOcTreeBase< RtabmapColorOcTreeNode >
bool bbxSet () const
 
virtual bool castRay (const point3d &origin, const point3d &direction, point3d &end, bool ignoreUnknownCells=false, double maxRange=-1.0) const
 
KeyBoolMap::const_iterator changedKeysBegin () const
 
KeyBoolMap::const_iterator changedKeysEnd () const
 
void computeDiscreteUpdate (const Pointcloud &scan, const octomap::point3d &origin, KeySet &free_cells, KeySet &occupied_cells, double maxrange)
 
void computeUpdate (const Pointcloud &scan, const octomap::point3d &origin, KeySet &free_cells, KeySet &occupied_cells, double maxrange)
 
void enableChangeDetection (bool enable)
 
point3d getBBXBounds () const
 
point3d getBBXCenter () const
 
point3d getBBXMax () const
 
point3d getBBXMin () const
 
bool getNormals (const point3d &point, std::vector< point3d > &normals, bool unknownStatus=true) const
 
virtual bool getRayIntersection (const point3d &origin, const point3d &direction, const point3d &center, point3d &intersection, double delta=0.0) const
 
bool inBBX (const point3d &p) const
 
bool inBBX (const OcTreeKey &key) const
 
virtual void insertPointCloud (const Pointcloud &scan, const octomap::point3d &sensor_origin, double maxrange=-1., bool lazy_eval=false, bool discretize=false)
 
virtual void insertPointCloud (const Pointcloud &scan, const point3d &sensor_origin, const pose6d &frame_origin, double maxrange=-1., bool lazy_eval=false, bool discretize=false)
 
virtual void insertPointCloud (const ScanNode &scan, double maxrange=-1., bool lazy_eval=false, bool discretize=false)
 
virtual void insertPointCloudRays (const Pointcloud &scan, const point3d &sensor_origin, double maxrange=-1., bool lazy_eval=false)
 
virtual bool insertRay (const point3d &origin, const point3d &end, double maxrange=-1.0, bool lazy_eval=false)
 
virtual void integrateHit (RtabmapColorOcTreeNode *occupancyNode) const
 
virtual void integrateMiss (RtabmapColorOcTreeNode *occupancyNode) const
 
bool isChangeDetectionEnabled () const
 
virtual void nodeToMaxLikelihood (RtabmapColorOcTreeNode *occupancyNode) const
 
virtual void nodeToMaxLikelihood (RtabmapColorOcTreeNode &occupancyNode) const
 
size_t numChangesDetected () const
 
 OccupancyOcTreeBase (double resolution)
 
 OccupancyOcTreeBase (const OccupancyOcTreeBase< RtabmapColorOcTreeNode > &rhs)
 
std::istream & readBinaryData (std::istream &s)
 
std::istream & readBinaryNode (std::istream &s, RtabmapColorOcTreeNode *node)
 
void resetChangeDetection ()
 
void setBBXMax (point3d &max)
 
void setBBXMin (point3d &min)
 
virtual RtabmapColorOcTreeNode * setNodeValue (const point3d &value, float log_odds_value, bool lazy_eval=false)
 
virtual RtabmapColorOcTreeNode * setNodeValue (const OcTreeKey &key, float log_odds_value, bool lazy_eval=false)
 
virtual RtabmapColorOcTreeNode * setNodeValue (double x, double y, double z, float log_odds_value, bool lazy_eval=false)
 
virtual void toMaxLikelihood ()
 
void updateInnerOccupancy ()
 
virtual RtabmapColorOcTreeNode * updateNode (double x, double y, double z, bool occupied, bool lazy_eval=false)
 
virtual RtabmapColorOcTreeNode * updateNode (const point3d &value, bool occupied, bool lazy_eval=false)
 
virtual RtabmapColorOcTreeNode * updateNode (const point3d &value, float log_odds_update, bool lazy_eval=false)
 
virtual RtabmapColorOcTreeNode * updateNode (double x, double y, double z, float log_odds_update, bool lazy_eval=false)
 
virtual RtabmapColorOcTreeNode * updateNode (const OcTreeKey &key, float log_odds_update, bool lazy_eval=false)
 
virtual RtabmapColorOcTreeNode * updateNode (const OcTreeKey &key, bool occupied, bool lazy_eval=false)
 
virtual void updateNodeLogOdds (RtabmapColorOcTreeNode *occupancyNode, const float &update) const
 
void useBBXLimit (bool enable)
 
std::ostream & writeBinaryData (std::ostream &s) const
 
std::ostream & writeBinaryNode (std::ostream &s, const RtabmapColorOcTreeNode *node) const
 
virtual ~OccupancyOcTreeBase ()
 
- Public Member Functions inherited from octomap::OcTreeBaseImpl< RtabmapColorOcTreeNode, AbstractOccupancyOcTree >
OcTreeKey adjustKeyAtDepth (const OcTreeKey &key, unsigned int depth) const
 
key_type adjustKeyAtDepth (key_type key, unsigned int depth) const
 
iterator begin (unsigned char maxDepth=0) const
 
leaf_iterator begin_leafs (unsigned char maxDepth=0) const
 
leaf_bbx_iterator begin_leafs_bbx (const OcTreeKey &min, const OcTreeKey &max, unsigned char maxDepth=0) const
 
leaf_bbx_iterator begin_leafs_bbx (const point3d &min, const point3d &max, unsigned char maxDepth=0) const
 
tree_iterator begin_tree (unsigned char maxDepth=0) const
 
size_t calcNumNodes () const
 
void clear ()
 
void clearKeyRays ()
 
bool computeRay (const point3d &origin, const point3d &end, std::vector< point3d > &ray)
 
bool computeRayKeys (const point3d &origin, const point3d &end, KeyRay &ray) const
 
OcTreeKey coordToKey (double x, double y, double z) const
 
OcTreeKey coordToKey (const point3d &coord, unsigned depth) const
 
OcTreeKey coordToKey (double x, double y, double z, unsigned depth) const
 
key_type coordToKey (double coordinate) const
 
key_type coordToKey (double coordinate, unsigned depth) const
 
OcTreeKey coordToKey (const point3d &coord) const
 
bool coordToKeyChecked (const point3d &coord, OcTreeKey &key) const
 
bool coordToKeyChecked (const point3d &coord, unsigned depth, OcTreeKey &key) const
 
bool coordToKeyChecked (double x, double y, double z, OcTreeKey &key) const
 
bool coordToKeyChecked (double x, double y, double z, unsigned depth, OcTreeKey &key) const
 
bool coordToKeyChecked (double coordinate, key_type &key) const
 
bool coordToKeyChecked (double coordinate, unsigned depth, key_type &key) const
 
RtabmapColorOcTreeNode * createNodeChild (RtabmapColorOcTreeNode *node, unsigned int childIdx)
 
bool deleteNode (double x, double y, double z, unsigned int depth=0)
 
bool deleteNode (const point3d &value, unsigned int depth=0)
 
bool deleteNode (const OcTreeKey &key, unsigned int depth=0)
 
void deleteNodeChild (RtabmapColorOcTreeNode *node, unsigned int childIdx)
 
const iterator end () const
 
const leaf_iterator end_leafs () const
 
const leaf_bbx_iterator end_leafs_bbx () const
 
const tree_iterator end_tree () const
 
virtual void expand ()
 
virtual void expandNode (RtabmapColorOcTreeNode *node)
 
virtual void getMetricMax (double &x, double &y, double &z)
 
void getMetricMax (double &x, double &y, double &z) const
 
virtual void getMetricMin (double &x, double &y, double &z)
 
void getMetricMin (double &x, double &y, double &z) const
 
virtual void getMetricSize (double &x, double &y, double &z)
 
virtual void getMetricSize (double &x, double &y, double &z) const
 
const RtabmapColorOcTreeNode * getNodeChild (const RtabmapColorOcTreeNode *node, unsigned int childIdx) const
 
RtabmapColorOcTreeNode * getNodeChild (RtabmapColorOcTreeNode *node, unsigned int childIdx) const
 
double getNodeSize (unsigned depth) const
 
size_t getNumLeafNodes () const
 
double getResolution () const
 
RtabmapColorOcTreeNode * getRoot () const
 
unsigned int getTreeDepth () const
 
std::string getTreeType () const
 
void getUnknownLeafCenters (point3d_list &node_centers, point3d pmin, point3d pmax, unsigned int depth=0) const
 
virtual bool isNodeCollapsible (const RtabmapColorOcTreeNode *node) const
 
point3d keyToCoord (const OcTreeKey &key) const
 
point3d keyToCoord (const OcTreeKey &key, unsigned depth) const
 
double keyToCoord (key_type key) const
 
double keyToCoord (key_type key, unsigned depth) const
 
unsigned long long memoryFullGrid () const
 
virtual size_t memoryUsage () const
 
virtual size_t memoryUsageNode () const
 
bool nodeChildExists (const RtabmapColorOcTreeNode *node, unsigned int childIdx) const
 
bool nodeHasChildren (const RtabmapColorOcTreeNode *node) const
 
 OcTreeBaseImpl (const OcTreeBaseImpl< RtabmapColorOcTreeNode, AbstractOccupancyOcTree > &rhs)
 
 OcTreeBaseImpl (double resolution)
 
bool operator== (const OcTreeBaseImpl< RtabmapColorOcTreeNode, AbstractOccupancyOcTree > &rhs) const
 
virtual void prune ()
 
virtual bool pruneNode (RtabmapColorOcTreeNode *node)
 
std::istream & readData (std::istream &s)
 
RtabmapColorOcTreeNode * search (const point3d &value, unsigned int depth=0) const
 
RtabmapColorOcTreeNode * search (const OcTreeKey &key, unsigned int depth=0) const
 
RtabmapColorOcTreeNode * search (double x, double y, double z, unsigned int depth=0) const
 
void setResolution (double r)
 
virtual size_t size () const
 
void swapContent (OcTreeBaseImpl< RtabmapColorOcTreeNode, AbstractOccupancyOcTree > &rhs)
 
double volume ()
 
std::ostream & writeData (std::ostream &s) const
 
virtual ~OcTreeBaseImpl ()
 

Protected Member Functions

void updateInnerOccupancyRecurs (RtabmapColorOcTreeNode *node, unsigned int depth)
 
- Protected Member Functions inherited from octomap::OccupancyOcTreeBase< RtabmapColorOcTreeNode >
bool integrateMissOnRay (const point3d &origin, const point3d &end, bool lazy_eval=false)
 
 OccupancyOcTreeBase (double resolution, unsigned int tree_depth, unsigned int tree_max_val)
 
RtabmapColorOcTreeNode * setNodeValueRecurs (RtabmapColorOcTreeNode *node, bool node_just_created, const OcTreeKey &key, unsigned int depth, const float &log_odds_value, bool lazy_eval=false)
 
void toMaxLikelihoodRecurs (RtabmapColorOcTreeNode *node, unsigned int depth, unsigned int max_depth)
 
void updateInnerOccupancyRecurs (RtabmapColorOcTreeNode *node, unsigned int depth)
 
RtabmapColorOcTreeNode * updateNodeRecurs (RtabmapColorOcTreeNode *node, bool node_just_created, const OcTreeKey &key, unsigned int depth, const float &log_odds_update, bool lazy_eval=false)
 
- Protected Member Functions inherited from octomap::OcTreeBaseImpl< RtabmapColorOcTreeNode, AbstractOccupancyOcTree >
void allocNodeChildren (RtabmapColorOcTreeNode *node)
 
void calcMinMax ()
 
void calcNumNodesRecurs (RtabmapColorOcTreeNode *node, size_t &num_nodes) const
 
void deleteNodeRecurs (RtabmapColorOcTreeNode *node)
 
bool deleteNodeRecurs (RtabmapColorOcTreeNode *node, unsigned int depth, unsigned int max_depth, const OcTreeKey &key)
 
void expandRecurs (RtabmapColorOcTreeNode *node, unsigned int depth, unsigned int max_depth)
 
size_t getNumLeafNodesRecurs (const RtabmapColorOcTreeNode *parent) const
 
void init ()
 
 OcTreeBaseImpl (double resolution, unsigned int tree_depth, unsigned int tree_max_val)
 
void pruneRecurs (RtabmapColorOcTreeNode *node, unsigned int depth, unsigned int max_depth, unsigned int &num_pruned)
 
std::istream & readNodesRecurs (RtabmapColorOcTreeNode *, std::istream &s)
 
std::ostream & writeNodesRecurs (const RtabmapColorOcTreeNode *, std::ostream &s) const
 

Static Protected Attributes

static StaticMemberInitializer RtabmapColorOcTreeMemberInit
 static member to ensure static initialization (only once) More...
 

Additional Inherited Members

- Public Types inherited from octomap::OcTreeBaseImpl< RtabmapColorOcTreeNode, AbstractOccupancyOcTree >
typedef leaf_iterator iterator
 
typedef RtabmapColorOcTreeNode NodeType
 
- Protected Attributes inherited from octomap::OccupancyOcTreeBase< RtabmapColorOcTreeNode >
point3d bbx_max
 
OcTreeKey bbx_max_key
 
point3d bbx_min
 
OcTreeKey bbx_min_key
 
KeyBoolMap changed_keys
 
bool use_bbx_limit
 
bool use_change_detection
 
- Protected Attributes inherited from octomap::OcTreeBaseImpl< RtabmapColorOcTreeNode, AbstractOccupancyOcTree >
std::vector< KeyRaykeyrays
 
const leaf_bbx_iterator leaf_iterator_bbx_end
 
const leaf_iterator leaf_iterator_end
 
double max_value [3]
 
double min_value [3]
 
double resolution
 
double resolution_factor
 
RtabmapColorOcTreeNode * root
 
bool size_changed
 
std::vector< double > sizeLookupTable
 
point3d tree_center
 
const unsigned int tree_depth
 
const tree_iterator tree_iterator_end
 
const unsigned int tree_max_val
 
size_t tree_size
 

Detailed Description

Definition at line 82 of file OctoMap.h.

Constructor & Destructor Documentation

rtabmap::RtabmapColorOcTree::RtabmapColorOcTree ( double  resolution)

Default constructor, sets resolution of leafs.

Definition at line 107 of file OctoMap.cpp.

Member Function Documentation

RtabmapColorOcTreeNode * rtabmap::RtabmapColorOcTree::averageNodeColor ( const octomap::OcTreeKey key,
uint8_t  r,
uint8_t  g,
uint8_t  b 
)

Definition at line 172 of file OctoMap.cpp.

RtabmapColorOcTreeNode* rtabmap::RtabmapColorOcTree::averageNodeColor ( float  x,
float  y,
float  z,
uint8_t  r,
uint8_t  g,
uint8_t  b 
)
inline

Definition at line 120 of file OctoMap.h.

RtabmapColorOcTree* rtabmap::RtabmapColorOcTree::create ( ) const
inline

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

Definition at line 90 of file OctoMap.h.

std::string rtabmap::RtabmapColorOcTree::getTreeType ( ) const
inline

Definition at line 92 of file OctoMap.h.

RtabmapColorOcTreeNode * rtabmap::RtabmapColorOcTree::integrateNodeColor ( const octomap::OcTreeKey key,
uint8_t  r,
uint8_t  g,
uint8_t  b 
)

Definition at line 189 of file OctoMap.cpp.

RtabmapColorOcTreeNode* rtabmap::RtabmapColorOcTree::integrateNodeColor ( float  x,
float  y,
float  z,
uint8_t  r,
uint8_t  g,
uint8_t  b 
)
inline

Definition at line 132 of file OctoMap.h.

bool rtabmap::RtabmapColorOcTree::isNodeCollapsible ( const RtabmapColorOcTreeNode node) const
virtual

Definition at line 148 of file OctoMap.cpp.

bool rtabmap::RtabmapColorOcTree::pruneNode ( RtabmapColorOcTreeNode node)
virtual

Prunes a node when it is collapsible. This overloaded version only considers the node occupancy for pruning, different colors of child nodes are ignored.

Returns
true if pruning was successful

Definition at line 123 of file OctoMap.cpp.

RtabmapColorOcTreeNode * rtabmap::RtabmapColorOcTree::setNodeColor ( const octomap::OcTreeKey key,
uint8_t  r,
uint8_t  g,
uint8_t  b 
)

Definition at line 112 of file OctoMap.cpp.

RtabmapColorOcTreeNode* rtabmap::RtabmapColorOcTree::setNodeColor ( float  x,
float  y,
float  z,
uint8_t  r,
uint8_t  g,
uint8_t  b 
)
inline

Definition at line 108 of file OctoMap.h.

void rtabmap::RtabmapColorOcTree::updateInnerOccupancy ( )

Definition at line 214 of file OctoMap.cpp.

void rtabmap::RtabmapColorOcTree::updateInnerOccupancyRecurs ( RtabmapColorOcTreeNode node,
unsigned int  depth 
)
protected

Definition at line 218 of file OctoMap.cpp.

Member Data Documentation

StaticMemberInitializer rtabmap::RtabmapColorOcTree::RtabmapColorOcTreeMemberInit
staticprotected

static member to ensure static initialization (only once)

Definition at line 165 of file OctoMap.h.


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


rtabmap
Author(s): Mathieu Labbe
autogenerated on Wed Jun 5 2019 22:43:43