variant.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 #ifndef VARIANT_H
00036 #define VARIANT_H
00037 
00038 #include <type_traits>
00039 #include <limits>
00040 #include "ros_type_introspection/builtin_types.hpp"
00041 #include "ros_type_introspection/details/exceptions.hpp"
00042 #include "ros_type_introspection/details/conversion_impl.hpp"
00043 #include "absl/strings/string_view.h"
00044 
00045 
00046 namespace RosIntrospection
00047 {
00048 
00049 class Variant
00050 {
00051 
00052 public:
00053 
00054   Variant() {
00055     _type = OTHER;
00056     _storage.raw_string = nullptr;
00057   }
00058 
00059   ~Variant();
00060 
00061   Variant(const Variant& other): _type(OTHER)
00062   {
00063     if( other._type == STRING)
00064     {
00065       const char* raw = other._storage.raw_string;
00066       const uint32_t size = *(reinterpret_cast<const uint32_t*>( &raw[0] ));
00067       const char* data = (&raw[4]);
00068       assign( data, size );
00069     }
00070     else{
00071       _type = other._type;
00072       _storage.raw_data = other._storage.raw_data;
00073     }
00074   }
00075 
00076   Variant(Variant&& other): _type(OTHER)
00077   {
00078     if( other._type == STRING)
00079     {
00080       _storage.raw_string = nullptr;
00081       std::swap( _storage.raw_string,  other._storage.raw_string);
00082       std::swap( _type, other._type);
00083     }
00084     else{
00085       _type = other._type;
00086       _storage.raw_data = other._storage.raw_data;
00087     }
00088   }
00089 
00090   Variant& operator = (const Variant& other)
00091   {
00092     if( other._type == STRING)
00093     {
00094       const char* raw = other._storage.raw_string;
00095       const uint32_t size = *(reinterpret_cast<const uint32_t*>( &raw[0] ));
00096       const char* data = (&raw[4]);
00097       assign( data, size );
00098     }
00099     else{
00100       _type = other._type;
00101       _storage.raw_data = other._storage.raw_data;
00102     }
00103     return *this;
00104   }
00105 
00106   template<typename T> Variant(const T& value);
00107 
00108   // specialization for raw string
00109   Variant(const char* buffer, size_t length);
00110 
00111   BuiltinType getTypeID() const;
00112 
00113   template<typename T> T convert( ) const;
00114 
00115   template<typename T> T extract( ) const;
00116 
00117   template <typename T> void assign(const T& value);
00118 
00119   void assign(const char* buffer, size_t length);
00120 
00121 private:
00122 
00123   union {
00124     std::array<uint8_t,8> raw_data;
00125     char* raw_string;
00126   }_storage;
00127 
00128   void clearStringIfNecessary();
00129 
00130   BuiltinType _type;
00131 };
00132 
00133 
00134 //----------------------- Implementation ----------------------------------------------
00135 
00136 
00137 template<typename T>
00138 inline Variant::Variant(const T& value):
00139   _type(OTHER)
00140 {
00141   static_assert (std::numeric_limits<T>::is_specialized ||
00142                  std::is_same<T, ros::Time>::value ||
00143                  std::is_same<T, absl::string_view>::value ||
00144                  std::is_same<T, std::string>::value ||
00145                  std::is_same<T, ros::Duration>::value
00146                  , "not a valid type");
00147 
00148   _storage.raw_string = (nullptr);
00149   assign(value);
00150 }
00151 
00152 inline Variant::Variant(const char* buffer, size_t length):_type(OTHER)
00153 {
00154   _storage.raw_string = (nullptr);
00155   assign(buffer,length);
00156 }
00157 
00158 inline Variant::~Variant()
00159 {
00160   clearStringIfNecessary();
00161 }
00162 
00163 //-------------------------------------
00164 
00165 inline BuiltinType Variant::getTypeID() const {
00166   return _type;
00167 }
00168 
00169 template<typename T> inline T Variant::extract( ) const
00170 {
00171   static_assert (std::numeric_limits<T>::is_specialized ||
00172                  std::is_same<T, ros::Time>::value ||
00173                  std::is_same<T, ros::Duration>::value
00174                  , "not a valid type");
00175 
00176   if( _type != RosIntrospection::getType<T>() )
00177   {
00178     throw TypeException("Variant::extract -> wrong type");
00179   }
00180   return * reinterpret_cast<const T*>( &_storage.raw_data[0] );
00181 }
00182 
00183 template<> inline absl::string_view Variant::extract( ) const
00184 {
00185 
00186   if( _type != STRING )
00187   {
00188     throw TypeException("Variant::extract -> wrong type");
00189   }
00190   const uint32_t size = *(reinterpret_cast<const uint32_t*>( &_storage.raw_string[0] ));
00191   char* data = static_cast<char*>(&_storage.raw_string[4]);
00192   return absl::string_view(data, size);
00193 }
00194 
00195 template<> inline std::string Variant::extract( ) const
00196 {
00197   if( _type != STRING )
00198   {
00199     throw TypeException("Variant::extract -> wrong type");
00200   }
00201   const uint32_t size = *(reinterpret_cast<const uint32_t*>( &_storage.raw_string[0] ));
00202   char* data = static_cast<char*>(&_storage.raw_string[4]);
00203   return std::string(data, size);
00204 }
00205 
00206 //-------------------------------------
00207 
00208 template <typename T> inline void Variant::assign(const T& value)
00209 {
00210   static_assert (std::numeric_limits<T>::is_specialized ||
00211                  std::is_same<T, ros::Time>::value ||
00212                  std::is_same<T, ros::Duration>::value
00213                  , "not a valid type");
00214 
00215   clearStringIfNecessary();
00216   _type = RosIntrospection::getType<T>() ;
00217   *reinterpret_cast<T *>( &_storage.raw_data[0] ) =  value;
00218 }
00219 
00220 inline void Variant::clearStringIfNecessary()
00221 {
00222   if( _storage.raw_string && _type == STRING)
00223   {
00224     delete [] _storage.raw_string;
00225     _storage.raw_string = nullptr;
00226   }
00227 }
00228 
00229 inline void Variant::assign(const char* buffer, size_t size)
00230 {
00231   clearStringIfNecessary();
00232   _type = STRING;
00233 
00234   _storage.raw_string = new char[size+5];
00235   *reinterpret_cast<uint32_t *>( &_storage.raw_string[0] ) = size;
00236   memcpy(&_storage.raw_string[4] , buffer, size );
00237   _storage.raw_string[size+4] = '\0';
00238 }
00239 
00240 
00241 
00242 template <> inline void Variant::assign(const absl::string_view& value)
00243 {
00244   assign( value.data(), value.size() );
00245 }
00246 
00247 template <> inline void Variant::assign(const std::string& value)
00248 {
00249   assign( value.data(), value.size() );
00250 }
00251 
00252 //-------------------------------------
00253 
00254 template<typename DST> inline DST Variant::convert() const
00255 {
00256   static_assert (std::numeric_limits<DST>::is_specialized ||
00257                  std::is_same<DST, ros::Time>::value ||
00258                  std::is_same<DST, ros::Duration>::value
00259                  , "not a valid type");
00260 
00261   using namespace RosIntrospection::details;
00262   DST target;
00263 
00264   const auto& raw_data = &_storage.raw_data[0];
00265   //----------
00266   switch( _type )
00267   {
00268   case CHAR:
00269   case INT8:   convert_impl<int8_t,  DST>(*reinterpret_cast<const int8_t*>( raw_data), target  ); break;
00270 
00271   case INT16:  convert_impl<int16_t, DST>(*reinterpret_cast<const int16_t*>( raw_data), target  ); break;
00272   case INT32:  convert_impl<int32_t, DST>(*reinterpret_cast<const int32_t*>( raw_data), target  ); break;
00273   case INT64:  convert_impl<int64_t, DST>(*reinterpret_cast<const int64_t*>( raw_data), target  ); break;
00274 
00275   case BOOL:
00276   case BYTE:
00277   case UINT8:   convert_impl<uint8_t,  DST>(*reinterpret_cast<const uint8_t*>( raw_data), target  ); break;
00278 
00279   case UINT16:  convert_impl<uint16_t, DST>(*reinterpret_cast<const uint16_t*>( raw_data), target  ); break;
00280   case UINT32:  convert_impl<uint32_t, DST>(*reinterpret_cast<const uint32_t*>( raw_data), target  ); break;
00281   case UINT64:  convert_impl<uint64_t, DST>(*reinterpret_cast<const uint64_t*>( raw_data), target  ); break;
00282 
00283   case FLOAT32:  convert_impl<float, DST>(*reinterpret_cast<const float*>( raw_data), target  ); break;
00284   case FLOAT64:  convert_impl<double, DST>(*reinterpret_cast<const double*>( raw_data), target  ); break;
00285 
00286   case STRING: {
00287     throw TypeException("String will not be converted to a numerical value implicitly");
00288  } break;
00289 
00290   case DURATION:
00291   case TIME: {
00292      throw TypeException("ros::Duration and ros::Time can be converted only to double (will be seconds)");
00293   } break;
00294 
00295   default: throw TypeException("Variant::convert -> cannot convert type" + std::to_string(_type)); break;
00296 
00297   }
00298   return  target;
00299 }
00300 
00301 template<> inline double Variant::convert() const
00302 {
00303   using namespace RosIntrospection::details;
00304   double target = 0;
00305   const auto& raw_data = &_storage.raw_data[0];
00306   //----------
00307   switch( _type )
00308   {
00309   case CHAR:
00310   case INT8:   convert_impl<int8_t,  double>(*reinterpret_cast<const int8_t*>( raw_data), target  ); break;
00311 
00312   case INT16:  convert_impl<int16_t, double>(*reinterpret_cast<const int16_t*>( raw_data), target  ); break;
00313   case INT32:  convert_impl<int32_t, double>(*reinterpret_cast<const int32_t*>( raw_data), target  ); break;
00314   case INT64:  convert_impl<int64_t, double>(*reinterpret_cast<const int64_t*>( raw_data), target  ); break;
00315 
00316   case BOOL:
00317   case BYTE:
00318   case UINT8:   convert_impl<uint8_t,  double>(*reinterpret_cast<const uint8_t*>( raw_data), target  ); break;
00319 
00320   case UINT16:  convert_impl<uint16_t, double>(*reinterpret_cast<const uint16_t*>( raw_data), target  ); break;
00321   case UINT32:  convert_impl<uint32_t, double>(*reinterpret_cast<const uint32_t*>( raw_data), target  ); break;
00322   case UINT64:  convert_impl<uint64_t, double>(*reinterpret_cast<const uint64_t*>( raw_data), target  ); break;
00323 
00324   case FLOAT32:  convert_impl<float, double>(*reinterpret_cast<const float*>( raw_data), target  ); break;
00325   case FLOAT64:  return extract<double>();
00326 
00327   case STRING: {
00328     throw TypeException("String will not be converted to a double implicitly");
00329   }break;
00330 
00331   case DURATION: {
00332     ros::Duration tmp =  extract<ros::Duration>();
00333     target = tmp.toSec();
00334   }break;
00335 
00336   case TIME: {
00337     ros::Time tmp =  extract<ros::Time>();
00338     target = tmp.toSec();
00339   }break;
00340 
00341   default: throw TypeException("Variant::convert -> cannot convert type" + std::to_string(_type));
00342 
00343   }
00344   return  target;
00345 }
00346 
00347 template<> inline ros::Time Variant::convert() const
00348 {
00349   if(  _type != TIME )
00350   {
00351      throw TypeException("Variant::convert -> cannot convert ros::Time");
00352   }
00353   return extract<ros::Time>();
00354 }
00355 
00356 template<> inline ros::Duration Variant::convert() const
00357 {
00358   if(  _type != DURATION )
00359   {
00360      throw TypeException("Variant::convert -> cannot convert ros::Duration");
00361   }
00362   return extract<ros::Duration>();
00363 }
00364 
00365 
00366 template<> inline std::string Variant::convert() const
00367 {
00368   if(  _type != STRING )
00369   {
00370      throw TypeException("Variant::convert -> cannot convert to std::string");
00371   }
00372   return extract<std::string>();
00373 }
00374 
00375 } //end namespace
00376 
00377 
00378 #endif // VARIANT_H


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