tree.hpp
Go to the documentation of this file.
00001 /*********************************************************************
00002 * Software License Agreement (BSD License)
00003 *
00004 *  Copyright 2016-2017 Davide Faconti
00005 *  All rights reserved.
00006 *
00007 *  Redistribution and use in source and binary forms, with or without
00008 *  modification, are permitted provided that the following conditions
00009 *  are met:
00010 *
00011 *   * Redistributions of source code must retain the above copyright
00012 *     notice, this list of conditions and the following disclaimer.
00013 *   * Redistributions in binary form must reproduce the above
00014 *     copyright notice, this list of conditions and the following
00015 *     disclaimer in the documentation and/or other materials provided
00016 *     with the distribution.
00017 *   * Neither the name of Willow Garage, Inc. nor the names of its
00018 *     contributors may be used to endorse or promote products derived
00019 *     from this software without specific prior written permission.
00020 *
00021 *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022 *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023 *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024 *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025 *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026 *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027 *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028 *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029 *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030 *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031 *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032 *  POSSIBILITY OF SUCH DAMAGE.
00033 * *******************************************************************/
00034 
00035 
00036 #ifndef STRINGTREE_H
00037 #define STRINGTREE_H
00038 
00039 #include <vector>
00040 #include <deque>
00041 #include <iostream>
00042 #include <memory>
00043 #include <boost/container/stable_vector.hpp>
00044 #include <boost/noncopyable.hpp>
00045 #include "absl/strings/string_view.h"
00046 
00047 namespace RosIntrospection {
00048 
00049 namespace details{
00050 
00054 template <typename T> class TreeNode
00055 {
00056 
00057 public:
00058 
00059   typedef std::vector<TreeNode> ChildrenVector; // dangerous because of pointer invalidation (but faster)
00060 
00061   TreeNode(const TreeNode* parent );
00062 
00063   const TreeNode* parent() const  { return _parent; }
00064 
00065   const T& value() const          { return _value; }
00066   void setValue( const T& value)  { _value = value; }
00067 
00068   const ChildrenVector& children()const   { return _children; }
00069   ChildrenVector& children()              { return _children; }
00070 
00071   const TreeNode* child(size_t index) const { return &(_children[index]); }
00072   TreeNode* child(size_t index) { return &(_children[index]); }
00073 
00074   TreeNode *addChild(const T& child );
00075 
00076   bool isLeaf() const { return _children.empty(); }
00077 
00078 private:
00079   const TreeNode*   _parent;
00080   T                 _value;
00081   ChildrenVector    _children;
00082 };
00083 
00084 
00085 template <typename T> class Tree
00086 {
00087 public:
00088   Tree(): _root( new TreeNode<T>(nullptr) ) {}
00089 
00095   template<typename Vect> const TreeNode<T>* find( const Vect& concatenated_values, bool partial_allowed = false);
00096 
00098   const TreeNode<T>* croot() const { return _root.get(); }
00099 
00101   TreeNode<T>* root() { return _root.get(); }
00102 
00103 
00104   friend std::ostream& operator<<(std::ostream& os, const Tree& _this){
00105     _this.print_impl(os, _this.croot() , 0);
00106     return os;
00107   }
00108 
00109 private:
00110 
00111   void print_impl(std::ostream& os, const TreeNode<T> *node, int indent ) const;
00112 
00113   std::unique_ptr<TreeNode<T>> _root;
00114 };
00115 
00116 //-----------------------------------------
00117 
00118 
00119 template <typename T> inline
00120 std::ostream& operator<<(std::ostream &os, const std::pair<const TreeNode<T>*, const TreeNode<T>* >& tail_head )
00121 {
00122   const TreeNode<T>* tail = tail_head.first;
00123   const TreeNode<T>* head = tail_head.second;
00124 
00125   if( !head ) return os;
00126 
00127   const TreeNode<T>* array[64];
00128   int index = 0;
00129   array[index++] = head;
00130 
00131   while( !head || head != tail)
00132   {
00133     head = head->parent();
00134     array[index++] = head;
00135   };
00136   array[index] = nullptr;
00137   index--;
00138 
00139   while ( index >=0)
00140   {
00141     if( array[index] ){
00142       os << array[index]->value();
00143     }
00144     if( index >0 )  os << ".";
00145     index--;
00146   }
00147   return os;
00148 }
00149 
00150 template <typename T> inline
00151 void Tree<T>::print_impl(std::ostream &os, const TreeNode<T>* node, int indent) const
00152 {
00153   for (int i=0; i<indent; i++) os << " ";
00154   os << node->value() << std::endl;
00155 
00156   for (const auto& child: node->children() )
00157   {
00158     print_impl(os, &child, indent+3);
00159   }
00160 }
00161 
00162 template <typename T> inline
00163 TreeNode<T>::TreeNode(const TreeNode *parent):
00164   _parent(parent)
00165 {
00166 
00167 }
00168 
00169 template <typename T> inline
00170 TreeNode<T> *TreeNode<T>::addChild(const T& value)
00171 {
00172   assert(_children.capacity() > _children.size() );
00173   _children.push_back( TreeNode<T>(this) );
00174   _children.back().setValue( value );
00175   return &_children.back();
00176 }
00177 
00178 
00179 template <typename T> template<typename Vect> inline
00180 const TreeNode<T> *Tree<T>::find(const Vect& concatenated_values, bool partial_allowed )
00181 {
00182   TreeNode<T>* node = &_root;
00183 
00184   for (const auto& value: concatenated_values)
00185   {
00186     bool found = false;
00187     for (auto& child: (node->children() ) )
00188     {
00189       if( child.value() == value)
00190       {
00191         node = &(child);
00192         found = true;
00193         break;
00194       }
00195     }
00196     if( !found ) return nullptr;
00197   }
00198 
00199   if( partial_allowed || node->children().empty() )
00200   {
00201     return  node;
00202   }
00203   return nullptr;
00204 }
00205 
00206 }
00207 
00208 }
00209 
00210 
00211 
00212 #endif // STRINGTREE_H


ros_type_introspection
Author(s): Davide Faconti
autogenerated on Tue May 14 2019 02:49:42