safe_any.hpp
Go to the documentation of this file.
00001 #ifndef SAFE_ANY_VARNUMBER_H
00002 #define SAFE_ANY_VARNUMBER_H
00003 
00004 #include <exception>
00005 #include <algorithm>
00006 #include <iostream>
00007 #include <chrono>
00008 #include <string>
00009 #include <cstring>
00010 #include <type_traits>
00011 #include "any.hpp"
00012 #include "demangle_util.h"
00013 #include "convert_impl.hpp"
00014 #include "expected.hpp"
00015 #include "strcat.hpp"
00016 #include "strcat.hpp"
00017 
00018 namespace BT
00019 {
00020 // Rational: since type erased numbers will always use at least 8 bytes
00021 // it is faster to cast everything to either double, uint64_t or int64_t.
00022 class Any
00023 {
00024     template <typename T>
00025     using EnableIntegral =
00026         typename std::enable_if<std::is_integral<T>::value || std::is_enum<T>::value>::type*;
00027 
00028     template <typename T>
00029     using EnableNonIntegral =
00030         typename std::enable_if<!std::is_integral<T>::value && !std::is_enum<T>::value>::type*;
00031 
00032     template <typename T>
00033     using EnableString = typename std::enable_if<std::is_same<T, std::string>::value>::type*;
00034 
00035     template <typename T>
00036     using EnableArithmetic = typename std::enable_if<std::is_arithmetic<T>::value>::type*;
00037 
00038     template <typename T>
00039     using EnableEnum = typename std::enable_if<std::is_enum<T>::value>::type*;
00040 
00041     template <typename T>
00042     using EnableUnknownType =
00043         typename std::enable_if<!std::is_arithmetic<T>::value && !std::is_enum<T>::value &&
00044                                 !std::is_same<T, std::string>::value>::type*;
00045 
00046   public:
00047     Any(): _original_type(nullptr)
00048     {
00049     }
00050 
00051     ~Any() = default;
00052 
00053     Any(const Any& other) : _any(other._any), _original_type( other._original_type )
00054     {
00055     }
00056 
00057     Any(Any&& other) : _any( std::move(other._any) ), _original_type( other._original_type )
00058     {
00059     }
00060 
00061     explicit Any(const double& value) : _any(value), _original_type( &typeid(double) )
00062     {
00063     }
00064 
00065     explicit Any(const uint64_t& value) : _any(value), _original_type( &typeid(uint64_t) )
00066     {
00067     }
00068 
00069     explicit Any(const float& value) : _any(double(value)), _original_type( &typeid(float) )
00070     {
00071     }
00072 
00073     explicit Any(const std::string& str) : _any(SafeAny::SimpleString(str)), _original_type( &typeid(std::string) )
00074     {
00075     }
00076 
00077     explicit Any(const char* str) : _any(SafeAny::SimpleString(str)), _original_type( &typeid(std::string) )
00078     {
00079     }
00080 
00081     explicit Any(const SafeAny::SimpleString& str) : _any(str), _original_type( &typeid(std::string) )
00082     {
00083     }
00084 
00085     // all the other integrals are casted to int64_t
00086     template <typename T>
00087     explicit Any(const T& value, EnableIntegral<T> = 0) : _any(int64_t(value)), _original_type( &typeid(T) )
00088     {
00089     }
00090 
00091     // default for other custom types
00092     template <typename T>
00093     explicit Any(const T& value, EnableNonIntegral<T> = 0) : _any(value), _original_type( &typeid(T) )
00094     {
00095     }
00096 
00097     Any& operator = (const Any& other)
00098     {
00099         this->_any = other._any;
00100         this->_original_type = other._original_type;
00101         return *this;
00102     }
00103 
00104     bool isNumber() const
00105     {
00106         return _any.type() == typeid(int64_t) ||
00107                _any.type() == typeid(uint64_t) ||
00108                _any.type() == typeid(double);
00109     }
00110 
00111     bool isString() const
00112     {
00113         return _any.type() == typeid(SafeAny::SimpleString);
00114     }
00115 
00116     // this is different from any_cast, because if allows safe
00117     // conversions between arithmetic values.
00118     template <typename T>
00119     T cast() const
00120     {
00121         if( _any.empty() )
00122         {
00123             throw std::runtime_error("Any::cast failed because it is empty");
00124         }
00125         if (_any.type() == typeid(T))
00126         {
00127             return linb::any_cast<T>(_any);
00128         }
00129         else
00130         {
00131             auto res = convert<T>();
00132             if( !res )
00133             {
00134                 throw std::runtime_error( res.error() );
00135             }
00136             return res.value();
00137         }
00138     }
00139 
00140     const std::type_info& type() const noexcept
00141     {
00142         return *_original_type;
00143     }
00144 
00145     const std::type_info& castedType() const noexcept
00146     {
00147         return _any.type();
00148     }
00149 
00150     bool empty() const noexcept
00151     {
00152         return _any.empty();
00153     }
00154 
00155   private:
00156     linb::any _any;
00157     const std::type_info* _original_type;
00158 
00159     //----------------------------
00160 
00161     template <typename DST>
00162     nonstd::expected<DST,std::string> convert(EnableString<DST> = 0) const
00163     {
00164         const auto& type = _any.type();
00165 
00166         if (type == typeid(SafeAny::SimpleString))
00167         {
00168             return linb::any_cast<SafeAny::SimpleString>(_any).toStdString();
00169         }
00170         else if (type == typeid(int64_t))
00171         {
00172             return std::to_string(linb::any_cast<int64_t>(_any));
00173         }
00174         else if (type == typeid(uint64_t))
00175         {
00176             return std::to_string(linb::any_cast<uint64_t>(_any));
00177         }
00178         else if (type == typeid(double))
00179         {
00180             return std::to_string(linb::any_cast<double>(_any));
00181         }
00182 
00183         return nonstd::make_unexpected( errorMsg<DST>() );
00184     }
00185 
00186     template <typename DST>
00187     nonstd::expected<DST,std::string> convert(EnableArithmetic<DST> = 0) const
00188     {
00189         using SafeAny::details::convertNumber;
00190         DST out;
00191 
00192         const auto& type = _any.type();
00193 
00194         if (type == typeid(int64_t))
00195         {
00196             convertNumber<int64_t, DST>(linb::any_cast<int64_t>(_any), out);
00197         }
00198         else if (type == typeid(uint64_t))
00199         {
00200             convertNumber<uint64_t, DST>(linb::any_cast<uint64_t>(_any), out);
00201         }
00202         else if (type == typeid(double))
00203         {
00204             convertNumber<double, DST>(linb::any_cast<double>(_any), out);
00205         }
00206         else{
00207             return nonstd::make_unexpected( errorMsg<DST>() );
00208         }
00209         return out;
00210     }
00211 
00212     template <typename DST>
00213     nonstd::expected<DST,std::string> convert(EnableEnum<DST> = 0) const
00214     {
00215         using SafeAny::details::convertNumber;
00216 
00217         const auto& type = _any.type();
00218 
00219         if (type == typeid(int64_t))
00220         {
00221             uint64_t out = linb::any_cast<int64_t>(_any);
00222             return static_cast<DST>(out);
00223         }
00224         else if (type == typeid(uint64_t))
00225         {
00226             uint64_t out = linb::any_cast<uint64_t>(_any);
00227             return static_cast<DST>(out);
00228         }
00229 
00230         return nonstd::make_unexpected( errorMsg<DST>() );
00231     }
00232 
00233     template <typename DST>
00234     nonstd::expected<DST,std::string> convert(EnableUnknownType<DST> = 0) const
00235     {
00236         return nonstd::make_unexpected( errorMsg<DST>() );
00237     }
00238 
00239     template <typename T>
00240     std::string errorMsg() const
00241     {
00242         return StrCat("[Any::convert]: no known safe conversion between [",
00243                       demangle( _any.type() ), "] and [", demangle( typeid(T) ),"]");
00244     }
00245 };
00246 
00247 }   // end namespace BT
00248 
00249 #endif   // VARNUMBER_H


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