ros2_introspection/include/ros2_introspection/tree.hpp
Go to the documentation of this file.
1 /*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright 2016-2017 Davide Faconti
5 * All rights reserved.
6 *
7 * Redistribution and use in source and binary forms, with or without
8 * modification, are permitted provided that the following conditions
9 * are met:
10 *
11 * * Redistributions of source code must retain the above copyright
12 * notice, this list of conditions and the following disclaimer.
13 * * Redistributions in binary form must reproduce the above
14 * copyright notice, this list of conditions and the following
15 * disclaimer in the documentation and/or other materials provided
16 * with the distribution.
17 * * Neither the name of Willow Garage, Inc. nor the names of its
18 * contributors may be used to endorse or promote products derived
19 * from this software without specific prior written permission.
20 *
21 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32 * POSSIBILITY OF SUCH DAMAGE.
33 * *******************************************************************/
34 
35 #pragma once
36 
37 #include <vector>
38 #include <deque>
39 #include <iostream>
40 #include <memory>
41 #include <boost/container/stable_vector.hpp>
42 #include <boost/noncopyable.hpp>
43 
44 
45 namespace Ros2Introspection {
46 
50 template <typename T> class TreeNode
51 {
52 public:
53 
54  typedef std::vector<TreeNode> ChildrenVector; // dangerous because of pointer invalidation (but faster)
55 
56  TreeNode(const TreeNode* parent );
57 
58  const TreeNode* parent() const { return _parent; }
59 
60  const T& value() const { return _value; }
61  void setValue( const T& value) { _value = value; }
62 
63  const ChildrenVector& children()const { return _children; }
64  ChildrenVector& children() { return _children; }
65 
66  const TreeNode* child(size_t index) const { return &(_children[index]); }
67  TreeNode* child(size_t index) { return &(_children[index]); }
68 
69  TreeNode *addChild(const T& child );
70 
71  bool isLeaf() const { return _children.empty(); }
72 
73 private:
74  const TreeNode* _parent;
75  T _value;
76  ChildrenVector _children;
77 };
78 
79 
80 template <typename T> class Tree
81 {
82 public:
83  Tree(): _root( new TreeNode<T>(nullptr) ) {}
84 
86  TreeNode<T>* root() { return _root.get(); }
87 
88  const TreeNode<T>* root() const { return _root.get(); }
89 
90  friend std::ostream& operator<<(std::ostream& os, const Tree& _this){
91  _this.print_impl(os, _this.croot() , 0);
92  return os;
93  }
94 
95 private:
96 
97  void print_impl(std::ostream& os, const TreeNode<T> *node, int indent ) const;
98 
99  std::unique_ptr<TreeNode<T>> _root;
100 };
101 
102 //-----------------------------------------
103 
104 
105 template <typename T> inline
106 std::ostream& operator<<(std::ostream &os, const std::pair<const TreeNode<T>*, const TreeNode<T>* >& tail_head )
107 {
108  const TreeNode<T>* tail = tail_head.first;
109  const TreeNode<T>* head = tail_head.second;
110 
111  if( !head ) return os;
112 
113  const TreeNode<T>* array[64];
114  int index = 0;
115  array[index++] = head;
116 
117  while( !head || head != tail)
118  {
119  head = head->parent();
120  array[index++] = head;
121  };
122  array[index] = nullptr;
123  index--;
124 
125  while ( index >=0)
126  {
127  if( array[index] ){
128  os << array[index]->value();
129  }
130  if( index >0 ) os << ".";
131  index--;
132  }
133  return os;
134 }
135 
136 template <typename T> inline
137 void Tree<T>::print_impl(std::ostream &os, const TreeNode<T>* node, int indent) const
138 {
139  for (int i=0; i<indent; i++) os << " ";
140  os << node->value() << std::endl;
141 
142  for (const auto& child: node->children() )
143  {
144  print_impl(os, &child, indent+3);
145  }
146 }
147 
148 template <typename T> inline
150  _parent(parent)
151 {
152 
153 }
154 
155 template <typename T> inline
157 {
158  assert(_children.capacity() > _children.size() );
159  _children.push_back( TreeNode<T>(this) );
160  _children.back().setValue( value );
161  return &_children.back();
162 }
163 
164 }
165 
166 
TreeNode< T > * root()
Mutable pointer to the root of the tree.
#define nullptr
Element of the tree. it has a single parent and N >= 0 children.
#define assert(condition)
std::size_t index
size_t & i
friend std::ostream & operator<<(std::ostream &os, const Tree &_this)
void print_impl(std::ostream &os, const TreeNode< T > *node, int indent) const


plotjuggler_ros
Author(s): Davide Faconti
autogenerated on Fri Jun 23 2023 02:28:04