octomap 1.5.0
octomap::OcTreeBaseSE< NODE > Class Template Reference
Inheritance diagram for octomap::OcTreeBaseSE< NODE >:
Collaboration diagram for octomap::OcTreeBaseSE< NODE >:

Public Types

typedef leaf_iterator iterator
typedef NODE NodeType
 Make the templated NODE type available from the outside.

Public Member Functions

OcTreeKey adjustKeyAtDepth (const OcTreeKey &key, unsigned int depth) const
 Adjusts a 3D key from the lowest level to correspond to a higher depth (by shifting the key values)
unsigned short int adjustKeyAtDepth (unsigned short int key, unsigned int depth) const
 Adjusts a single key value from the lowest level to correspond to a higher depth (by shifting the key value)
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.
void clear ()
 Deletes the complete tree structure (only the root node will remain)
bool computeRay (const point3d &origin, const point3d &end, std::vector< point3d > &ray)
 Traces a ray from origin to end (excluding), returning the coordinates of all nodes traversed by the beam.
bool 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.
OcTreeKey coordToKey (const point3d &coord) const
 Converts from a 3D coordinate into a 3D addressing key.
OcTreeKey coordToKey (const point3d &coord, unsigned depth) const
 Converts from a 3D coordinate into a 3D addressing key at a given depth.
unsigned short int coordToKey (double coordinate) const
 Converts from a single coordinate into a discrete key.
unsigned short int coordToKey (double coordinate, unsigned depth) const
 Converts from a single coordinate into a discrete key at a given depth.
bool coordToKeyChecked (const point3d &coord, OcTreeKey &key) const
 Converts a 3D coordinate into a 3D OcTreeKey, with boundary checking.
bool coordToKeyChecked (const point3d &coord, unsigned depth, OcTreeKey &key) const
 Converts a 3D coordinate into a 3D OcTreeKey at a certain depth, with boundary checking.
bool coordToKeyChecked (double coordinate, unsigned short int &key) const
 Converts a single coordinate into a discrete addressing key, with boundary checking.
bool coordToKeyChecked (double coordinate, unsigned depth, unsigned short int &key) const
 Converts a single coordinate into a discrete addressing key, with boundary checking.
OcTreeBase< NODE > * create () const
 virtual constructor: creates a new object of same type (Covariant return type requires an up-to-date compiler)
OcTreeBaseImpl deepCopy () const
bool deleteNode (const point3d &value, unsigned int depth=0)
 Delete a node (if exists) given a 3d point.
bool deleteNode (float x, float y, float z, unsigned int depth=0)
 Delete a node (if exists) given a 3d point.
bool deleteNode (const OcTreeKey &key, unsigned int depth=0)
 Delete a node (if exists) given an addressing key.
 DEPRECATED (bool genKeyValueAtDepth(const unsigned short int keyval, unsigned int depth, unsigned short int &out_keyval) const )
 DEPRECATED (bool genKeyAtDepth(const OcTreeKey &key, unsigned int depth, OcTreeKey &out_key) const )
 DEPRECATED (bool genCoordFromKey(const unsigned short int &key, unsigned depth, float &coord) const )
 DEPRECATED (inline bool genCoordFromKey(const unsigned short int &key, float &coord) const)
 DEPRECATED (double genCoordFromKey(const unsigned short int &key, unsigned depth) const)
 DEPRECATED (inline double genCoordFromKey(const unsigned short int &key) const)
 DEPRECATED (inline bool genCoordFromKey(const unsigned short int &key, float &coord, unsigned depth) const)
 DEPRECATED (inline void genPos(const OcTreeKey &key, int depth, unsigned int &pos) const)
 generate child index (between 0 and 7) from key at given tree depth DEPRECATED
 DEPRECATED (inline bool genCoords(const OcTreeKey &key, unsigned int depth, point3d &point) const)
 DEPRECATED (bool genKeyValue(double coordinate, unsigned short int &keyval) const)
 DEPRECATED (bool genKey(const point3d &point, OcTreeKey &key) const )
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 ()
 Expands all pruned nodes (reverse of prune())
NODE * getLUTNeighbor (const point3d &value, OcTreeLUT::NeighborDirection dir) const
void getMetricMax (double &x, double &y, double &z) const
 maximum value of the bounding box of all known space in x, y, z
virtual void getMetricMax (double &x, double &y, double &z)
 maximum value of the bounding box of all known space in x, y, z
void getMetricMin (double &x, double &y, double &z) const
 minimum value of the bounding box of all known space in x, y, z
virtual void getMetricMin (double &x, double &y, double &z)
 minimum value of the bounding box of all known space in x, y, z
virtual void getMetricSize (double &x, double &y, double &z)
 Size of OcTree (all known space) in meters for x, y and z dimension.
double getNodeSize (unsigned depth) const
size_t getNumLeafNodes () const
 Traverses the tree to calculate the total number of leaf nodes.
double getResolution () const
NODE * getRoot () const
unsigned int getTreeDepth () const
std::string getTreeType () const
 returns actual class name as string for identification
void getUnknownLeafCenters (point3d_list &node_centers, point3d pmin, point3d pmax) const
 return centers of leafs that do NOT exist (but could) in a given bounding box
point3d keyToCoord (const OcTreeKey &key, unsigned depth) const
 converts from an addressing key at a given depth into a coordinate corresponding to the key's center
point3d keyToCoord (const OcTreeKey &key) const
 converts from an addressing key at the lowest tree level into a coordinate corresponding to the key's center
double keyToCoord (unsigned short int key, unsigned depth) const
 converts from a discrete key at a given depth into a coordinate corresponding to the key's center
double keyToCoord (unsigned short int key) const
 converts from a discrete key at the lowest tree level into a coordinate corresponding to the key's center
size_t memoryFullGrid ()
virtual size_t memoryUsage () const
virtual size_t memoryUsageNode () const
 OcTreeBaseSE (double _resolution)
bool operator== (const OcTreeBaseImpl< NODE, AbstractOcTree > &rhs) const
virtual void prune ()
 Lossless compression of OcTree: merge children to parent when there are eight children with identical values.
std::istream & readData (std::istream &s)
 Read all nodes from the input stream (without file header), for this the tree needs to be already created.
NODE * search (const point3d &value, unsigned int depth=0) const
 Search node at specified depth given a 3d point (depth=0: search full tree depth)
NODE * search (float x, float y, float z, unsigned int depth=0) const
 Search node at specified depth given a 3d point (depth=0: search full tree depth)
NODE * search (const OcTreeKey &key, unsigned int depth=0) const
 Search a node at specified depth given an addressing key (depth=0: search full tree depth)
void setResolution (double r)
 Change the resolution of the octree, scaling all voxels.
virtual size_t size () const
double volume ()
bool write (std::ostream &s) const
 Write file header and complete tree to stream (serialization)
bool write (const std::string &filename) const
 Write file header and complete tree to file (serialization)
std::ostream & writeData (std::ostream &s) const
 Write complete state of tree to stream (without file header) unmodified.
virtual ~OcTreeBaseSE ()

Static Public Member Functions

static AbstractOcTreecreateTree (const std::string id, double res)
 Creates a certain OcTree (factory pattern)
static AbstractOcTreeread (std::istream &s)
 Read the file header, create the appropriate class and deserialize.
static AbstractOcTreeread (const std::string &filename)
 Read the file header, create the appropriate class and deserialize.

Protected Member Functions

void calcMinMax ()
 recalculates min and max in x, y, z. Does nothing when tree size didn't change.
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()
void expandRecurs (NODE *node, unsigned int depth, unsigned int max_depth)
 recursive call of expand()
size_t getNumLeafNodesRecurs (const NODE *parent) const
void pruneRecurs (NODE *node, unsigned int depth, unsigned int max_depth, unsigned int &num_pruned)
 recursive call of prune()

Static Protected Member Functions

static bool readHeader (std::istream &s, std::string &id, unsigned &size, double &res)
static void registerTreeType (AbstractOcTree *tree)

Protected Attributes

KeyRay keyray
const leaf_bbx_iterator leaf_iterator_bbx_end
const leaf_iterator leaf_iterator_end
OcTreeLUTlut
double max_value [3]
 max in x, y, z
double min_value [3]
 min in x, y, z
double resolution
 in meters
double resolution_factor
 = 1. / resolution
NODE * root
bool size_changed
 flag to denote whether the octree extent changed (for lazy min/max eval)
std::vector< double > sizeLookupTable
 contains the size of a voxel at level i (0: root node). tree_depth+1 levels (incl. 0)
point3d tree_center
const unsigned int tree_depth
 Maximum tree depth is fixed to 16 currently.
const tree_iterator tree_iterator_end
const unsigned int tree_max_val
size_t tree_size
 number of nodes in tree

Static Protected Attributes

static const std::string fileHeader = "# Octomap OcTree file"

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


Member Typedef Documentation

typedef NODE octomap::OcTreeBaseImpl< NODE, AbstractOcTree >::NodeType [inherited]

Make the templated NODE type available from the outside.


Constructor & Destructor Documentation

template<class NODE >
octomap::OcTreeBaseSE< NODE >::~OcTreeBaseSE ( ) [virtual]

Member Function Documentation

OcTreeKey octomap::OcTreeBaseImpl< NODE, AbstractOcTree >::adjustKeyAtDepth ( const OcTreeKey key,
unsigned int  depth 
) const [inline, inherited]

Adjusts a 3D key from the lowest level to correspond to a higher depth (by shifting the key values)

Parameters:
keyInput key, at the lowest tree level
depthTarget depth level for the new key
Returns:
Key for the new depth level
unsigned short int octomap::OcTreeBaseImpl< NODE, AbstractOcTree >::adjustKeyAtDepth ( unsigned short int  key,
unsigned int  depth 
) const [inherited]

Adjusts a single key value from the lowest level to correspond to a higher depth (by shifting the key value)

Parameters:
keyInput key, at the lowest tree level
depthTarget depth level for the new key
Returns:
Key for the new depth level
iterator octomap::OcTreeBaseImpl< NODE, AbstractOcTree >::begin ( unsigned char  maxDepth = 0) const [inline, inherited]
Returns:
beginning of the tree as leaf iterator
leaf_iterator octomap::OcTreeBaseImpl< NODE, AbstractOcTree >::begin_leafs ( unsigned char  maxDepth = 0) const [inline, inherited]
Returns:
beginning of the tree as leaf iterator
leaf_bbx_iterator octomap::OcTreeBaseImpl< NODE, AbstractOcTree >::begin_leafs_bbx ( const OcTreeKey min,
const OcTreeKey max,
unsigned char  maxDepth = 0 
) const [inline, inherited]
Returns:
beginning of the tree as leaf iterator in a bounding box
leaf_bbx_iterator octomap::OcTreeBaseImpl< NODE, AbstractOcTree >::begin_leafs_bbx ( const point3d min,
const point3d max,
unsigned char  maxDepth = 0 
) const [inline, inherited]
Returns:
beginning of the tree as leaf iterator in a bounding box
tree_iterator octomap::OcTreeBaseImpl< NODE, AbstractOcTree >::begin_tree ( unsigned char  maxDepth = 0) const [inline, inherited]
Returns:
beginning of the tree as iterator to all nodes (incl. inner)
void octomap::OcTreeBaseImpl< NODE, AbstractOcTree >::calcMinMax ( ) [protected, inherited]

recalculates min and max in x, y, z. Does nothing when tree size didn't change.

size_t octomap::OcTreeBaseImpl< NODE, AbstractOcTree >::calcNumNodes ( ) const [inherited]

Traverses the tree to calculate the total number of nodes.

void octomap::OcTreeBaseImpl< NODE, AbstractOcTree >::calcNumNodesRecurs ( NODE *  node,
size_t &  num_nodes 
) const [protected, inherited]
void octomap::OcTreeBaseImpl< NODE, AbstractOcTree >::clear ( ) [virtual, inherited]

Deletes the complete tree structure (only the root node will remain)

Implements octomap::AbstractOcTree.

bool octomap::OcTreeBaseImpl< NODE, AbstractOcTree >::computeRay ( const point3d origin,
const point3d end,
std::vector< point3d > &  ray 
) [inherited]

Traces a ray from origin to end (excluding), returning the coordinates of all nodes traversed by the beam.

You still need to check if a node at that coordinate exists (e.g. with search()).

Note:
: use the faster computeRayKeys method if possible.
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 >
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

Reimplemented from octomap::OcTreeBaseImpl< NODE, AbstractOcTree >.

References octomap::KeyRay::addKey(), OCTOMAP_WARNING_STR, octomap::KeyRay::reset(), octomap::KeyRay::size(), and octomap::KeyRay::sizeMax().

unsigned short int octomap::OcTreeBaseImpl< NODE, AbstractOcTree >::coordToKey ( double  coordinate) const [inline, inherited]

Converts from a single coordinate into a discrete key.

unsigned short int octomap::OcTreeBaseImpl< NODE, AbstractOcTree >::coordToKey ( double  coordinate,
unsigned  depth 
) const [inherited]

Converts from a single coordinate into a discrete key at a given depth.

OcTreeKey octomap::OcTreeBaseImpl< NODE, AbstractOcTree >::coordToKey ( const point3d coord) const [inline, inherited]

Converts from a 3D coordinate into a 3D addressing key.

OcTreeKey octomap::OcTreeBaseImpl< NODE, AbstractOcTree >::coordToKey ( const point3d coord,
unsigned  depth 
) const [inline, inherited]

Converts from a 3D coordinate into a 3D addressing key at a given depth.

bool octomap::OcTreeBaseImpl< NODE, AbstractOcTree >::coordToKeyChecked ( const point3d coord,
OcTreeKey key 
) const [inherited]

Converts a 3D coordinate into a 3D OcTreeKey, with boundary checking.

Parameters:
coord3d coordinate of a point
keyvalues that will be computed, an array of fixed size 3.
Returns:
true if point is within the octree (valid), false otherwise
bool octomap::OcTreeBaseImpl< NODE, AbstractOcTree >::coordToKeyChecked ( const point3d coord,
unsigned  depth,
OcTreeKey key 
) const [inherited]

Converts a 3D coordinate into a 3D OcTreeKey at a certain depth, with boundary checking.

Parameters:
coord3d coordinate of a point
depthlevel of the key from the top
keyvalues that will be computed, an array of fixed size 3.
Returns:
true if point is within the octree (valid), false otherwise
bool octomap::OcTreeBaseImpl< NODE, AbstractOcTree >::coordToKeyChecked ( double  coordinate,
unsigned short int &  key 
) const [inherited]

Converts a single coordinate into a discrete addressing key, with boundary checking.

Parameters:
coordinate3d coordinate of a point
keydiscrete 16 bit adressing key, result
Returns:
true if coordinate is within the octree bounds (valid), false otherwise
bool octomap::OcTreeBaseImpl< NODE, AbstractOcTree >::coordToKeyChecked ( double  coordinate,
unsigned  depth,
unsigned short int &  key 
) const [inherited]

Converts a single coordinate into a discrete addressing key, with boundary checking.

Parameters:
coordinate3d coordinate of a point
depthlevel of the key from the top
keydiscrete 16 bit adressing key, result
Returns:
true if coordinate is within the octree bounds (valid), false otherwise
template<class NODE>
OcTreeBase<NODE>* octomap::OcTreeBase< NODE >::create ( ) const [inline, virtual, inherited]

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

Implements octomap::AbstractOcTree.

AbstractOcTree * octomap::AbstractOcTree::createTree ( const std::string  id,
double  res 
) [static, inherited]

Creates a certain OcTree (factory pattern)

Parameters:
idunique ID of OcTree
resresolution of OcTree
Returns:
pointer to newly created OcTree (empty). NULL if the ID is unknown!

References octomap::AbstractOcTree::create(), OCTOMAP_ERROR, and octomap::AbstractOcTree::setResolution().

Referenced by octomap::AbstractOcTree::read().

OcTreeBaseImpl octomap::OcTreeBaseImpl< NODE, AbstractOcTree >::deepCopy ( ) const [inherited]
bool octomap::OcTreeBaseImpl< NODE, AbstractOcTree >::deleteNode ( const OcTreeKey key,
unsigned int  depth = 0 
) [inherited]

Delete a node (if exists) given an addressing key.

Will always delete at the lowest level unless depth !=0, and expand pruned inner nodes as needed. Pruned nodes at level "depth" will directly be deleted as a whole.

bool octomap::OcTreeBaseImpl< NODE, AbstractOcTree >::deleteNode ( float  x,
float  y,
float  z,
unsigned int  depth = 0 
) [inherited]

Delete a node (if exists) given a 3d point.

Will always delete at the lowest level unless depth !=0, and expand pruned inner nodes as needed. Pruned nodes at level "depth" will directly be deleted as a whole.

bool octomap::OcTreeBaseImpl< NODE, AbstractOcTree >::deleteNode ( const point3d value,
unsigned int  depth = 0 
) [inherited]

Delete a node (if exists) given a 3d point.

Will always delete at the lowest level unless depth !=0, and expand pruned inner nodes as needed. Pruned nodes at level "depth" will directly be deleted as a whole.

bool octomap::OcTreeBaseImpl< NODE, AbstractOcTree >::deleteNodeRecurs ( NODE *  node,
unsigned int  depth,
unsigned int  max_depth,
const OcTreeKey key 
) [protected, inherited]

recursive call of deleteNode()

octomap::OcTreeBaseImpl< NODE, AbstractOcTree >::DEPRECATED ( bool genCoordFromKey(const unsigned short int &key, unsigned depth, float &coord)  const) [inline, inherited]
octomap::OcTreeBaseImpl< NODE, AbstractOcTree >::DEPRECATED ( inline bool genCoordFromKey(const unsigned short int &key, float &coord, unsigned depth)  const) [inline, inherited]
octomap::OcTreeBaseImpl< NODE, AbstractOcTree >::DEPRECATED ( inline bool genCoordFromKey(const unsigned short int &key, float &coord)  const) [inline, inherited]
octomap::OcTreeBaseImpl< NODE, AbstractOcTree >::DEPRECATED ( inline bool genCoords(const OcTreeKey &key, unsigned int depth, point3d &point)  const) [inline, inherited]

Will always return true, there is no more boundary check here

octomap::OcTreeBaseImpl< NODE, AbstractOcTree >::DEPRECATED ( inline double genCoordFromKey(const unsigned short int &key)  const) [inline, inherited]
octomap::OcTreeBaseImpl< NODE, AbstractOcTree >::DEPRECATED ( bool genKey(const point3d &point, OcTreeKey &key)  const) [inline, inherited]
octomap::OcTreeBaseImpl< NODE, AbstractOcTree >::DEPRECATED ( inline void genPos(const OcTreeKey &key, int depth, unsigned int &pos)  const) [inline, inherited]

generate child index (between 0 and 7) from key at given tree depth DEPRECATED

octomap::OcTreeBaseImpl< NODE, AbstractOcTree >::DEPRECATED ( double genCoordFromKey(const unsigned short int &key, unsigned depth)  const) [inline, inherited]
octomap::OcTreeBaseImpl< NODE, AbstractOcTree >::DEPRECATED ( bool genKeyAtDepth(const OcTreeKey &key, unsigned int depth, OcTreeKey &out_key)  const) [inherited]
octomap::OcTreeBaseImpl< NODE, AbstractOcTree >::DEPRECATED ( bool genKeyValue(double coordinate, unsigned short int &keyval)  const) [inline, inherited]
octomap::OcTreeBaseImpl< NODE, AbstractOcTree >::DEPRECATED ( bool genKeyValueAtDepth(const unsigned short int keyval, unsigned int depth, unsigned short int &out_keyval)  const) [inherited]
const iterator octomap::OcTreeBaseImpl< NODE, AbstractOcTree >::end ( ) const [inline, inherited]
Returns:
end of the tree as leaf iterator
const leaf_iterator octomap::OcTreeBaseImpl< NODE, AbstractOcTree >::end_leafs ( ) const [inline, inherited]
Returns:
end of the tree as leaf iterator
const leaf_bbx_iterator octomap::OcTreeBaseImpl< NODE, AbstractOcTree >::end_leafs_bbx ( ) const [inline, inherited]
Returns:
end of the tree as leaf iterator in a bounding box
const tree_iterator octomap::OcTreeBaseImpl< NODE, AbstractOcTree >::end_tree ( ) const [inline, inherited]
Returns:
end of the tree as iterator to all nodes (incl. inner)
virtual void octomap::OcTreeBaseImpl< NODE, AbstractOcTree >::expand ( ) [virtual, inherited]

Expands all pruned nodes (reverse of prune())

Note:
This is an expensive operation, especially when the tree is nearly empty!

Implements octomap::AbstractOcTree.

void octomap::OcTreeBaseImpl< NODE, AbstractOcTree >::expandRecurs ( NODE *  node,
unsigned int  depth,
unsigned int  max_depth 
) [protected, inherited]

recursive call of expand()

template<class NODE >
NODE * octomap::OcTreeBaseSE< NODE >::getLUTNeighbor ( const point3d value,
OcTreeLUT::NeighborDirection  dir 
) const

References OCTOMAP_ERROR_STR.

void octomap::OcTreeBaseImpl< NODE, AbstractOcTree >::getMetricMax ( double &  x,
double &  y,
double &  z 
) const [virtual, inherited]

maximum value of the bounding box of all known space in x, y, z

Implements octomap::AbstractOcTree.

virtual void octomap::OcTreeBaseImpl< NODE, AbstractOcTree >::getMetricMax ( double &  x,
double &  y,
double &  z 
) [virtual, inherited]

maximum value of the bounding box of all known space in x, y, z

Implements octomap::AbstractOcTree.

virtual void octomap::OcTreeBaseImpl< NODE, AbstractOcTree >::getMetricMin ( double &  x,
double &  y,
double &  z 
) [virtual, inherited]

minimum value of the bounding box of all known space in x, y, z

Implements octomap::AbstractOcTree.

void octomap::OcTreeBaseImpl< NODE, AbstractOcTree >::getMetricMin ( double &  x,
double &  y,
double &  z 
) const [virtual, inherited]

minimum value of the bounding box of all known space in x, y, z

Implements octomap::AbstractOcTree.

virtual void octomap::OcTreeBaseImpl< NODE, AbstractOcTree >::getMetricSize ( double &  x,
double &  y,
double &  z 
) [virtual, inherited]

Size of OcTree (all known space) in meters for x, y and z dimension.

Implements octomap::AbstractOcTree.

double octomap::OcTreeBaseImpl< NODE, AbstractOcTree >::getNodeSize ( unsigned  depth) const [inline, inherited]
size_t octomap::OcTreeBaseImpl< NODE, AbstractOcTree >::getNumLeafNodes ( ) const [inherited]

Traverses the tree to calculate the total number of leaf nodes.

size_t octomap::OcTreeBaseImpl< NODE, AbstractOcTree >::getNumLeafNodesRecurs ( const NODE *  parent) const [protected, inherited]
double octomap::OcTreeBaseImpl< NODE, AbstractOcTree >::getResolution ( ) const [inline, virtual, inherited]
NODE* octomap::OcTreeBaseImpl< NODE, AbstractOcTree >::getRoot ( ) const [inline, inherited]
Returns:
Pointer to the root node of the tree. This pointer should not be modified or deleted externally, the OcTree manages its memory itself.
unsigned int octomap::OcTreeBaseImpl< NODE, AbstractOcTree >::getTreeDepth ( ) const [inline, inherited]
template<class NODE>
std::string octomap::OcTreeBase< NODE >::getTreeType ( ) const [inline, virtual, inherited]

returns actual class name as string for identification

Reimplemented from octomap::OcTreeBaseImpl< NODE, AbstractOcTree >.

void octomap::OcTreeBaseImpl< NODE, AbstractOcTree >::getUnknownLeafCenters ( point3d_list node_centers,
point3d  pmin,
point3d  pmax 
) const [inherited]

return centers of leafs that do NOT exist (but could) in a given bounding box

double octomap::OcTreeBaseImpl< NODE, AbstractOcTree >::keyToCoord ( unsigned short int  key) const [inline, inherited]

converts from a discrete key at the lowest tree level into a coordinate corresponding to the key's center

double octomap::OcTreeBaseImpl< NODE, AbstractOcTree >::keyToCoord ( unsigned short int  key,
unsigned  depth 
) const [inherited]

converts from a discrete key at a given depth into a coordinate corresponding to the key's center

point3d octomap::OcTreeBaseImpl< NODE, AbstractOcTree >::keyToCoord ( const OcTreeKey key) const [inline, inherited]

converts from an addressing key at the lowest tree level into a coordinate corresponding to the key's center

point3d octomap::OcTreeBaseImpl< NODE, AbstractOcTree >::keyToCoord ( const OcTreeKey key,
unsigned  depth 
) const [inline, inherited]

converts from an addressing key at a given depth into a coordinate corresponding to the key's center

size_t octomap::OcTreeBaseImpl< NODE, AbstractOcTree >::memoryFullGrid ( ) [inherited]
Returns:
Memory usage of a full grid of the same size as the OcTree in bytes (for comparison)
virtual size_t octomap::OcTreeBaseImpl< NODE, AbstractOcTree >::memoryUsage ( ) const [virtual, inherited]
Returns:
Memory usage of the complete octree in bytes (may vary between architectures)

Implements octomap::AbstractOcTree.

virtual size_t octomap::OcTreeBaseImpl< NODE, AbstractOcTree >::memoryUsageNode ( ) const [inline, virtual, inherited]
Returns:
Memory usage of the a single octree node

Implements octomap::AbstractOcTree.

bool octomap::OcTreeBaseImpl< NODE, AbstractOcTree >::operator== ( const OcTreeBaseImpl< NODE, AbstractOcTree > &  rhs) const [inherited]
virtual void octomap::OcTreeBaseImpl< NODE, AbstractOcTree >::prune ( ) [virtual, inherited]

Lossless compression of OcTree: merge children to parent when there are eight children with identical values.

Implements octomap::AbstractOcTree.

void octomap::OcTreeBaseImpl< NODE, AbstractOcTree >::pruneRecurs ( NODE *  node,
unsigned int  depth,
unsigned int  max_depth,
unsigned int &  num_pruned 
) [protected, inherited]

recursive call of prune()

AbstractOcTree * octomap::AbstractOcTree::read ( std::istream &  s) [static, inherited]

Read the file header, create the appropriate class and deserialize.

This creates a new octree which you need to delete yourself.

References octomap::AbstractOcTree::createTree(), octomap::AbstractOcTree::fileHeader, OCTOMAP_DEBUG_STR, OCTOMAP_ERROR_STR, octomap::AbstractOcTree::readData(), octomap::AbstractOcTree::readHeader(), and octomap::AbstractOcTree::size().

AbstractOcTree * octomap::AbstractOcTree::read ( const std::string &  filename) [static, inherited]

Read the file header, create the appropriate class and deserialize.

This creates a new octree which you need to delete yourself. If you expect or requre a specific kind of octree, use dynamic_cast afterwards:

 AbstractOcTree* tree = AbstractOcTree::read("filename.ot");
 OcTree* octree = dynamic_cast<OcTree*>(tree);

References OCTOMAP_ERROR_STR.

std::istream& octomap::OcTreeBaseImpl< NODE, AbstractOcTree >::readData ( std::istream &  s) [virtual, inherited]

Read all nodes from the input stream (without file header), for this the tree needs to be already created.

For general file IO, you should probably use AbstractOcTree::read() instead.

Implements octomap::AbstractOcTree.

bool octomap::AbstractOcTree::readHeader ( std::istream &  s,
std::string &  id,
unsigned &  size,
double &  res 
) [static, protected, inherited]
NODE* octomap::OcTreeBaseImpl< NODE, AbstractOcTree >::search ( const OcTreeKey key,
unsigned int  depth = 0 
) const [inherited]

Search a node at specified depth given an addressing key (depth=0: search full tree depth)

Returns:
pointer to node if found, NULL otherwise
NODE* octomap::OcTreeBaseImpl< NODE, AbstractOcTree >::search ( float  x,
float  y,
float  z,
unsigned int  depth = 0 
) const [inherited]

Search node at specified depth given a 3d point (depth=0: search full tree depth)

Returns:
pointer to node if found, NULL otherwise
NODE* octomap::OcTreeBaseImpl< NODE, AbstractOcTree >::search ( const point3d value,
unsigned int  depth = 0 
) const [inherited]

Search node at specified depth given a 3d point (depth=0: search full tree depth)

Returns:
pointer to node if found, NULL otherwise
void octomap::OcTreeBaseImpl< NODE, AbstractOcTree >::setResolution ( double  r) [virtual, inherited]

Change the resolution of the octree, scaling all voxels.

This will not preserve the (metric) scale!

Implements octomap::AbstractOcTree.

virtual size_t octomap::OcTreeBaseImpl< NODE, AbstractOcTree >::size ( ) const [inline, virtual, inherited]
Returns:
The number of nodes in the tree

Implements octomap::AbstractOcTree.

double octomap::OcTreeBaseImpl< NODE, AbstractOcTree >::volume ( ) [inherited]
bool octomap::AbstractOcTree::write ( std::ostream &  s) const [inherited]
bool octomap::AbstractOcTree::write ( const std::string &  filename) const [inherited]

Write file header and complete tree to file (serialization)

References OCTOMAP_ERROR_STR.

Referenced by main().

std::ostream& octomap::OcTreeBaseImpl< NODE, AbstractOcTree >::writeData ( std::ostream &  s) const [virtual, inherited]

Write complete state of tree to stream (without file header) unmodified.

Pruning the tree first produces smaller files (lossless compression)

Implements octomap::AbstractOcTree.


Field Documentation

const std::string octomap::AbstractOcTree::fileHeader = "# Octomap OcTree file" [static, protected, inherited]
template<class NODE >
KeyRay octomap::OcTreeBaseSE< NODE >::keyray [protected]
template<class NODE >
OcTreeLUT* octomap::OcTreeBaseSE< NODE >::lut [protected]
double octomap::OcTreeBaseImpl< NODE, AbstractOcTree >::max_value[3] [protected, inherited]

max in x, y, z

double octomap::OcTreeBaseImpl< NODE, AbstractOcTree >::min_value[3] [protected, inherited]

min in x, y, z

double octomap::OcTreeBaseImpl< NODE, AbstractOcTree >::resolution [protected, inherited]
double octomap::OcTreeBaseImpl< NODE, AbstractOcTree >::resolution_factor [protected, inherited]

= 1. / resolution

NODE* octomap::OcTreeBaseImpl< NODE, AbstractOcTree >::root [protected, inherited]
bool octomap::OcTreeBaseImpl< NODE, AbstractOcTree >::size_changed [protected, inherited]

flag to denote whether the octree extent changed (for lazy min/max eval)

std::vector<double> octomap::OcTreeBaseImpl< NODE, AbstractOcTree >::sizeLookupTable [protected, inherited]

contains the size of a voxel at level i (0: root node). tree_depth+1 levels (incl. 0)

point3d octomap::OcTreeBaseImpl< NODE, AbstractOcTree >::tree_center [protected, inherited]
const unsigned int octomap::OcTreeBaseImpl< NODE, AbstractOcTree >::tree_depth [protected, inherited]

Maximum tree depth is fixed to 16 currently.

Referenced by octomap::OcTreeBaseSE< NODE >::OcTreeBaseSE().

const unsigned int octomap::OcTreeBaseImpl< NODE, AbstractOcTree >::tree_max_val [protected, inherited]
size_t octomap::OcTreeBaseImpl< NODE, AbstractOcTree >::tree_size [protected, inherited]

number of nodes in tree


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