CountingOcTree.cpp
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 #include <cassert>
35 #include <octomap/CountingOcTree.h>
36 
37 namespace octomap {
38 
39 
41 
43  : OcTreeDataNode<unsigned int>(0)
44  {
45  }
46 
48 
49  }
50 
52  CountingOcTree::CountingOcTree(double resolution)
53  : OcTreeBase<CountingOcTreeNode>(resolution) {
55  }
56 
58 
59  OcTreeKey key;
60  if (!coordToKeyChecked(value, key)) return NULL;
61  return updateNode(key);
62  }
63 
64 
65  // Note: do not inline this method, will decrease speed (KMW)
67 
68  CountingOcTreeNode* curNode (root);
69  curNode->increaseCount();
70 
71 
72  // follow or construct nodes down to last level...
73  for (int i=(tree_depth-1); i>=0; i--) {
74 
75  unsigned int pos = computeChildIdx(k, i);
76 
77  // requested node does not exist
78  if (!nodeChildExists(curNode, pos)) {
79  createNodeChild(curNode, pos);
80  }
81  // descent tree
82  curNode = getNodeChild(curNode, pos);
83  curNode->increaseCount(); // modify traversed nodes
84  }
85 
86  return curNode;
87  }
88 
89 
90  void CountingOcTree::getCentersMinHits(point3d_list& node_centers, unsigned int min_hits) const {
91 
92  OcTreeKey root_key;
93  root_key[0] = root_key[1] = root_key[2] = this->tree_max_val;
94  getCentersMinHitsRecurs(node_centers, min_hits, this->tree_depth, this->root, 0, root_key);
95  }
96 
97 
99  unsigned int& min_hits,
100  unsigned int max_depth,
101  CountingOcTreeNode* node, unsigned int depth,
102  const OcTreeKey& parent_key) const {
103 
104  if (depth < max_depth && nodeHasChildren(node)) {
105 
106  key_type center_offset_key = this->tree_max_val >> (depth + 1);
107  OcTreeKey search_key;
108 
109  for (unsigned int i=0; i<8; ++i) {
110  if (nodeChildExists(node,i)) {
111  computeChildKey(i, center_offset_key, parent_key, search_key);
112  getCentersMinHitsRecurs(node_centers, min_hits, max_depth, getNodeChild(node,i), depth+1, search_key);
113  }
114  }
115  }
116 
117  else { // max level reached
118 
119  if (node->getCount() >= min_hits) {
120  node_centers.push_back(this->keyToCoord(parent_key, depth));
121  }
122  }
123  }
124 
126 
127 
128 } // namespace
uint16_t key_type
Definition: OcTreeKey.h:64
const unsigned int tree_depth
Maximum tree depth is fixed to 16 currently.
bool coordToKeyChecked(const point3d &coord, OcTreeKey &key) const
CountingOcTreeNode * createNodeChild(CountingOcTreeNode *node, unsigned int childIdx)
Creates (allocates) the i-th child of the node.
CountingOcTreeNode * getNodeChild(CountingOcTreeNode *node, unsigned int childIdx) const
CountingOcTree(double resolution)
Default constructor, sets resolution of leafs.
uint8_t computeChildIdx(const OcTreeKey &key, int depth)
generate child index (between 0 and 7) from key at given tree depth
Definition: OcTreeKey.h:206
void getCentersMinHits(point3d_list &node_centers, unsigned int min_hits) const
bool nodeHasChildren(const CountingOcTreeNode *node) const
void getCentersMinHitsRecurs(point3d_list &node_centers, unsigned int &min_hits, unsigned int max_depth, CountingOcTreeNode *node, unsigned int depth, const OcTreeKey &parent_key) const
static StaticMemberInitializer countingOcTreeMemberInit
static member to ensure static initialization (only once)
std::list< octomath::Vector3 > point3d_list
Definition: octomap_types.h:53
This class represents a three-dimensional vector.
Definition: Vector3.h:50
void computeChildKey(unsigned int pos, key_type center_offset_key, const OcTreeKey &parent_key, OcTreeKey &child_key)
Definition: OcTreeKey.h:192
CountingOcTreeNode()
implementation of CountingOcTreeNode -------------------------------—
virtual CountingOcTreeNode * updateNode(const point3d &value)
CountingOcTreeNode * root
Pointer to the root NODE, NULL for empty tree.
bool nodeChildExists(const CountingOcTreeNode *node, unsigned int childIdx) const
unsigned int getCount() const
double keyToCoord(key_type key, unsigned depth) const


octomap
Author(s): Kai M. Wurm , Armin Hornung
autogenerated on Wed Jun 5 2019 19:26:27