Go to the documentation of this file.
34 #ifndef OCTOMAP_OCTREE_BASE_IMPL_H
35 #define OCTOMAP_OCTREE_BASE_IMPL_H
52 class AbstractOcTreeNode;
74 template <
class NODE,
class INTERFACE>
83 #include <octomap/OcTreeIterator.hxx>
133 NODE*
getNodeChild(NODE* node,
unsigned int childIdx)
const;
136 const NODE*
getNodeChild(
const NODE* node,
unsigned int childIdx)
const;
186 NODE*
search(
double x,
double y,
double z,
unsigned int depth = 0)
const;
193 NODE*
search(
const point3d& value,
unsigned int depth = 0)
const;
207 bool deleteNode(
double x,
double y,
double z,
unsigned int depth = 0);
232 virtual void prune();
258 virtual void getMetricSize(
double& x,
double& y,
double& z)
const;
260 virtual void getMetricMin(
double& x,
double& y,
double& z);
262 void getMetricMin(
double& x,
double& y,
double& z)
const;
264 virtual void getMetricMax(
double& x,
double& y,
double& z);
266 void getMetricMax(
double& x,
double& y,
double& z)
const;
318 std::istream&
readData(std::istream &s);
322 std::ostream&
writeData(std::ostream &s)
const;
332 leaf_iterator
begin_leafs(
unsigned char maxDepth=0)
const {
return leaf_iterator(
this, maxDepth);}
338 return leaf_bbx_iterator(
this, min, max, maxDepth);
342 return leaf_bbx_iterator(
this, min, max, maxDepth);
348 tree_iterator
begin_tree(
unsigned char maxDepth=0)
const {
return tree_iterator(
this, maxDepth);}
527 void pruneRecurs(NODE* node,
unsigned int depth,
unsigned int max_depth,
unsigned int& num_pruned);
530 void expandRecurs(NODE* node,
unsigned int depth,
unsigned int max_depth);
573 #include <octomap/OcTreeBaseImpl.hxx>
const leaf_bbx_iterator end_leafs_bbx() const
NODE NodeType
Make the templated NODE type available from the outside.
std::vector< double > sizeLookupTable
contains the size of a voxel at level i (0: root node). tree_depth+1 levels (incl....
point3d keyToCoord(const OcTreeKey &key, unsigned depth) const
void pruneRecurs(NODE *node, unsigned int depth, unsigned int max_depth, unsigned int &num_pruned)
recursive call of prune()
virtual size_t size() const
size_t calcNumNodes() const
Traverses the tree to calculate the total number of nodes.
void deleteNodeChild(NODE *node, unsigned int childIdx)
Deletes the i-th child of the node.
const leaf_iterator end_leafs() const
unsigned long long memoryFullGrid() const
virtual bool isNodeCollapsible(const NODE *node) const
virtual void expandNode(NODE *node)
OcTreeBaseImpl< NODE, INTERFACE > & operator=(const OcTreeBaseImpl< NODE, INTERFACE > &)
bool computeRayKeys(const point3d &origin, const point3d &end, KeyRay &ray) const
point3d keyToCoord(const OcTreeKey &key) const
void calcNumNodesRecurs(NODE *node, size_t &num_nodes) const
const unsigned int tree_max_val
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
virtual void getMetricMax(double &x, double &y, double &z)
maximum value of the bounding box of all known space in x, y, z
bool computeRay(const point3d &origin, const point3d &end, std::vector< point3d > &ray)
leaf_iterator begin_leafs(unsigned char maxDepth=0) const
OcTreeKey coordToKey(const point3d &coord) const
Converts from a 3D coordinate into a 3D addressing key.
double keyToCoord(key_type key) const
OcTreeKey coordToKey(const point3d &coord, unsigned depth) const
Converts from a 3D coordinate into a 3D addressing key at a given depth.
const unsigned int tree_depth
Maximum tree depth is fixed to 16 currently.
std::ostream & writeData(std::ostream &s) const
double resolution_factor
= 1. / resolution
bool deleteNode(double x, double y, double z, unsigned int depth=0)
const leaf_bbx_iterator leaf_iterator_bbx_end
NODE * root
Pointer to the root NODE, NULL for empty tree.
This class represents a three-dimensional vector.
NODE * search(double x, double y, double z, unsigned int depth=0) const
double getResolution() const
virtual bool pruneNode(NODE *node)
const tree_iterator end_tree() const
OcTreeKey coordToKey(double x, double y, double z) const
Converts from a 3D coordinate into a 3D addressing key.
void init()
initialize non-trivial members, helper for constructors
OcTreeBaseImpl(double resolution)
void deleteNodeRecurs(NODE *node)
bool operator==(const OcTreeBaseImpl< NODE, INTERFACE > &rhs) const
key_type coordToKey(double coordinate) const
Converts from a single coordinate into a discrete key.
virtual ~OcTreeBaseImpl()
void calcMinMax()
recalculates min and max in x, y, z. Does nothing when tree size didn't change.
std::istream & readData(std::istream &s)
double max_value[3]
max in x, y, z
std::istream & readNodesRecurs(NODE *, std::istream &s)
recursive call of readData()
bool nodeChildExists(const NODE *node, unsigned int childIdx) const
bool nodeHasChildren(const NODE *node) const
void setResolution(double r)
iterator begin(unsigned char maxDepth=0) const
bool coordToKeyChecked(const point3d &coord, OcTreeKey &key) const
NODE * createNodeChild(NODE *node, unsigned int childIdx)
Creates (allocates) the i-th child of the node.
double keyToCoord(key_type key, unsigned depth) const
tree_iterator begin_tree(unsigned char maxDepth=0) const
std::list< octomath::Vector3 > point3d_list
OcTreeKey adjustKeyAtDepth(const OcTreeKey &key, unsigned int depth) const
std::vector< KeyRay > keyrays
data structure for ray casting, array for multithreading
double getNodeSize(unsigned depth) const
void swapContent(OcTreeBaseImpl< NODE, INTERFACE > &rhs)
size_t getNumLeafNodes() const
Traverses the tree to calculate the total number of leaf nodes.
NODE * getNodeChild(NODE *node, unsigned int childIdx) const
const iterator end() const
leaf_bbx_iterator begin_leafs_bbx(const point3d &min, const point3d &max, unsigned char maxDepth=0) const
virtual size_t memoryUsageNode() const
const leaf_iterator leaf_iterator_end
bool size_changed
flag to denote whether the octree extent changed (for lazy min/max eval)
std::string getTreeType() const
virtual size_t memoryUsage() const
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.
double resolution
in meters
octomath::Vector3 point3d
Use Vector3 (float precision) as a point3d in octomap.
std::ostream & writeNodesRecurs(const NODE *, std::ostream &s) const
recursive call of writeData()
void clear()
Deletes the complete tree structure.
void expandRecurs(NODE *node, unsigned int depth, unsigned int max_depth)
recursive call of expand()
leaf_bbx_iterator begin_leafs_bbx(const OcTreeKey &min, const OcTreeKey &max, unsigned char maxDepth=0) const
void allocNodeChildren(NODE *node)
virtual void getMetricSize(double &x, double &y, double &z)
Size of OcTree (all known space) in meters for x, y and z dimension.
size_t getNumLeafNodesRecurs(const NODE *parent) const
const tree_iterator tree_iterator_end
unsigned int getTreeDepth() const
virtual void getMetricMin(double &x, double &y, double &z)
minimum value of the bounding box of all known space in x, y, z
octomap
Author(s): Kai M. Wurm
, Armin Hornung
autogenerated on Tue Dec 12 2023 03:39:40