blackboard.h
Go to the documentation of this file.
00001 #ifndef BLACKBOARD_H
00002 #define BLACKBOARD_H
00003 
00004 #include <iostream>
00005 #include <string>
00006 #include <memory>
00007 #include <stdint.h>
00008 #include <unordered_map>
00009 #include <mutex>
00010 #include <sstream>
00011 
00012 #include "behaviortree_cpp/basic_types.h"
00013 #include "behaviortree_cpp/utils/safe_any.hpp"
00014 #include "behaviortree_cpp/exceptions.h"
00015 
00016 namespace BT
00017 {
00018 
00023 class Blackboard
00024 {
00025   public:
00026     typedef std::shared_ptr<Blackboard> Ptr;
00027 
00028   protected:
00029     // This is intentionally protected. Use Blackboard::create instead
00030     Blackboard(Blackboard::Ptr parent): parent_bb_(parent)
00031     {}
00032 
00033   public:
00034 
00038     static Blackboard::Ptr create(Blackboard::Ptr parent = {})
00039     {
00040         return std::shared_ptr<Blackboard>( new Blackboard(parent) );
00041     }
00042 
00043     virtual ~Blackboard() = default;
00044 
00051     const Any* getAny(const std::string& key) const
00052     {
00053         std::unique_lock<std::mutex> lock(mutex_);
00054 
00055         if( auto parent = parent_bb_.lock())
00056         {
00057             auto remapping_it = internal_to_external_.find(key);
00058             if( remapping_it != internal_to_external_.end())
00059             {
00060                 return parent->getAny( remapping_it->second );
00061             }
00062         }
00063         auto it = storage_.find(key);
00064         return ( it == storage_.end()) ? nullptr : &(it->second.value);
00065     }
00066 
00067     Any* getAny(const std::string& key)
00068     {
00069         std::unique_lock<std::mutex> lock(mutex_);
00070 
00071         if( auto parent = parent_bb_.lock())
00072         {
00073             auto remapping_it = internal_to_external_.find(key);
00074             if( remapping_it != internal_to_external_.end())
00075             {
00076                 return parent->getAny( remapping_it->second );
00077             }
00078         }
00079         auto it = storage_.find(key);
00080         return ( it == storage_.end()) ? nullptr : &(it->second.value);
00081     }
00082 
00086     template <typename T>
00087     bool get(const std::string& key, T& value) const
00088     {
00089         const Any* val = getAny(key);
00090         if (val)
00091         {
00092             value = val->cast<T>();
00093         }
00094         return (bool)val;
00095     }
00096 
00100     template <typename T>
00101     T get(const std::string& key) const
00102     {
00103         const Any* val = getAny(key);
00104         if (val)
00105         {
00106             return val->cast<T>();
00107         }
00108         else
00109         {
00110             throw RuntimeError("Blackboard::get() error. Missing key [", key, "]");
00111         }
00112     }
00113 
00114 
00116     template <typename T>
00117     void set(const std::string& key, const T& value)
00118     {
00119         std::unique_lock<std::mutex> lock(mutex_);
00120         auto it = storage_.find(key);
00121 
00122         if( auto parent = parent_bb_.lock())
00123         {
00124             auto remapping_it = internal_to_external_.find(key);
00125             if( remapping_it != internal_to_external_.end())
00126             {
00127                 const auto& remapped_key = remapping_it->second;
00128                 if( it == storage_.end() ) // virgin entry
00129                 {
00130                     auto parent_info = parent->portInfo(remapped_key);
00131                     if( parent_info )
00132                     {
00133                         storage_.insert( {key, Entry( *parent_info ) } );
00134                     }
00135                     else{
00136                         storage_.insert( {key, Entry( PortInfo() ) } );
00137                     }
00138                 }
00139                 parent->set( remapped_key, value );
00140                 return;
00141             }
00142         }
00143 
00144         if( it != storage_.end() ) // already there. check the type
00145         {
00146             const PortInfo& port_info = it->second.port_info;
00147             auto& previous_any = it->second.value;
00148             const auto locked_type = port_info.type();
00149 
00150             Any temp(value);
00151 
00152             if( locked_type && locked_type != &typeid(T) && locked_type != &temp.type() )
00153             {
00154                 bool mismatching = true;
00155                 if( std::is_constructible<StringView, T>::value )
00156                 {
00157                     Any any_from_string = port_info.parseString( value );
00158                     if( any_from_string.empty() == false)
00159                     {
00160                         mismatching = false;
00161                         temp = std::move( any_from_string );
00162                     }
00163                 }
00164 
00165                 if( mismatching )
00166                 {
00167                     debugMessage();
00168 
00169                     throw LogicError( "Blackboard::set() failed: once declared, the type of a port shall not change. "
00170                                      "Declared type [", demangle( locked_type ),
00171                                      "] != current type [", demangle( typeid(T) ),"]" );
00172                 }
00173             }
00174             previous_any = std::move(temp);
00175         }
00176         else{ // create for the first time without any info
00177             storage_.emplace( key, Entry( Any(value), PortInfo() ) );
00178         }
00179         return;
00180     }
00181 
00182     void setPortInfo(std::string key, const PortInfo& info);
00183 
00184     const PortInfo *portInfo(const std::string& key);
00185 
00186     void addSubtreeRemapping(std::string internal, std::string external);
00187 
00188     void debugMessage() const;
00189 
00190   private:
00191 
00192     struct Entry{
00193         Any value;
00194         const PortInfo port_info;
00195 
00196         Entry( const PortInfo& info ):
00197           port_info(info)
00198         {}
00199 
00200         Entry(Any&& other_any, const PortInfo& info):
00201           value(std::move(other_any)),
00202           port_info(info)
00203         {}
00204     };
00205 
00206     mutable std::mutex mutex_;
00207     std::unordered_map<std::string, Entry> storage_;
00208     std::weak_ptr<Blackboard> parent_bb_;
00209     std::unordered_map<std::string,std::string> internal_to_external_;
00210 
00211 };
00212 
00213 
00214 } // end namespace
00215 
00216 #endif   // BLACKBOARD_H


behaviortree_cpp
Author(s): Michele Colledanchise, Davide Faconti
autogenerated on Sat Jun 8 2019 20:17:15