octomap 1.5.0
|
OcTree base class, to be used with with any kind of OcTreeDataNode. More...
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 an OcTreeKey of all nodes traversed by the beam. | |
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. | |
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. | |
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. | |
OcTreeBaseImpl | deepCopy () const |
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. | |
bool | deleteNode (const point3d &value, unsigned int depth=0) |
Delete a node (if exists) given a 3d point. | |
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, unsigned depth) const) | |
DEPRECATED (bool genKeyValueAtDepth(const unsigned short int keyval, unsigned int depth, unsigned short int &out_keyval) const ) | |
DEPRECATED (double genCoordFromKey(const unsigned short int &key, unsigned depth) const) | |
DEPRECATED (inline bool genCoords(const OcTreeKey &key, unsigned int depth, point3d &point) const) | |
DEPRECATED (inline bool genCoordFromKey(const unsigned short int &key, float &coord) const) | |
DEPRECATED (inline double genCoordFromKey(const unsigned short int &key) 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 (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()) | |
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 | |
virtual void | getMetricMin (double &x, double &y, double &z) |
minimum 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 | 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 |
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 | |
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 | |
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 | |
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 | |
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 | |
size_t | memoryFullGrid () |
virtual size_t | memoryUsage () const |
virtual size_t | memoryUsageNode () const |
OcTreeBaseImpl (double resolution) | |
OcTreeBaseImpl (const OcTreeBaseImpl< NODE, INTERFACE > &rhs) | |
bool | operator== (const OcTreeBaseImpl< NODE, INTERFACE > &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 OcTreeKey &key, unsigned int depth=0) const |
Search a node at specified depth given an addressing key (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 point3d &value, unsigned int depth=0) const |
Search node at specified depth given a 3d point (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 () |
std::ostream & | writeData (std::ostream &s) const |
Write complete state of tree to stream (without file header) unmodified. | |
virtual | ~OcTreeBaseImpl () |
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 |
OcTreeBaseImpl (double resolution, unsigned int tree_depth, unsigned int tree_max_val) | |
Constructor to enable derived classes to change tree constants. | |
void | pruneRecurs (NODE *node, unsigned int depth, unsigned int max_depth, unsigned int &num_pruned) |
recursive call of prune() | |
Protected Attributes | |
KeyRay | keyray |
const leaf_bbx_iterator | leaf_iterator_bbx_end |
const leaf_iterator | leaf_iterator_end |
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 |
OcTree base class, to be used with with any kind of OcTreeDataNode.
This tree implementation currently has a maximum depth of 16 nodes. For this reason, coordinates values have to be, e.g., below +/- 327.68 meters (2^15) at a maximum resolution of 0.01m.
This limitation enables the use of an efficient key generation method which uses the binary representation of the data point coordinates.
NODE | Node class to be used in tree (usually derived from OcTreeDataNode) |
INTERFACE | Interface to be derived from, should be either AbstractOcTree or AbstractOccupancyOcTree |
typedef leaf_iterator octomap::OcTreeBaseImpl< NODE, INTERFACE >::iterator |
typedef NODE octomap::OcTreeBaseImpl< NODE, INTERFACE >::NodeType |
Make the templated NODE type available from the outside.
octomap::OcTreeBaseImpl< NODE, I >::OcTreeBaseImpl | ( | double | resolution | ) |
References octomap::OcTreeBaseImpl< NODE, INTERFACE >::max_value, octomap::OcTreeBaseImpl< NODE, INTERFACE >::min_value, octomap::OcTreeBaseImpl< NODE, INTERFACE >::root, octomap::OcTreeBaseImpl< NODE, INTERFACE >::setResolution(), octomap::OcTreeBaseImpl< NODE, INTERFACE >::size_changed, and octomap::OcTreeBaseImpl< NODE, INTERFACE >::tree_size.
octomap::OcTreeBaseImpl< NODE, I >::~OcTreeBaseImpl | ( | ) | [virtual] |
octomap::OcTreeBaseImpl< NODE, I >::OcTreeBaseImpl | ( | const OcTreeBaseImpl< NODE, I > & | rhs | ) |
octomap::OcTreeBaseImpl< NODE, I >::OcTreeBaseImpl | ( | double | resolution, |
unsigned int | tree_depth, | ||
unsigned int | tree_max_val | ||
) | [protected] |
Constructor to enable derived classes to change tree constants.
This usually requires a re-implementation of some core tree-traversal functions as well!
References octomap::OcTreeBaseImpl< NODE, INTERFACE >::max_value, octomap::OcTreeBaseImpl< NODE, INTERFACE >::min_value, octomap::OcTreeBaseImpl< NODE, INTERFACE >::root, octomap::OcTreeBaseImpl< NODE, INTERFACE >::setResolution(), octomap::OcTreeBaseImpl< NODE, INTERFACE >::size_changed, and octomap::OcTreeBaseImpl< NODE, INTERFACE >::tree_size.
OcTreeKey octomap::OcTreeBaseImpl< NODE, INTERFACE >::adjustKeyAtDepth | ( | const OcTreeKey & | key, |
unsigned int | depth | ||
) | const [inline] |
Adjusts a 3D key from the lowest level to correspond to a higher depth (by shifting the key values)
key | Input key, at the lowest tree level |
depth | Target depth level for the new key |
Referenced by octomap::OcTreeBaseImpl< CountingOcTreeNode, AbstractOcTree >::adjustKeyAtDepth().
unsigned short int octomap::OcTreeBaseImpl< NODE, I >::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)
key | Input key, at the lowest tree level |
depth | Target depth level for the new key |
iterator octomap::OcTreeBaseImpl< NODE, INTERFACE >::begin | ( | unsigned char | maxDepth = 0 | ) | const [inline] |
Referenced by main().
leaf_iterator octomap::OcTreeBaseImpl< NODE, INTERFACE >::begin_leafs | ( | unsigned char | maxDepth = 0 | ) | const [inline] |
Referenced by octomap::OcTreeStamped::degradeOutdatedNodes(), and main().
leaf_bbx_iterator octomap::OcTreeBaseImpl< NODE, INTERFACE >::begin_leafs_bbx | ( | const OcTreeKey & | min, |
const OcTreeKey & | max, | ||
unsigned char | maxDepth = 0 |
||
) | const [inline] |
leaf_bbx_iterator octomap::OcTreeBaseImpl< NODE, INTERFACE >::begin_leafs_bbx | ( | const point3d & | min, |
const point3d & | max, | ||
unsigned char | maxDepth = 0 |
||
) | const [inline] |
tree_iterator octomap::OcTreeBaseImpl< NODE, INTERFACE >::begin_tree | ( | unsigned char | maxDepth = 0 | ) | const [inline] |
Referenced by octomap::OcTreeBaseImpl< NODE, INTERFACE >::operator==(), printChanges(), and octomap::ColorOcTree::writeColorHistogram().
void octomap::OcTreeBaseImpl< NODE, I >::calcMinMax | ( | ) | [protected] |
recalculates min and max in x, y, z. Does nothing when tree size didn't change.
size_t octomap::OcTreeBaseImpl< NODE, I >::calcNumNodes | ( | ) | const |
Traverses the tree to calculate the total number of nodes.
Referenced by main(), and octomap::OccupancyOcTreeBase< NODE >::readBinaryData().
void octomap::OcTreeBaseImpl< NODE, I >::calcNumNodesRecurs | ( | NODE * | node, |
size_t & | num_nodes | ||
) | const [protected] |
void octomap::OcTreeBaseImpl< NODE, I >::clear | ( | ) |
Deletes the complete tree structure (only the root node will remain)
bool octomap::OcTreeBaseImpl< NODE, I >::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.
You still need to check if a node at that coordinate exists (e.g. with search()).
origin | start coordinate of ray |
end | end coordinate of ray |
ray | KeyRay structure that holds the keys of all nodes traversed by the ray, excluding "end" |
bool octomap::OcTreeBaseImpl< NODE, I >::computeRayKeys | ( | const point3d & | origin, |
const point3d & | end, | ||
KeyRay & | ray | ||
) | const |
Traces a ray from origin to end (excluding), returning an OcTreeKey of all nodes traversed by the beam.
You still need to check if a node at that coordinate exists (e.g. with search()).
origin | start coordinate of ray |
end | end coordinate of ray |
ray | KeyRay structure that holds the keys of all nodes traversed by the ray, excluding "end" |
Reimplemented in octomap::OcTreeBaseSE< NODE >.
References octomap::KeyRay::addKey(), octomath::Vector3::norm(), OCTOMAP_WARNING_STR, octomap::KeyRay::reset(), octomap::KeyRay::size(), and octomap::KeyRay::sizeMax().
unsigned short int octomap::OcTreeBaseImpl< NODE, INTERFACE >::coordToKey | ( | double | coordinate | ) | const [inline] |
Converts from a single coordinate into a discrete key.
Referenced by octomap::OcTreeBaseImpl< CountingOcTreeNode, AbstractOcTree >::coordToKey().
unsigned short int octomap::OcTreeBaseImpl< NODE, I >::coordToKey | ( | double | coordinate, |
unsigned | depth | ||
) | const [inline] |
Converts from a single coordinate into a discrete key at a given depth.
OcTreeKey octomap::OcTreeBaseImpl< NODE, INTERFACE >::coordToKey | ( | const point3d & | coord | ) | const [inline] |
Converts from a 3D coordinate into a 3D addressing key.
OcTreeKey octomap::OcTreeBaseImpl< NODE, INTERFACE >::coordToKey | ( | const point3d & | coord, |
unsigned | depth | ||
) | const [inline] |
Converts from a 3D coordinate into a 3D addressing key at a given depth.
bool octomap::OcTreeBaseImpl< NODE, I >::coordToKeyChecked | ( | const point3d & | coord, |
OcTreeKey & | key | ||
) | const |
Converts a 3D coordinate into a 3D OcTreeKey, with boundary checking.
coord | 3d coordinate of a point |
key | values that will be computed, an array of fixed size 3. |
Referenced by octomap::ColorOcTree::averageNodeColor(), octomap::OcTreeBaseImpl< CountingOcTreeNode, AbstractOcTree >::DEPRECATED(), octomap::ColorOcTree::integrateNodeColor(), main(), octomap::ColorOcTree::setNodeColor(), and octomap::CountingOcTree::updateNode().
bool octomap::OcTreeBaseImpl< NODE, I >::coordToKeyChecked | ( | const point3d & | coord, |
unsigned | depth, | ||
OcTreeKey & | key | ||
) | const |
Converts a 3D coordinate into a 3D OcTreeKey at a certain depth, with boundary checking.
coord | 3d coordinate of a point |
depth | level of the key from the top |
key | values that will be computed, an array of fixed size 3. |
bool octomap::OcTreeBaseImpl< NODE, I >::coordToKeyChecked | ( | double | coordinate, |
unsigned short int & | key | ||
) | const |
Converts a single coordinate into a discrete addressing key, with boundary checking.
coordinate | 3d coordinate of a point |
key | discrete 16 bit adressing key, result |
bool octomap::OcTreeBaseImpl< NODE, I >::coordToKeyChecked | ( | double | coordinate, |
unsigned | depth, | ||
unsigned short int & | key | ||
) | const |
Converts a single coordinate into a discrete addressing key, with boundary checking.
coordinate | 3d coordinate of a point |
depth | level of the key from the top |
key | discrete 16 bit adressing key, result |
OcTreeBaseImpl octomap::OcTreeBaseImpl< NODE, INTERFACE >::deepCopy | ( | ) | const |
bool octomap::OcTreeBaseImpl< NODE, I >::deleteNode | ( | const OcTreeKey & | key, |
unsigned int | depth = 0 |
||
) |
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, I >::deleteNode | ( | float | x, |
float | y, | ||
float | z, | ||
unsigned int | depth = 0 |
||
) |
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, I >::deleteNode | ( | const point3d & | value, |
unsigned int | depth = 0 |
||
) |
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.
References OCTOMAP_ERROR_STR.
bool octomap::OcTreeBaseImpl< NODE, I >::deleteNodeRecurs | ( | NODE * | node, |
unsigned int | depth, | ||
unsigned int | max_depth, | ||
const OcTreeKey & | key | ||
) | [protected] |
recursive call of deleteNode()
References octomap::computeChildIdx().
octomap::OcTreeBaseImpl< NODE, INTERFACE >::DEPRECATED | ( | bool genKey(const point3d &point, OcTreeKey &key) | const | ) | [inline] |
octomap::OcTreeBaseImpl< NODE, INTERFACE >::DEPRECATED | ( | double genCoordFromKey(const unsigned short int &key, unsigned depth) | const | ) | [inline] |
octomap::OcTreeBaseImpl< NODE, INTERFACE >::DEPRECATED | ( | inline double genCoordFromKey(const unsigned short int &key) | const | ) | [inline] |
octomap::OcTreeBaseImpl< NODE, INTERFACE >::DEPRECATED | ( | inline void genPos(const OcTreeKey &key, int depth, unsigned int &pos) | const | ) | [inline] |
generate child index (between 0 and 7) from key at given tree depth DEPRECATED
octomap::OcTreeBaseImpl< NODE, INTERFACE >::DEPRECATED | ( | inline bool genCoordFromKey(const unsigned short int &key, float &coord) | const | ) | [inline] |
octomap::OcTreeBaseImpl< NODE, INTERFACE >::DEPRECATED | ( | inline bool genCoords(const OcTreeKey &key, unsigned int depth, point3d &point) | const | ) | [inline] |
Will always return true, there is no more boundary check here
octomap::OcTreeBaseImpl< NODE, INTERFACE >::DEPRECATED | ( | bool genKeyAtDepth(const OcTreeKey &key, unsigned int depth, OcTreeKey &out_key) | const | ) |
octomap::OcTreeBaseImpl< NODE, INTERFACE >::DEPRECATED | ( | inline bool genCoordFromKey(const unsigned short int &key, float &coord, unsigned depth) | const | ) | [inline] |
octomap::OcTreeBaseImpl< NODE, INTERFACE >::DEPRECATED | ( | bool genKeyValue(double coordinate, unsigned short int &keyval) | const | ) | [inline] |
octomap::OcTreeBaseImpl< NODE, INTERFACE >::DEPRECATED | ( | bool genKeyValueAtDepth(const unsigned short int keyval, unsigned int depth, unsigned short int &out_keyval) | const | ) |
octomap::OcTreeBaseImpl< NODE, INTERFACE >::DEPRECATED | ( | bool genCoordFromKey(const unsigned short int &key, unsigned depth, float &coord) | const | ) | [inline] |
const iterator octomap::OcTreeBaseImpl< NODE, INTERFACE >::end | ( | ) | const [inline] |
Referenced by octomap::OcTreeStamped::degradeOutdatedNodes(), main(), and octomap::ColorOcTree::writeColorHistogram().
const leaf_iterator octomap::OcTreeBaseImpl< NODE, INTERFACE >::end_leafs | ( | ) | const [inline] |
Referenced by octomap::OcTreeStamped::degradeOutdatedNodes(), and main().
const leaf_bbx_iterator octomap::OcTreeBaseImpl< NODE, INTERFACE >::end_leafs_bbx | ( | ) | const [inline] |
const tree_iterator octomap::OcTreeBaseImpl< NODE, INTERFACE >::end_tree | ( | ) | const [inline] |
Referenced by octomap::OcTreeBaseImpl< NODE, INTERFACE >::operator==(), printChanges(), and octomap::ColorOcTree::writeColorHistogram().
void octomap::OcTreeBaseImpl< NODE, I >::expand | ( | ) | [virtual] |
Expands all pruned nodes (reverse of prune())
Referenced by main(), and printChanges().
void octomap::OcTreeBaseImpl< NODE, I >::expandRecurs | ( | NODE * | node, |
unsigned int | depth, | ||
unsigned int | max_depth | ||
) | [protected] |
recursive call of expand()
void octomap::OcTreeBaseImpl< NODE, I >::getMetricMax | ( | double & | x, |
double & | y, | ||
double & | z | ||
) | [virtual] |
maximum value of the bounding box of all known space in x, y, z
void octomap::OcTreeBaseImpl< NODE, I >::getMetricMax | ( | double & | x, |
double & | y, | ||
double & | z | ||
) | const |
maximum value of the bounding box of all known space in x, y, z
void octomap::OcTreeBaseImpl< NODE, I >::getMetricMin | ( | double & | x, |
double & | y, | ||
double & | z | ||
) | [virtual] |
minimum value of the bounding box of all known space in x, y, z
void octomap::OcTreeBaseImpl< NODE, I >::getMetricMin | ( | double & | x, |
double & | y, | ||
double & | z | ||
) | const |
minimum value of the bounding box of all known space in x, y, z
void octomap::OcTreeBaseImpl< NODE, I >::getMetricSize | ( | double & | x, |
double & | y, | ||
double & | z | ||
) | [virtual] |
double octomap::OcTreeBaseImpl< NODE, INTERFACE >::getNodeSize | ( | unsigned | depth | ) | const [inline] |
size_t octomap::OcTreeBaseImpl< NODE, I >::getNumLeafNodes | ( | ) | const |
Traverses the tree to calculate the total number of leaf nodes.
Referenced by main().
size_t octomap::OcTreeBaseImpl< NODE, I >::getNumLeafNodesRecurs | ( | const NODE * | parent | ) | const [protected] |
double octomap::OcTreeBaseImpl< NODE, INTERFACE >::getResolution | ( | ) | const [inline] |
Referenced by getLeafNodesRecurs(), and main().
NODE* octomap::OcTreeBaseImpl< NODE, INTERFACE >::getRoot | ( | ) | const [inline] |
unsigned int octomap::OcTreeBaseImpl< NODE, INTERFACE >::getTreeDepth | ( | ) | const [inline] |
std::string octomap::OcTreeBaseImpl< NODE, INTERFACE >::getTreeType | ( | ) | const [inline] |
void octomap::OcTreeBaseImpl< NODE, I >::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
References octomath::Vector3::x(), octomath::Vector3::y(), and octomath::Vector3::z().
point3d octomap::OcTreeBaseImpl< NODE, INTERFACE >::keyToCoord | ( | const OcTreeKey & | key | ) | const [inline] |
converts from an addressing key at the lowest tree level into a coordinate corresponding to the key's center
double octomap::OcTreeBaseImpl< NODE, INTERFACE >::keyToCoord | ( | unsigned short int | key | ) | const [inline] |
converts from a discrete key at the lowest tree level into a coordinate corresponding to the key's center
double octomap::OcTreeBaseImpl< NODE, I >::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
Referenced by octomap::OcTreeBaseImpl< CountingOcTreeNode, AbstractOcTree >::DEPRECATED(), octomap::CountingOcTree::getCentersMinHitsRecurs(), octomap::OcTreeBaseImpl< CountingOcTreeNode, AbstractOcTree >::keyToCoord(), and main().
point3d octomap::OcTreeBaseImpl< NODE, INTERFACE >::keyToCoord | ( | const OcTreeKey & | key, |
unsigned | depth | ||
) | const [inline] |
converts from an addressing key at a given depth into a coordinate corresponding to the key's center
size_t octomap::OcTreeBaseImpl< NODE, I >::memoryFullGrid | ( | ) |
size_t octomap::OcTreeBaseImpl< NODE, I >::memoryUsage | ( | ) | const [virtual] |
Referenced by main().
virtual size_t octomap::OcTreeBaseImpl< NODE, INTERFACE >::memoryUsageNode | ( | ) | const [inline, virtual] |
bool octomap::OcTreeBaseImpl< NODE, I >::operator== | ( | const OcTreeBaseImpl< NODE, I > & | rhs | ) | const |
References octomap::OcTreeBaseImpl< NODE, INTERFACE >::begin_tree(), octomap::OcTreeBaseImpl< NODE, INTERFACE >::end_tree(), octomap::OcTreeBaseImpl< NODE, INTERFACE >::resolution, octomap::OcTreeBaseImpl< NODE, INTERFACE >::tree_depth, octomap::OcTreeBaseImpl< NODE, INTERFACE >::tree_max_val, and octomap::OcTreeBaseImpl< NODE, INTERFACE >::tree_size.
void octomap::OcTreeBaseImpl< NODE, I >::prune | ( | ) | [virtual] |
Lossless compression of OcTree: merge children to parent when there are eight children with identical values.
Referenced by main(), and printChanges().
void octomap::OcTreeBaseImpl< NODE, I >::pruneRecurs | ( | NODE * | node, |
unsigned int | depth, | ||
unsigned int | max_depth, | ||
unsigned int & | num_pruned | ||
) | [protected] |
recursive call of prune()
std::istream & octomap::OcTreeBaseImpl< NODE, I >::readData | ( | std::istream & | s | ) |
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.
References OCTOMAP_ERROR_STR, and OCTOMAP_WARNING_STR.
Referenced by main().
NODE * octomap::OcTreeBaseImpl< NODE, I >::search | ( | const point3d & | value, |
unsigned int | depth = 0 |
||
) | const |
Search node at specified depth given a 3d point (depth=0: search full tree depth)
References OCTOMAP_ERROR_STR.
NODE * octomap::OcTreeBaseImpl< NODE, I >::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)
References octomap::computeChildIdx().
NODE * octomap::OcTreeBaseImpl< NODE, I >::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)
Referenced by octomap::ColorOcTree::averageNodeColor(), octomap::ColorOcTree::integrateNodeColor(), main(), printChanges(), and octomap::ColorOcTree::setNodeColor().
void octomap::OcTreeBaseImpl< NODE, I >::setResolution | ( | double | r | ) |
Change the resolution of the octree, scaling all voxels.
This will not preserve the (metric) scale!
Referenced by main(), and octomap::OcTreeBaseImpl< NODE, INTERFACE >::OcTreeBaseImpl().
virtual size_t octomap::OcTreeBaseImpl< NODE, INTERFACE >::size | ( | ) | const [inline, virtual] |
Referenced by main().
double octomap::OcTreeBaseImpl< NODE, I >::volume | ( | ) |
std::ostream & octomap::OcTreeBaseImpl< NODE, I >::writeData | ( | std::ostream & | s | ) | const |
Write complete state of tree to stream (without file header) unmodified.
Pruning the tree first produces smaller files (lossless compression)
KeyRay octomap::OcTreeBaseImpl< NODE, INTERFACE >::keyray [protected] |
Reimplemented in octomap::OcTreeBaseSE< NODE >.
const leaf_bbx_iterator octomap::OcTreeBaseImpl< NODE, INTERFACE >::leaf_iterator_bbx_end [protected] |
const leaf_iterator octomap::OcTreeBaseImpl< NODE, INTERFACE >::leaf_iterator_end [protected] |
double octomap::OcTreeBaseImpl< NODE, INTERFACE >::max_value[3] [protected] |
max in x, y, z
Referenced by octomap::OcTreeBaseImpl< NODE, INTERFACE >::OcTreeBaseImpl().
double octomap::OcTreeBaseImpl< NODE, INTERFACE >::min_value[3] [protected] |
min in x, y, z
Referenced by octomap::OcTreeBaseImpl< NODE, INTERFACE >::OcTreeBaseImpl().
double octomap::OcTreeBaseImpl< NODE, INTERFACE >::resolution [protected] |
in meters
Referenced by octomap::OcTreeStamped::create(), octomap::OcTree::create(), octomap::ColorOcTree::create(), octomap::OcTreeBaseImpl< CountingOcTreeNode, AbstractOcTree >::getResolution(), octomap::OcTreeBaseImpl< CountingOcTreeNode, AbstractOcTree >::keyToCoord(), octomap::OcTreeBaseImpl< NODE, INTERFACE >::OcTreeBaseImpl(), and octomap::OcTreeBaseImpl< NODE, INTERFACE >::operator==().
double octomap::OcTreeBaseImpl< NODE, INTERFACE >::resolution_factor [protected] |
= 1. / resolution
Referenced by octomap::OcTreeBaseImpl< CountingOcTreeNode, AbstractOcTree >::coordToKey().
NODE* octomap::OcTreeBaseImpl< NODE, INTERFACE >::root [protected] |
Referenced by octomap::CountingOcTree::getCentersMinHits(), octomap::OcTreeStamped::getLastUpdateTime(), octomap::OcTreeBaseImpl< CountingOcTreeNode, AbstractOcTree >::getRoot(), octomap::OcTreeBaseImpl< NODE, INTERFACE >::OcTreeBaseImpl(), octomap::ColorOcTree::updateInnerOccupancy(), and octomap::CountingOcTree::updateNode().
bool octomap::OcTreeBaseImpl< NODE, INTERFACE >::size_changed [protected] |
flag to denote whether the octree extent changed (for lazy min/max eval)
Referenced by octomap::OcTreeBaseImpl< NODE, INTERFACE >::OcTreeBaseImpl().
std::vector<double> octomap::OcTreeBaseImpl< NODE, INTERFACE >::sizeLookupTable [protected] |
contains the size of a voxel at level i (0: root node). tree_depth+1 levels (incl. 0)
Referenced by octomap::OcTreeBaseImpl< CountingOcTreeNode, AbstractOcTree >::getNodeSize().
point3d octomap::OcTreeBaseImpl< NODE, INTERFACE >::tree_center [protected] |
const unsigned int octomap::OcTreeBaseImpl< NODE, INTERFACE >::tree_depth [protected] |
Maximum tree depth is fixed to 16 currently.
Referenced by octomap::OcTreeBaseImpl< CountingOcTreeNode, AbstractOcTree >::adjustKeyAtDepth(), octomap::OcTreeBaseImpl< CountingOcTreeNode, AbstractOcTree >::coordToKey(), octomap::CountingOcTree::getCentersMinHits(), octomap::OcTreeBaseImpl< CountingOcTreeNode, AbstractOcTree >::getNodeSize(), octomap::OcTreeBaseImpl< CountingOcTreeNode, AbstractOcTree >::getTreeDepth(), octomap::OcTreeBaseImpl< NODE, INTERFACE >::operator==(), octomap::ColorOcTree::updateInnerOccupancyRecurs(), and octomap::CountingOcTree::updateNode().
const tree_iterator octomap::OcTreeBaseImpl< NODE, INTERFACE >::tree_iterator_end [protected] |
const unsigned int octomap::OcTreeBaseImpl< NODE, INTERFACE >::tree_max_val [protected] |
Referenced by octomap::OcTreeBaseImpl< CountingOcTreeNode, AbstractOcTree >::coordToKey(), octomap::CountingOcTree::getCentersMinHits(), octomap::CountingOcTree::getCentersMinHitsRecurs(), octomap::OcTreeBaseImpl< CountingOcTreeNode, AbstractOcTree >::keyToCoord(), and octomap::OcTreeBaseImpl< NODE, INTERFACE >::operator==().
size_t octomap::OcTreeBaseImpl< NODE, INTERFACE >::tree_size [protected] |