1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
|
diff --git a/octomap/include/octomap/OcTreeIterator.hxx b/octomap/include/octomap/OcTreeIterator.hxx
index 66ae63f8..5f2dd7e5 100644
--- ros-humble-octovis-1.9.8_org/include/octomap/OcTreeIterator.hxx
+++ ros-humble-octovis-1.9.8/include/octomap/OcTreeIterator.hxx
@@ -39,8 +39,15 @@
* const with respect to the tree. This file is included within
* OcTreeBaseImpl.h, you should probably not include this directly.
*/
- class iterator_base : public std::iterator<std::forward_iterator_tag, NodeType>{
+ template<class NodeType>
+ class iterator_base{
public:
+ using iterator_category = std::forward_iterator_tag;
+ using value_type = NodeType;
+ using difference_type = NodeType;
+ using pointer = NodeType*;
+ using reference = NodeType&;
+
struct StackElement;
/// Default ctor, only used for the end-iterator
iterator_base() : tree(NULL), maxDepth(0){}
@@ -204,16 +211,16 @@
* }
* @endcode
*/
- class tree_iterator : public iterator_base {
+ class tree_iterator : public iterator_base<NodeType> {
public:
- tree_iterator() : iterator_base(){}
+ tree_iterator() : iterator_base<NodeType>(){}
/**
* Constructor of the iterator.
*
* @param ptree OcTreeBaseImpl on which the iterator is used on
* @param depth Maximum depth to traverse the tree. 0 (default): unlimited
*/
- tree_iterator(OcTreeBaseImpl<NodeType,INTERFACE> const* ptree, uint8_t depth=0) : iterator_base(ptree, depth) {};
+ tree_iterator(OcTreeBaseImpl<NodeType,INTERFACE> const* ptree, uint8_t depth=0) : iterator_base<NodeType>(ptree, depth) {};
/// postfix increment operator of iterator (it++)
tree_iterator operator++(int){
@@ -260,9 +267,9 @@
* @endcode
*
*/
- class leaf_iterator : public iterator_base {
+ class leaf_iterator : public iterator_base<NodeType> {
public:
- leaf_iterator() : iterator_base(){}
+ leaf_iterator() : iterator_base<NodeType>(){}
/**
* Constructor of the iterator.
@@ -270,7 +277,7 @@
* @param ptree OcTreeBaseImpl on which the iterator is used on
* @param depth Maximum depth to traverse the tree. 0 (default): unlimited
*/
- leaf_iterator(OcTreeBaseImpl<NodeType, INTERFACE> const* ptree, uint8_t depth=0) : iterator_base(ptree, depth) {
+ leaf_iterator(OcTreeBaseImpl<NodeType, INTERFACE> const* ptree, uint8_t depth=0) : iterator_base<NodeType>(ptree, depth) {
// tree could be empty (= no stack)
if (this->stack.size() > 0){
// skip forward to next valid leaf node:
@@ -280,7 +287,7 @@
}
}
- leaf_iterator(const leaf_iterator& other) : iterator_base(other) {};
+ leaf_iterator(const leaf_iterator& other) : iterator_base<NodeType>(other) {};
/// postfix increment operator of iterator (it++)
leaf_iterator operator++(int){
@@ -332,9 +339,9 @@
* }
* @endcode
*/
- class leaf_bbx_iterator : public iterator_base {
+ class leaf_bbx_iterator : public iterator_base<NodeType> {
public:
- leaf_bbx_iterator() : iterator_base() {};
+ leaf_bbx_iterator() : iterator_base<NodeType>() {};
/**
* Constructor of the iterator. The bounding box corners min and max are
* converted into an OcTreeKey first.
@@ -351,7 +358,7 @@
* @param depth Maximum depth to traverse the tree. 0 (default): unlimited
*/
leaf_bbx_iterator(OcTreeBaseImpl<NodeType,INTERFACE> const* ptree, const point3d& min, const point3d& max, uint8_t depth=0)
- : iterator_base(ptree, depth)
+ : iterator_base<NodeType>(ptree, depth)
{
if (this->stack.size() > 0){
assert(ptree);
@@ -379,7 +386,7 @@
* @param depth Maximum depth to traverse the tree. 0 (default): unlimited
*/
leaf_bbx_iterator(OcTreeBaseImpl<NodeType,INTERFACE> const* ptree, const OcTreeKey& min, const OcTreeKey& max, uint8_t depth=0)
- : iterator_base(ptree, depth), minKey(min), maxKey(max)
+ : iterator_base<NodeType>(ptree, depth), minKey(min), maxKey(max)
{
// tree could be empty (= no stack)
if (this->stack.size() > 0){
@@ -389,7 +396,7 @@
}
}
- leaf_bbx_iterator(const leaf_bbx_iterator& other) : iterator_base(other) {
+ leaf_bbx_iterator(const leaf_bbx_iterator& other) : iterator_base<NodeType>(other) {
minKey = other.minKey;
maxKey = other.maxKey;
}
@@ -430,10 +437,10 @@
protected:
void singleIncrement(){
- typename iterator_base::StackElement top = this->stack.top();
+ typename iterator_base<NodeType>::StackElement top = this->stack.top();
this->stack.pop();
- typename iterator_base::StackElement s;
+ typename iterator_base<NodeType>::StackElement s;
s.depth = top.depth +1;
key_type center_offset_key = this->tree->tree_max_val >> s.depth;
// push on stack in reverse order
|