Public Member Functions | Protected Attributes | List of all members
octomap::OcTreeBaseSE< NODE > Class Template Reference

#include <OcTreeBaseSE.h>

Inheritance diagram for octomap::OcTreeBaseSE< NODE >:
Inheritance graph
[legend]

Public Member Functions

bool computeRayKeys (const point3d &origin, const point3d &end, KeyRay &ray) const
 
NODE * getLUTNeighbor (const point3d &value, OcTreeLUT::NeighborDirection dir) const
 
 OcTreeBaseSE (double _resolution)
 
virtual ~OcTreeBaseSE ()
 
- Public Member Functions inherited from octomap::OcTreeBase< NODE >
OcTreeBase< NODE > * create () const
 
std::string getTreeType () const
 returns actual class name as string for identification More...
 
 OcTreeBase (double res)
 
- Public Member Functions inherited from octomap::OcTreeBaseImpl< NODE, AbstractOcTree >
OcTreeKey adjustKeyAtDepth (const OcTreeKey &key, unsigned int depth) const
 
unsigned short int adjustKeyAtDepth (unsigned short int 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
 Traverses the tree to calculate the total number of nodes. More...
 
void clear ()
 Deletes the complete tree structure. More...
 
bool computeRay (const point3d &origin, const point3d &end, std::vector< point3d > &ray)
 
bool computeRayKeys (const point3d &origin, const point3d &end, KeyRay &ray) const
 
unsigned short int coordToKey (double coordinate) const
 Converts from a single coordinate into a discrete key. More...
 
unsigned short int coordToKey (double coordinate, unsigned depth) const
 Converts from a single coordinate into a discrete key at a given depth. More...
 
OcTreeKey coordToKey (const point3d &coord) const
 Converts from a 3D coordinate into a 3D addressing key. More...
 
OcTreeKey coordToKey (double x, double y, double z) const
 Converts from a 3D coordinate into a 3D addressing key. More...
 
OcTreeKey coordToKey (const point3d &coord, unsigned depth) const
 Converts from a 3D coordinate into a 3D addressing key at a given depth. More...
 
OcTreeKey coordToKey (double x, double y, double z, unsigned depth) const
 Converts from a 3D coordinate into a 3D addressing key at a given depth. More...
 
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, unsigned short int &key) const
 
bool coordToKeyChecked (double coordinate, unsigned depth, unsigned short int &key) const
 
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)
 
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 getMetricMax (double &x, double &y, double &z)
 maximum value of the bounding box of all known space in x, y, z More...
 
void getMetricMax (double &x, double &y, double &z) const
 maximum value of the bounding box of all known space in x, y, z More...
 
virtual void getMetricMin (double &x, double &y, double &z)
 minimum value of the bounding box of all known space in x, y, z More...
 
void getMetricMin (double &x, double &y, double &z) const
 minimum value of the bounding box of all known space in x, y, z More...
 
virtual void getMetricSize (double &x, double &y, double &z)
 Size of OcTree (all known space) in meters for x, y and z dimension. More...
 
virtual void getMetricSize (double &x, double &y, double &z) const
 Size of OcTree (all known space) in meters for x, y and z dimension. More...
 
double getNodeSize (unsigned depth) const
 
size_t getNumLeafNodes () const
 Traverses the tree to calculate the total number of leaf nodes. More...
 
double getResolution () const
 
NODE * 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
 return centers of leafs that do NOT exist (but could) in a given bounding box More...
 
double keyToCoord (unsigned short int key, unsigned depth) const
 
double keyToCoord (unsigned short int key) const
 
point3d keyToCoord (const OcTreeKey &key) const
 
point3d keyToCoord (const OcTreeKey &key, unsigned depth) const
 
unsigned long long memoryFullGrid () const
 
virtual size_t memoryUsage () const
 
virtual size_t memoryUsageNode () const
 
 OcTreeBaseImpl (double resolution)
 
 OcTreeBaseImpl (const OcTreeBaseImpl< NODE, AbstractOcTree > &rhs)
 Deep copy constructor. More...
 
bool operator== (const OcTreeBaseImpl< NODE, AbstractOcTree > &rhs) const
 
virtual void prune ()
 
std::istream & readData (std::istream &s)
 
NODE * search (double x, double y, double z, unsigned int depth=0) const
 
NODE * search (const point3d &value, unsigned int depth=0) const
 
NODE * search (const OcTreeKey &key, unsigned int depth=0) const
 
void setResolution (double r)
 
virtual size_t size () const
 
void swapContent (OcTreeBaseImpl< NODE, AbstractOcTree > &rhs)
 
double volume ()
 
std::ostream & writeData (std::ostream &s) const
 
virtual ~OcTreeBaseImpl ()
 
- Public Member Functions inherited from octomap::AbstractOcTree
 AbstractOcTree ()
 
bool write (const std::string &filename) const
 Write file header and complete tree to file (serialization) More...
 
bool write (std::ostream &s) const
 Write file header and complete tree to stream (serialization) More...
 
virtual ~AbstractOcTree ()
 

Protected Attributes

KeyRay keyray
 
OcTreeLUTlut
 
- Protected Attributes inherited from octomap::OcTreeBaseImpl< NODE, AbstractOcTree >
std::vector< KeyRaykeyrays
 data structure for ray casting, array for multithreading More...
 
const leaf_bbx_iterator leaf_iterator_bbx_end
 
const leaf_iterator leaf_iterator_end
 
double max_value [3]
 max in x, y, z More...
 
double min_value [3]
 
double resolution
 in meters More...
 
double resolution_factor
 = 1. / resolution More...
 
NODE * root
 Pointer to the root NODE, NULL for empty tree. More...
 
bool size_changed
 flag to denote whether the octree extent changed (for lazy min/max eval) More...
 
std::vector< double > sizeLookupTable
 contains the size of a voxel at level i (0: root node). tree_depth+1 levels (incl. 0) More...
 
point3d tree_center
 
const unsigned int tree_depth
 Maximum tree depth is fixed to 16 currently. More...
 
const tree_iterator tree_iterator_end
 
const unsigned int tree_max_val
 
size_t tree_size
 

Additional Inherited Members

- Public Types inherited from octomap::OcTreeBaseImpl< NODE, AbstractOcTree >
typedef leaf_iterator iterator
 
typedef NODE NodeType
 Make the templated NODE type available from the outside. More...
 
- Static Public Member Functions inherited from octomap::AbstractOcTree
static AbstractOcTreecreateTree (const std::string id, double res)
 
static AbstractOcTreeread (const std::string &filename)
 
static AbstractOcTreeread (std::istream &s)
 
- Protected Member Functions inherited from octomap::OcTreeBaseImpl< NODE, AbstractOcTree >
void calcMinMax ()
 recalculates min and max in x, y, z. Does nothing when tree size didn't change. More...
 
void calcNumNodesRecurs (NODE *node, size_t &num_nodes) const
 
bool deleteNodeRecurs (NODE *node, unsigned int depth, unsigned int max_depth, const OcTreeKey &key)
 recursive call of deleteNode() More...
 
void expandRecurs (NODE *node, unsigned int depth, unsigned int max_depth)
 recursive call of expand() More...
 
size_t getNumLeafNodesRecurs (const NODE *parent) const
 
void init ()
 initialize non-trivial members, helper for constructors More...
 
 OcTreeBaseImpl (double resolution, unsigned int tree_depth, unsigned int tree_max_val)
 
void pruneRecurs (NODE *node, unsigned int depth, unsigned int max_depth, unsigned int &num_pruned)
 recursive call of prune() More...
 
- Static Protected Member Functions inherited from octomap::AbstractOcTree
static bool readHeader (std::istream &s, std::string &id, unsigned &size, double &res)
 
static void registerTreeType (AbstractOcTree *tree)
 
- Static Protected Attributes inherited from octomap::AbstractOcTree
static const std::string fileHeader = "# Octomap OcTree file"
 

Detailed Description

template<class NODE>
class octomap::OcTreeBaseSE< NODE >

Definition at line 46 of file OcTreeBaseSE.h.

Constructor & Destructor Documentation

template<class NODE >
octomap::OcTreeBaseSE< NODE >::OcTreeBaseSE ( double  _resolution)
template<class NODE >
virtual octomap::OcTreeBaseSE< NODE >::~OcTreeBaseSE ( )
virtual

Member Function Documentation

template<class NODE >
bool octomap::OcTreeBaseSE< NODE >::computeRayKeys ( const point3d origin,
const point3d end,
KeyRay ray 
) const

Traces a ray from origin to end (excluding), returning the coordinates of all nodes traversed by the beam. (Essentially using the DDA algorithm in 3D).

Parameters
originstart coordinate of ray
endend coordinate of ray
rayKeyRay structure that holds the keys of all nodes traversed by the ray, excluding "end"
Returns
Success of operation. Returning false usually means that one of the coordinates is out of the OcTree's range
template<class NODE >
NODE* octomap::OcTreeBaseSE< NODE >::getLUTNeighbor ( const point3d value,
OcTreeLUT::NeighborDirection  dir 
) const

Member Data Documentation

template<class NODE >
KeyRay octomap::OcTreeBaseSE< NODE >::keyray
protected

Definition at line 70 of file OcTreeBaseSE.h.

template<class NODE >
OcTreeLUT* octomap::OcTreeBaseSE< NODE >::lut
protected

Definition at line 71 of file OcTreeBaseSE.h.


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


octomap
Author(s): Kai M. Wurm , Armin Hornung
autogenerated on Mon Jun 10 2019 14:00:13