builtin_types.hpp
Go to the documentation of this file.
00001 
00002 /*********************************************************************
00003 * Software License Agreement (BSD License)
00004 *
00005 *  Copyright 2016-2017 Davide Faconti
00006 *  All rights reserved.
00007 *
00008 *  Redistribution and use in source and binary forms, with or without
00009 *  modification, are permitted provided that the following conditions
00010 *  are met:
00011 *
00012 *   * Redistributions of source code must retain the above copyright
00013 *     notice, this list of conditions and the following disclaimer.
00014 *   * Redistributions in binary form must reproduce the above
00015 *     copyright notice, this list of conditions and the following
00016 *     disclaimer in the documentation and/or other materials provided
00017 *     with the distribution.
00018 *   * Neither the name of Willow Garage, Inc. nor the names of its
00019 *     contributors may be used to endorse or promote products derived
00020 *     from this software without specific prior written permission.
00021 *
00022 *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00023 *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00024 *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00025 *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00026 *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00027 *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00028 *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00029 *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00030 *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00031 *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00032 *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00033 *  POSSIBILITY OF SUCH DAMAGE.
00034 * *******************************************************************/
00035 
00036 #ifndef ROS_BUILTIN_TYPES_HPP
00037 #define ROS_BUILTIN_TYPES_HPP
00038 
00039 #include <stdint.h>
00040 #include <string>
00041 #include <ros/ros.h>
00042 #include <unordered_map>
00043 
00044 namespace RosIntrospection{
00045 
00046 
00047 enum BuiltinType {
00048   BOOL , BYTE, CHAR,
00049   UINT8, UINT16, UINT32, UINT64,
00050   INT8, INT16, INT32, INT64,
00051   FLOAT32, FLOAT64,
00052   TIME, DURATION,
00053   STRING, OTHER
00054 };
00055 
00056 //---------------------------------------------------------
00057 
00058 inline int builtinSize(const BuiltinType c) {
00059   switch (c) {
00060   case BOOL:
00061   case BYTE:
00062   case INT8:
00063   case CHAR:
00064   case UINT8:    return 1;
00065   case UINT16:
00066   case INT16:    return 2;
00067   case UINT32:
00068   case INT32:
00069   case FLOAT32:  return 4;
00070   case UINT64:
00071   case INT64:
00072   case FLOAT64:
00073   case TIME:
00074   case DURATION: return 8;
00075   case STRING:
00076   case OTHER: return -1;
00077   }
00078   throw std::runtime_error( "unsupported builtin type value");
00079 }
00080 
00081 inline const char* toStr(const BuiltinType& c)
00082 {
00083   switch (c) {
00084   case BOOL:     return "BOOL";
00085   case BYTE:     return "BYTE";
00086   case INT8:     return "INT8";
00087   case CHAR:     return "CHAR";
00088   case UINT8:    return "UINT8";
00089   case UINT16:   return "UINT16";
00090   case UINT32:   return "UINT32";
00091   case UINT64:   return "UINT64";
00092   case INT16:    return "INT16";
00093   case INT32:    return "INT32";
00094   case INT64:    return "INT64";
00095   case FLOAT32:  return "FLOAT32";
00096   case FLOAT64:  return "FLOAT64";
00097   case TIME:     return "TIME";
00098   case DURATION: return "DURATION";
00099   case STRING:   return "STRING";
00100   case OTHER:    return "OTHER";
00101   }
00102   throw std::runtime_error( "unsupported builtin type value");
00103 }
00104 
00105 inline std::ostream& operator<<(std::ostream& os, const BuiltinType& c)
00106 {
00107   os << toStr(c);
00108   return os;
00109 }
00110 
00111 template <typename T> BuiltinType getType()
00112 {
00113     return OTHER;
00114 }
00115 
00116 template <> inline BuiltinType getType<bool>()  {  return BOOL; }
00117 
00118 template <> inline BuiltinType getType<char>()           {  return CHAR; }
00119 
00120 template <> inline BuiltinType getType<int8_t>()  {  return INT8; }
00121 template <> inline BuiltinType getType<int16_t>() {  return INT16; }
00122 template <> inline BuiltinType getType<int32_t>() {  return INT32; }
00123 template <> inline BuiltinType getType<int64_t>() {  return INT64; }
00124 
00125 template <> inline BuiltinType getType<uint8_t>()  {  return UINT8; }
00126 template <> inline BuiltinType getType<uint16_t>() {  return UINT16; }
00127 template <> inline BuiltinType getType<uint32_t>() {  return UINT32; }
00128 template <> inline BuiltinType getType<uint64_t>() {  return UINT64; }
00129 
00130 template <> inline BuiltinType getType<float>()  {  return FLOAT32; }
00131 template <> inline BuiltinType getType<double>() {  return FLOAT64; }
00132 
00133 template <> inline BuiltinType getType<std::string>() {  return STRING; }
00134 
00135 template <> inline BuiltinType getType<ros::Time>()     {  return TIME; }
00136 template <> inline BuiltinType getType<ros::Duration>() {  return DURATION; }
00137 
00138 }
00139 
00140 #endif // ROS_BUILTIN_TYPES_HPP


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