stringtree.hpp
Go to the documentation of this file.
00001 /*********************************************************************
00002 * Software License Agreement (BSD License)
00003 *
00004 *  Copyright 2016 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 #ifndef STRINGTREE_H
00036 #define STRINGTREE_H
00037 
00038 #include <vector>
00039 #include <deque>
00040 #include <iostream>
00041 #include <boost/container/stable_vector.hpp>
00042 #include <boost/noncopyable.hpp>
00043 #include "ros_type_introspection/string.hpp"
00044 
00045 namespace RosIntrospection {
00046 
00047 namespace details{
00048 
00049 // If you set this to true, Tree can not be modified
00050 // once it is created. The main reason is that std::vector will be used to store
00051 // the children. this is faster but might invalidate the pointer to the node's parent.
00052 #define STATIC_TREE true
00053 
00057 template <typename T> class TreeElement
00058 {
00059 
00060 public:
00061 #if !STATIC_TREE
00062     typedef boost::container::stable_vector<TreeElement> ChildrenVector;
00063 #else
00064     typedef std::vector<TreeElement> ChildrenVector; // dangerous because of pointer invalidation (but faster)
00065 #endif
00066 
00067     TreeElement(const TreeElement* parent, const T& value );
00068 
00069     const TreeElement* parent() const       { return _parent; }
00070 
00071     const T& value() const                  { return _value; }
00072     T& value()                              { return _value; }
00073 
00074     const ChildrenVector& children()const   { return _children; }
00075     ChildrenVector& children()              { return _children; }
00076 
00077     void addChild(const T& child );
00078 
00079     bool isLeaf() const { return _children.empty(); }
00080 
00081 private:
00082     const TreeElement*   _parent;
00083     T              _value;
00084     ChildrenVector _children;
00085 };
00086 
00087 
00088 template <typename T> class Tree : boost::noncopyable
00089 {
00090 public:
00091     Tree(): _root(nullptr,"root") {}
00092 
00093 #if !STATIC_TREE // this operation is illegal in a static tree
00094 
00099     template<typename Vect> void insert(const Vect& concatenated_values);
00100 #endif
00101 
00107     template<typename Vect> const TreeElement<T>* find( const Vect& concatenated_values, bool partial_allowed = false);
00108 
00110     const TreeElement<T>* croot() const { return &_root; }
00111 
00113     TreeElement<T>* root() { return &_root; }
00114 
00115 
00116     friend std::ostream& operator<<(std::ostream& os, const Tree& _this){
00117         _this.print_impl(os, (_this._root.children()), 0);
00118         return os;
00119     }
00120 
00121 private:
00122 
00123     void print_impl(std::ostream& os, const typename TreeElement<T>::ChildrenVector& children, int indent ) const;
00124 
00125     TreeElement<T> _root;
00126 };
00127 
00128 //-----------------------------------------
00129 
00130 
00131 template <typename T> inline
00132 std::ostream& operator<<(std::ostream &os, const std::pair<const TreeElement<T>*, const TreeElement<T>* >& tail_head )
00133 {
00134     const TreeElement<T>* tail = tail_head.first;
00135     const TreeElement<T>* head = tail_head.second;
00136 
00137     if( !head ) return os;
00138 
00139     const TreeElement<T>* array[64];
00140     int index = 0;
00141     array[index++] = head;
00142 
00143     while( !head || head != tail)
00144     {
00145         head = head->parent();
00146         array[index++] = head;
00147     };
00148     array[index] = nullptr;
00149     index--;
00150 
00151     while ( index >=0)
00152     {
00153         if( array[index] ){
00154             os << array[index]->value();
00155         }
00156         if( index >0 )  os << ".";
00157         index--;
00158     }
00159     return os;
00160 }
00161 
00162 template <typename T> inline
00163 void Tree<T>::print_impl(std::ostream &os, const typename TreeElement<T>::ChildrenVector& children, int indent) const
00164 {
00165     for (const auto& child: children)
00166     {
00167         for (int i=0; i<indent; i++) os << " ";
00168         os << child.value();
00169         if( child.parent())
00170           std::cout << "("<< child.parent()->value() << ")" << std::endl;
00171         else
00172           std::cout << "(null)" << std::endl;
00173         print_impl(os, child.children(), indent+3);
00174     }
00175 }
00176 
00177 template <typename T> inline
00178 TreeElement<T>::TreeElement(const TreeElement *parent, const T& value):
00179     _parent(parent), _value(value)
00180 {
00181 
00182 }
00183 
00184 template <typename T> inline
00185 void TreeElement<T>::addChild(const T& value)
00186 {
00187     //skip existing child
00188     for (int i=0; i< _children.size(); i++){
00189       if( value == _children[i].value() ){
00190         return;
00191       }
00192     }
00193 #if STATIC_TREE
00194    assert(_children.capacity() > _children.size() );
00195 #endif
00196     _children.push_back( TreeElement<T>(this, value));
00197 }
00198 
00199 #if !STATIC_TREE
00200 template <typename T> template<typename Vect> inline
00201 void Tree<T>::insert(const Vect &concatenated_values)
00202 {
00203     TreeElement<T>* node = &_root;
00204 
00205     for (const auto& value: concatenated_values)
00206     {
00207         bool found = false;
00208         for (auto& child: (node->children() ) )
00209         {
00210             if( child.value() == value)
00211             {
00212                 node = &(child);
00213                 found = true;
00214                 break;
00215             }
00216         }
00217         if(!found){
00218             node->addChild( value );
00219             node = &(node->children().back());
00220         }
00221     }
00222 }
00223 #endif
00224 
00225 template <typename T> template<typename Vect> inline
00226 const TreeElement<T> *Tree<T>::find(const Vect& concatenated_values, bool partial_allowed )
00227 {
00228     TreeElement<T>* node = &_root;
00229 
00230     for (const auto& value: concatenated_values)
00231     {
00232         bool found = false;
00233         for (auto& child: (node->children() ) )
00234         {
00235             if( child.value() == value)
00236             {
00237                 node = &(child);
00238                 found = true;
00239                 break;
00240             }
00241         }
00242         if( !found ) return nullptr;
00243     }
00244 
00245     if( partial_allowed || node->children().empty() )
00246     {
00247         return  node;
00248     }
00249     return nullptr;
00250 }
00251 
00252 }
00253 
00254 }
00255 
00256 
00257 
00258 #endif // STRINGTREE_H


ros_type_introspection
Author(s): Davide Faconti
autogenerated on Sun Oct 1 2017 02:54:53