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 
43 
44 #include "octomap_types.h"
45 #include "OcTreeKey.h"
46 #include "ScanGraph.h"
47 
48 
49 namespace octomap {
50 
51 
71  template <class NODE,class INTERFACE>
72  class OcTreeBaseImpl : public INTERFACE {
73 
74  public:
76  typedef NODE NodeType;
77 
78  // the actual iterator implementation is included here
79  // as a member from this file
80  #include <octomap/OcTreeIterator.hxx>
81 
82  OcTreeBaseImpl(double resolution);
83  virtual ~OcTreeBaseImpl();
84 
87 
88 
96 
99  bool operator== (const OcTreeBaseImpl<NODE,INTERFACE>& rhs) const;
100 
101  std::string getTreeType() const {return "OcTreeBaseImpl";}
102 
105  void setResolution(double r);
106  inline double getResolution() const { return resolution; }
107 
108  inline unsigned int getTreeDepth () const { return tree_depth; }
109 
110  inline double getNodeSize(unsigned depth) const {assert(depth <= tree_depth); return sizeLookupTable[depth];}
111 
117  inline NODE* getRoot() const { return root; }
118 
124  NODE* search(double x, double y, double z, unsigned int depth = 0) const;
125 
131  NODE* search(const point3d& value, unsigned int depth = 0) const;
132 
138  NODE* search(const OcTreeKey& key, unsigned int depth = 0) const;
139 
145  bool deleteNode(double x, double y, double z, unsigned int depth = 0);
146 
152  bool deleteNode(const point3d& value, unsigned int depth = 0);
153 
159  bool deleteNode(const OcTreeKey& key, unsigned int depth = 0);
160 
162  void clear();
163 
170  virtual void prune();
171 
174  virtual void expand();
175 
176  // -- statistics ----------------------
177 
179  virtual inline size_t size() const { return tree_size; }
180 
182  virtual size_t memoryUsage() const;
183 
185  virtual inline size_t memoryUsageNode() const {return sizeof(NODE); };
186 
189  unsigned long long memoryFullGrid() const;
190 
191  double volume();
192 
194  virtual void getMetricSize(double& x, double& y, double& z);
196  virtual void getMetricSize(double& x, double& y, double& z) const;
198  virtual void getMetricMin(double& x, double& y, double& z);
200  void getMetricMin(double& x, double& y, double& z) const;
202  virtual void getMetricMax(double& x, double& y, double& z);
204  void getMetricMax(double& x, double& y, double& z) const;
205 
207  size_t calcNumNodes() const;
208 
210  size_t getNumLeafNodes() const;
211 
212 
213  // -- access tree nodes ------------------
214 
216  void getUnknownLeafCenters(point3d_list& node_centers, point3d pmin, point3d pmax, unsigned int depth = 0) const;
217 
218 
219  // -- raytracing -----------------------
220 
231  bool computeRayKeys(const point3d& origin, const point3d& end, KeyRay& ray) const;
232 
233 
245  bool computeRay(const point3d& origin, const point3d& end, std::vector<point3d>& ray);
246 
247 
248  // file IO
249 
256  std::istream& readData(std::istream &s);
257 
260  std::ostream& writeData(std::ostream &s) const;
261 
262  typedef leaf_iterator iterator;
263 
265  iterator begin(unsigned char maxDepth=0) const {return iterator(this, maxDepth);};
267  const iterator end() const {return leaf_iterator_end;}; // TODO: RVE?
268 
270  leaf_iterator begin_leafs(unsigned char maxDepth=0) const {return leaf_iterator(this, maxDepth);};
272  const leaf_iterator end_leafs() const {return leaf_iterator_end;}
273 
275  leaf_bbx_iterator begin_leafs_bbx(const OcTreeKey& min, const OcTreeKey& max, unsigned char maxDepth=0) const {
276  return leaf_bbx_iterator(this, min, max, maxDepth);
277  }
279  leaf_bbx_iterator begin_leafs_bbx(const point3d& min, const point3d& max, unsigned char maxDepth=0) const {
280  return leaf_bbx_iterator(this, min, max, maxDepth);
281  }
283  const leaf_bbx_iterator end_leafs_bbx() const {return leaf_iterator_bbx_end;}
284 
286  tree_iterator begin_tree(unsigned char maxDepth=0) const {return tree_iterator(this, maxDepth);}
288  const tree_iterator end_tree() const {return tree_iterator_end;}
289 
290  //
291  // Key / coordinate conversion functions
292  //
293 
295  inline unsigned short int coordToKey(double coordinate) const{
296  return ((int) floor(resolution_factor * coordinate)) + tree_max_val;
297  }
298 
300  unsigned short int coordToKey(double coordinate, unsigned depth) const;
301 
302 
304  inline OcTreeKey coordToKey(const point3d& coord) const{
305  return OcTreeKey(coordToKey(coord(0)), coordToKey(coord(1)), coordToKey(coord(2)));
306  }
307 
309  inline OcTreeKey coordToKey(double x, double y, double z) const{
310  return OcTreeKey(coordToKey(x), coordToKey(y), coordToKey(z));
311  }
312 
314  inline OcTreeKey coordToKey(const point3d& coord, unsigned depth) const{
315  if (depth == tree_depth)
316  return coordToKey(coord);
317  else
318  return OcTreeKey(coordToKey(coord(0), depth), coordToKey(coord(1), depth), coordToKey(coord(2), depth));
319  }
320 
322  inline OcTreeKey coordToKey(double x, double y, double z, unsigned depth) const{
323  if (depth == tree_depth)
324  return coordToKey(x,y,z);
325  else
326  return OcTreeKey(coordToKey(x, depth), coordToKey(y, depth), coordToKey(z, depth));
327  }
328 
337  inline OcTreeKey adjustKeyAtDepth(const OcTreeKey& key, unsigned int depth) const{
338  if (depth == tree_depth)
339  return key;
340 
341  assert(depth <= tree_depth);
342  return OcTreeKey(adjustKeyAtDepth(key[0], depth), adjustKeyAtDepth(key[1], depth), adjustKeyAtDepth(key[2], depth));
343  }
344 
353  unsigned short int adjustKeyAtDepth(unsigned short int key, unsigned int depth) const;
354 
362  bool coordToKeyChecked(const point3d& coord, OcTreeKey& key) const;
363 
372  bool coordToKeyChecked(const point3d& coord, unsigned depth, OcTreeKey& key) const;
373 
383  bool coordToKeyChecked(double x, double y, double z, OcTreeKey& key) const;
384 
395  bool coordToKeyChecked(double x, double y, double z, unsigned depth, OcTreeKey& key) const;
396 
404  bool coordToKeyChecked(double coordinate, unsigned short int& key) const;
405 
414  bool coordToKeyChecked(double coordinate, unsigned depth, unsigned short int& key) const;
415 
418  double keyToCoord(unsigned short int key, unsigned depth) const;
419 
422  inline double keyToCoord(unsigned short int key) const{
423  return (double( (int) key - (int) this->tree_max_val ) +0.5) * this->resolution;
424  }
425 
428  inline point3d keyToCoord(const OcTreeKey& key) const{
429  return point3d(float(keyToCoord(key[0])), float(keyToCoord(key[1])), float(keyToCoord(key[2])));
430  }
431 
434  inline point3d keyToCoord(const OcTreeKey& key, unsigned depth) const{
435  return point3d(float(keyToCoord(key[0], depth)), float(keyToCoord(key[1], depth)), float(keyToCoord(key[2], depth)));
436  }
437 
438  protected:
441  OcTreeBaseImpl(double resolution, unsigned int tree_depth, unsigned int tree_max_val);
442 
444  void init();
445 
447  void calcMinMax();
448 
449  void calcNumNodesRecurs(NODE* node, size_t& num_nodes) const;
450 
452  bool deleteNodeRecurs(NODE* node, unsigned int depth, unsigned int max_depth, const OcTreeKey& key);
453 
455  void pruneRecurs(NODE* node, unsigned int depth, unsigned int max_depth, unsigned int& num_pruned);
456 
458  void expandRecurs(NODE* node, unsigned int depth, unsigned int max_depth);
459 
460  size_t getNumLeafNodesRecurs(const NODE* parent) const;
461 
462  private:
466 
467  protected:
468 
469  NODE* root;
470 
471  // constants of the tree
472  const unsigned int tree_depth;
473  const unsigned int tree_max_val;
474  double resolution;
476 
477  size_t tree_size;
478  bool size_changed;
480 
481  point3d tree_center; // coordinate offset of tree
482 
483  double max_value[3];
484  double min_value[3];
485  std::vector<double> sizeLookupTable;
487 
489  std::vector<KeyRay> keyrays;
490 
491  const leaf_iterator leaf_iterator_end;
492  const leaf_bbx_iterator leaf_iterator_bbx_end;
493  const tree_iterator tree_iterator_end;
494 
495 
496  };
497 
498 }
499 
500 #include <octomap/OcTreeBaseImpl.hxx>
501 
502 #endif
unsigned long long memoryFullGrid() const
size_t getNumLeafNodes() const
Traverses the tree to calculate the total number of leaf nodes.
void setResolution(double r)
virtual void expand()
size_t getNumLeafNodesRecurs(const NODE *parent) const
std::vector< double > sizeLookupTable
contains the size of a voxel at level i (0: root node). tree_depth+1 levels (incl. 0)
iterator begin(unsigned char maxDepth=0) const
virtual void getMetricSize(double &x, double &y, double &z)
Size of OcTree (all known space) in meters for x, y and z dimension.
const tree_iterator end_tree() const
void calcMinMax()
recalculates min and max in x, y, z. Does nothing when tree size didn&#39;t change.
unsigned short int coordToKey(double coordinate) const
Converts from a single coordinate into a discrete key.
virtual size_t memoryUsage() const
NODE * getRoot() const
OcTreeKey coordToKey(double x, double y, double z) const
Converts from a 3D coordinate into a 3D addressing key.
const unsigned int tree_depth
Maximum tree depth is fixed to 16 currently.
std::ostream & writeData(std::ostream &s) const
const iterator end() const
const leaf_iterator end_leafs() const
bool deleteNode(double x, double y, double z, unsigned int depth=0)
leaf_bbx_iterator begin_leafs_bbx(const OcTreeKey &min, const OcTreeKey &max, unsigned char maxDepth=0) const
bool deleteNodeRecurs(NODE *node, unsigned int depth, unsigned int max_depth, const OcTreeKey &key)
recursive call of deleteNode()
NODE * search(double x, double y, double z, unsigned int depth=0) const
double resolution
in meters
unsigned int getTreeDepth() const
point3d keyToCoord(const OcTreeKey &key, unsigned depth) const
bool coordToKeyChecked(const point3d &coord, OcTreeKey &key) const
OcTreeBaseImpl(double resolution)
point3d keyToCoord(const OcTreeKey &key) 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
void swapContent(OcTreeBaseImpl< NODE, INTERFACE > &rhs)
double keyToCoord(unsigned short int key, unsigned depth) const
bool computeRayKeys(const point3d &origin, const point3d &end, KeyRay &ray) const
const leaf_bbx_iterator leaf_iterator_bbx_end
bool size_changed
flag to denote whether the octree extent changed (for lazy min/max eval)
std::string getTreeType() 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 size_t memoryUsageNode() const
OcTreeBaseImpl< NODE, INTERFACE > & operator=(const OcTreeBaseImpl< NODE, INTERFACE > &)
leaf_bbx_iterator begin_leafs_bbx(const point3d &min, const point3d &max, unsigned char maxDepth=0) const
std::istream & readData(std::istream &s)
const tree_iterator tree_iterator_end
std::list< octomath::Vector3 > point3d_list
Definition: octomap_types.h:53
This class represents a three-dimensional vector.
Definition: Vector3.h:50
OcTreeKey coordToKey(const point3d &coord) const
Converts from a 3D coordinate into a 3D addressing key.
void expandRecurs(NODE *node, unsigned int depth, unsigned int max_depth)
recursive call of expand()
void calcNumNodesRecurs(NODE *node, size_t &num_nodes) const
NODE NodeType
Make the templated NODE type available from the outside.
tree_iterator begin_tree(unsigned char maxDepth=0) const
virtual void getMetricMax(double &x, double &y, double &z)
maximum value of the bounding box of all known space in x, y, z
double max_value[3]
max in x, y, z
void clear()
Deletes the complete tree structure.
bool computeRay(const point3d &origin, const point3d &end, std::vector< point3d > &ray)
double getResolution() const
void init()
initialize non-trivial members, helper for constructors
bool operator==(const OcTreeBaseImpl< NODE, INTERFACE > &rhs) const
octomath::Vector3 point3d
Use Vector3 (float precision) as a point3d in octomap.
Definition: octomap_types.h:48
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.
NODE * root
Pointer to the root NODE, NULL for empty tree.
double resolution_factor
= 1. / resolution
leaf_iterator begin_leafs(unsigned char maxDepth=0) const
OcTreeKey adjustKeyAtDepth(const OcTreeKey &key, unsigned int depth) const
void pruneRecurs(NODE *node, unsigned int depth, unsigned int max_depth, unsigned int &num_pruned)
recursive call of prune()
OcTreeKey coordToKey(const point3d &coord, unsigned depth) const
Converts from a 3D coordinate into a 3D addressing key at a given depth.
double getNodeSize(unsigned depth) const
std::vector< KeyRay > keyrays
data structure for ray casting, array for multithreading
const unsigned int tree_max_val
const leaf_bbx_iterator end_leafs_bbx() const
double keyToCoord(unsigned short int key) const
virtual void prune()
size_t calcNumNodes() const
Traverses the tree to calculate the total number of nodes.
virtual size_t size() const
const leaf_iterator leaf_iterator_end


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