OcTreeBaseImpl.h
Go to the documentation of this file.
1 /*
2  * OctoMap - An Efficient Probabilistic 3D Mapping Framework Based on Octrees
3  * http://octomap.github.com/
4  *
5  * Copyright (c) 2009-2013, K.M. Wurm and A. Hornung, University of Freiburg
6  * All rights reserved.
7  * License: New BSD
8  *
9  * Redistribution and use in source and binary forms, with or without
10  * modification, are permitted provided that the following conditions are met:
11  *
12  * * Redistributions of source code must retain the above copyright
13  * notice, this list of conditions and the following disclaimer.
14  * * Redistributions in binary form must reproduce the above copyright
15  * notice, this list of conditions and the following disclaimer in the
16  * documentation and/or other materials provided with the distribution.
17  * * Neither the name of the University of Freiburg nor the names of its
18  * contributors may be used to endorse or promote products derived from
19  * this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
22  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
23  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
24  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
25  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
26  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
27  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
28  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
29  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
30  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
31  * POSSIBILITY OF SUCH DAMAGE.
32  */
33 
34 #ifndef OCTOMAP_OCTREE_BASE_IMPL_H
35 #define OCTOMAP_OCTREE_BASE_IMPL_H
36 
37 
38 #include <list>
39 #include <limits>
40 #include <iterator>
41 #include <stack>
42 #include <bitset>
43 
44 #include "octomap_types.h"
45 #include "OcTreeKey.h"
46 #include "ScanGraph.h"
47 
48 
49 namespace octomap {
50 
51  // forward declaration for NODE children array
52  class AbstractOcTreeNode;
53 
54 
74  template <class NODE,class INTERFACE>
75  class OcTreeBaseImpl : public INTERFACE {
76 
77  public:
79  typedef NODE NodeType;
80 
81  // the actual iterator implementation is included here
82  // as a member from this file
83  #include <octomap/OcTreeIterator.hxx>
84 
85  OcTreeBaseImpl(double resolution);
86  virtual ~OcTreeBaseImpl();
87 
90 
91 
99 
102  bool operator== (const OcTreeBaseImpl<NODE,INTERFACE>& rhs) const;
103 
104  std::string getTreeType() const {return "OcTreeBaseImpl";}
105 
108  void setResolution(double r);
109  inline double getResolution() const { return resolution; }
110 
111  inline unsigned int getTreeDepth () const { return tree_depth; }
112 
113  inline double getNodeSize(unsigned depth) const {assert(depth <= tree_depth); return sizeLookupTable[depth];}
114 
120  void clearKeyRays(){
121  keyrays.clear();
122  }
123 
124  // -- Tree structure operations formerly contained in the nodes ---
125 
127  NODE* createNodeChild(NODE* node, unsigned int childIdx);
128 
130  void deleteNodeChild(NODE* node, unsigned int childIdx);
131 
133  NODE* getNodeChild(NODE* node, unsigned int childIdx) const;
134 
136  const NODE* getNodeChild(const NODE* node, unsigned int childIdx) const;
137 
140  virtual bool isNodeCollapsible(const NODE* node) const;
141 
147  bool nodeChildExists(const NODE* node, unsigned int childIdx) const;
148 
153  bool nodeHasChildren(const NODE* node) const;
154 
163  virtual void expandNode(NODE* node);
164 
169  virtual bool pruneNode(NODE* node);
170 
171 
172  // --------
173 
179  inline NODE* getRoot() const { return root; }
180 
186  NODE* search(double x, double y, double z, unsigned int depth = 0) const;
187 
193  NODE* search(const point3d& value, unsigned int depth = 0) const;
194 
200  NODE* search(const OcTreeKey& key, unsigned int depth = 0) const;
201 
207  bool deleteNode(double x, double y, double z, unsigned int depth = 0);
208 
214  bool deleteNode(const point3d& value, unsigned int depth = 0);
215 
221  bool deleteNode(const OcTreeKey& key, unsigned int depth = 0);
222 
224  void clear();
225 
232  virtual void prune();
233 
236  virtual void expand();
237 
238  // -- statistics ----------------------
239 
241  virtual inline size_t size() const { return tree_size; }
242 
244  virtual size_t memoryUsage() const;
245 
247  virtual inline size_t memoryUsageNode() const {return sizeof(NODE); };
248 
251  unsigned long long memoryFullGrid() const;
252 
253  double volume();
254 
256  virtual void getMetricSize(double& x, double& y, double& z);
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;
267 
269  size_t calcNumNodes() const;
270 
272  size_t getNumLeafNodes() const;
273 
274 
275  // -- access tree nodes ------------------
276 
278  void getUnknownLeafCenters(point3d_list& node_centers, point3d pmin, point3d pmax, unsigned int depth = 0) const;
279 
280 
281  // -- raytracing -----------------------
282 
293  bool computeRayKeys(const point3d& origin, const point3d& end, KeyRay& ray) const;
294 
295 
307  bool computeRay(const point3d& origin, const point3d& end, std::vector<point3d>& ray);
308 
309 
310  // file IO
311 
318  std::istream& readData(std::istream &s);
319 
322  std::ostream& writeData(std::ostream &s) const;
323 
324  typedef leaf_iterator iterator;
325 
327  iterator begin(unsigned char maxDepth=0) const {return iterator(this, maxDepth);};
329  const iterator end() const {return leaf_iterator_end;}; // TODO: RVE?
330 
332  leaf_iterator begin_leafs(unsigned char maxDepth=0) const {return leaf_iterator(this, maxDepth);};
334  const leaf_iterator end_leafs() const {return leaf_iterator_end;}
335 
337  leaf_bbx_iterator begin_leafs_bbx(const OcTreeKey& min, const OcTreeKey& max, unsigned char maxDepth=0) const {
338  return leaf_bbx_iterator(this, min, max, maxDepth);
339  }
341  leaf_bbx_iterator begin_leafs_bbx(const point3d& min, const point3d& max, unsigned char maxDepth=0) const {
342  return leaf_bbx_iterator(this, min, max, maxDepth);
343  }
345  const leaf_bbx_iterator end_leafs_bbx() const {return leaf_iterator_bbx_end;}
346 
348  tree_iterator begin_tree(unsigned char maxDepth=0) const {return tree_iterator(this, maxDepth);}
350  const tree_iterator end_tree() const {return tree_iterator_end;}
351 
352  //
353  // Key / coordinate conversion functions
354  //
355 
357  inline key_type coordToKey(double coordinate) const{
358  return ((int) floor(resolution_factor * coordinate)) + tree_max_val;
359  }
360 
362  key_type coordToKey(double coordinate, unsigned depth) const;
363 
364 
366  inline OcTreeKey coordToKey(const point3d& coord) const{
367  return OcTreeKey(coordToKey(coord(0)), coordToKey(coord(1)), coordToKey(coord(2)));
368  }
369 
371  inline OcTreeKey coordToKey(double x, double y, double z) const{
372  return OcTreeKey(coordToKey(x), coordToKey(y), coordToKey(z));
373  }
374 
376  inline OcTreeKey coordToKey(const point3d& coord, unsigned depth) const{
377  if (depth == tree_depth)
378  return coordToKey(coord);
379  else
380  return OcTreeKey(coordToKey(coord(0), depth), coordToKey(coord(1), depth), coordToKey(coord(2), depth));
381  }
382 
384  inline OcTreeKey coordToKey(double x, double y, double z, unsigned depth) const{
385  if (depth == tree_depth)
386  return coordToKey(x,y,z);
387  else
388  return OcTreeKey(coordToKey(x, depth), coordToKey(y, depth), coordToKey(z, depth));
389  }
390 
399  inline OcTreeKey adjustKeyAtDepth(const OcTreeKey& key, unsigned int depth) const{
400  if (depth == tree_depth)
401  return key;
402 
403  assert(depth <= tree_depth);
404  return OcTreeKey(adjustKeyAtDepth(key[0], depth), adjustKeyAtDepth(key[1], depth), adjustKeyAtDepth(key[2], depth));
405  }
406 
415  key_type adjustKeyAtDepth(key_type key, unsigned int depth) const;
416 
424  bool coordToKeyChecked(const point3d& coord, OcTreeKey& key) const;
425 
434  bool coordToKeyChecked(const point3d& coord, unsigned depth, OcTreeKey& key) const;
435 
445  bool coordToKeyChecked(double x, double y, double z, OcTreeKey& key) const;
446 
457  bool coordToKeyChecked(double x, double y, double z, unsigned depth, OcTreeKey& key) const;
458 
466  bool coordToKeyChecked(double coordinate, key_type& key) const;
467 
476  bool coordToKeyChecked(double coordinate, unsigned depth, key_type& key) const;
477 
480  double keyToCoord(key_type key, unsigned depth) const;
481 
484  inline double keyToCoord(key_type key) const{
485  return (double( (int) key - (int) this->tree_max_val ) +0.5) * this->resolution;
486  }
487 
490  inline point3d keyToCoord(const OcTreeKey& key) const{
491  return point3d(float(keyToCoord(key[0])), float(keyToCoord(key[1])), float(keyToCoord(key[2])));
492  }
493 
496  inline point3d keyToCoord(const OcTreeKey& key, unsigned depth) const{
497  return point3d(float(keyToCoord(key[0], depth)), float(keyToCoord(key[1], depth)), float(keyToCoord(key[2], depth)));
498  }
499 
500  protected:
503  OcTreeBaseImpl(double resolution, unsigned int tree_depth, unsigned int tree_max_val);
504 
506  void init();
507 
509  void calcMinMax();
510 
511  void calcNumNodesRecurs(NODE* node, size_t& num_nodes) const;
512 
514  std::istream& readNodesRecurs(NODE*, std::istream &s);
515 
517  std::ostream& writeNodesRecurs(const NODE*, std::ostream &s) const;
518 
521  void deleteNodeRecurs(NODE* node);
522 
524  bool deleteNodeRecurs(NODE* node, unsigned int depth, unsigned int max_depth, const OcTreeKey& key);
525 
527  void pruneRecurs(NODE* node, unsigned int depth, unsigned int max_depth, unsigned int& num_pruned);
528 
530  void expandRecurs(NODE* node, unsigned int depth, unsigned int max_depth);
531 
532  size_t getNumLeafNodesRecurs(const NODE* parent) const;
533 
534  private:
538 
539  protected:
540  void allocNodeChildren(NODE* node);
541 
542  NODE* root;
543 
544  // constants of the tree
545  const unsigned int tree_depth;
546  const unsigned int tree_max_val;
547  double resolution;
549 
550  size_t tree_size;
551  bool size_changed;
553 
554  point3d tree_center; // coordinate offset of tree
555 
556  double max_value[3];
557  double min_value[3];
558  std::vector<double> sizeLookupTable;
560 
562  std::vector<KeyRay> keyrays;
563 
564  const leaf_iterator leaf_iterator_end;
565  const leaf_bbx_iterator leaf_iterator_bbx_end;
566  const tree_iterator tree_iterator_end;
567 
568 
569  };
570 
571 }
572 
573 #include <octomap/OcTreeBaseImpl.hxx>
574 
575 #endif
OcTreeKey coordToKey(double x, double y, double z) const
Converts from a 3D coordinate into a 3D addressing key.
void setResolution(double r)
std::ostream & writeNodesRecurs(const NODE *, std::ostream &s) const
recursive call of writeData()
tree_iterator begin_tree(unsigned char maxDepth=0) const
const tree_iterator end_tree() const
virtual void expand()
size_t calcNumNodes() const
Traverses the tree to calculate the total number of nodes.
std::vector< double > sizeLookupTable
contains the size of a voxel at level i (0: root node). tree_depth+1 levels (incl. 0)
const iterator end() 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.
void calcNumNodesRecurs(NODE *node, size_t &num_nodes) 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.
void calcMinMax()
recalculates min and max in x, y, z. Does nothing when tree size didn&#39;t change.
uint16_t key_type
Definition: OcTreeKey.h:63
const unsigned int tree_depth
Maximum tree depth is fixed to 16 currently.
std::istream & readNodesRecurs(NODE *, std::istream &s)
recursive call of readData()
double keyToCoord(key_type key, unsigned depth) const
unsigned long long memoryFullGrid() const
void deleteNodeChild(NODE *node, unsigned int childIdx)
Deletes the i-th child of the node.
bool deleteNode(double x, double y, double z, unsigned int depth=0)
point3d keyToCoord(const OcTreeKey &key, unsigned depth) const
NODE * getNodeChild(NODE *node, unsigned int childIdx) const
double resolution
in meters
bool operator==(const OcTreeBaseImpl< NODE, INTERFACE > &rhs) const
key_type coordToKey(double coordinate) const
Converts from a single coordinate into a discrete key.
const leaf_bbx_iterator end_leafs_bbx() const
NODE * createNodeChild(NODE *node, unsigned int childIdx)
Creates (allocates) the i-th child of the node.
OcTreeBaseImpl(double resolution)
void swapContent(OcTreeBaseImpl< NODE, INTERFACE > &rhs)
leaf_iterator begin_leafs(unsigned char maxDepth=0) const
OcTreeKey coordToKey(const point3d &coord, unsigned depth) const
Converts from a 3D coordinate into a 3D addressing key at a given depth.
const leaf_bbx_iterator leaf_iterator_bbx_end
bool size_changed
flag to denote whether the octree extent changed (for lazy min/max eval)
virtual size_t memoryUsageNode() const
virtual size_t memoryUsage() const
NODE * search(double x, double y, double z, unsigned int depth=0) const
iterator begin(unsigned char maxDepth=0) const
bool coordToKeyChecked(const point3d &coord, OcTreeKey &key) const
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 expandNode(NODE *node)
double getResolution() const
double getNodeSize(unsigned depth) const
OcTreeBaseImpl< NODE, INTERFACE > & operator=(const OcTreeBaseImpl< NODE, INTERFACE > &)
leaf_bbx_iterator begin_leafs_bbx(const OcTreeKey &min, const OcTreeKey &max, unsigned char maxDepth=0) const
std::istream & readData(std::istream &s)
double keyToCoord(key_type key) const
leaf_bbx_iterator begin_leafs_bbx(const point3d &min, const point3d &max, unsigned char maxDepth=0) const
OcTreeKey adjustKeyAtDepth(const OcTreeKey &key, unsigned int depth) const
size_t getNumLeafNodes() const
Traverses the tree to calculate the total number of leaf nodes.
const tree_iterator tree_iterator_end
std::list< octomath::Vector3 > point3d_list
Definition: octomap_types.h:54
This class represents a three-dimensional vector.
Definition: Vector3.h:50
void expandRecurs(NODE *node, unsigned int depth, unsigned int max_depth)
recursive call of expand()
std::string getTreeType() const
NODE NodeType
Make the templated NODE type available from the outside.
virtual void getMetricMax(double &x, double &y, double &z)
maximum value of the bounding box of all known space in x, y, z
const leaf_iterator end_leafs() 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
double max_value[3]
max in x, y, z
void clear()
Deletes the complete tree structure.
virtual bool isNodeCollapsible(const NODE *node) const
bool computeRay(const point3d &origin, const point3d &end, std::vector< point3d > &ray)
size_t getNumLeafNodesRecurs(const NODE *parent) const
void init()
initialize non-trivial members, helper for constructors
octomath::Vector3 point3d
Use Vector3 (float precision) as a point3d in octomap.
Definition: octomap_types.h:49
point3d keyToCoord(const OcTreeKey &key) const
NODE * root
Pointer to the root NODE, NULL for empty tree.
double resolution_factor
= 1. / resolution
void pruneRecurs(NODE *node, unsigned int depth, unsigned int max_depth, unsigned int &num_pruned)
recursive call of prune()
virtual size_t size() const
std::vector< KeyRay > keyrays
data structure for ray casting, array for multithreading
void deleteNodeRecurs(NODE *node)
std::ostream & writeData(std::ostream &s) const
virtual bool pruneNode(NODE *node)
const unsigned int tree_max_val
virtual void prune()
OcTreeKey coordToKey(const point3d &coord) const
Converts from a 3D coordinate into a 3D addressing key.
bool nodeChildExists(const NODE *node, unsigned int childIdx) const
bool nodeHasChildren(const NODE *node) const
unsigned int getTreeDepth() const
const leaf_iterator leaf_iterator_end
bool computeRayKeys(const point3d &origin, const point3d &end, KeyRay &ray) const


octomap
Author(s): Kai M. Wurm , Armin Hornung
autogenerated on Mon Feb 28 2022 22:58:06