ros_type.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 ROS_INTROSPECTION_ROSTYPE_H
00036 #define ROS_INTROSPECTION_ROSTYPE_H
00037 
00038 #include <vector>
00039 #include <map>
00040 #include <iostream>
00041 #include <functional>
00042 #include "ros_type_introspection/utils/variant.hpp"
00043 
00044 namespace RosIntrospection{
00045 
00046 
00050 class ROSType {
00051 public:
00052 
00053   ROSType(){}
00054 
00055   ROSType(absl::string_view name);
00056 
00057   ROSType(const ROSType& other) {  *this = other; }
00058 
00059   ROSType(ROSType&& other) {  *this = other; }
00060 
00061   ROSType& operator= (const ROSType& other);
00062 
00063   ROSType& operator= (ROSType&& other);
00064 
00067   const std::string& baseName() const;
00068 
00070   const absl::string_view& msgName()  const;
00071 
00073   const absl::string_view& pkgName()  const;
00074 
00075   void setPkgName(absl::string_view new_pkg);
00076 
00078   bool isBuiltin() const;
00079 
00081   int typeSize() const;
00082 
00084   BuiltinType typeID() const;
00085 
00086   bool operator==(const ROSType& other) const  {
00087     return _hash == other._hash;
00088   }
00089 
00090   bool operator!=(const ROSType& other) const  {
00091     return (_hash != other._hash);
00092   }
00093 
00094   bool operator<(const ROSType& other) const {
00095     return this->baseName() < other.baseName();
00096   }
00097 
00098   size_t hash() const { return _hash; }
00099 
00100 protected:
00101 
00102   BuiltinType _id;
00103   std::string _base_name;
00104   absl::string_view _msg_name;
00105   absl::string_view _pkg_name;
00106   size_t _hash;
00107 
00108 };
00109 
00110 //----------- definitions -------------
00111 
00112 inline const std::string &ROSType::baseName() const
00113 {
00114   return _base_name;
00115 }
00116 
00117 inline const absl::string_view& ROSType::msgName() const
00118 {
00119   return _msg_name;
00120 }
00121 
00122 inline const absl::string_view &ROSType::pkgName() const
00123 {
00124   return _pkg_name;
00125 }
00126 
00127 inline bool ROSType::isBuiltin() const
00128 {
00129   return _id != RosIntrospection::OTHER;
00130 }
00131 
00132 inline int ROSType::typeSize() const
00133 {
00134   return builtinSize( _id );
00135 }
00136 
00137 inline BuiltinType ROSType::typeID() const
00138 {
00139   return _id;
00140 }
00141 
00142 //--------- helper functions --------------
00143 
00144 inline std::ostream& operator<<(std::ostream &os, const ROSType& t )
00145 {
00146   os << t.baseName();
00147   return os;
00148 }
00149 
00150 inline BuiltinType toBuiltinType(const absl::string_view& s) {
00151   static std::map<absl::string_view, BuiltinType> string_to_builtin_map {
00152     { "bool", BOOL },
00153     { "byte", BYTE },
00154     { "char", CHAR },
00155     { "uint8", UINT8 },
00156     { "uint16", UINT16 },
00157     { "uint32", UINT32 },
00158     { "uint64", UINT64 },
00159     { "int8", INT8 },
00160     { "int16", INT16 },
00161     { "int32", INT32 },
00162     { "int64", INT64 },
00163     { "float32", FLOAT32 },
00164     { "float64", FLOAT64 },
00165     { "time", TIME },
00166     { "duration", DURATION },
00167     { "string", STRING },
00168   };
00169   const auto it = string_to_builtin_map.find(s);
00170   return (it != string_to_builtin_map.cend()) ? it->second : OTHER;
00171 }
00172 
00173 }
00174 
00175 namespace std {
00176   template <> struct hash<RosIntrospection::ROSType>
00177   {
00178 
00179     typedef RosIntrospection::ROSType argument_type;
00180     typedef std::size_t               result_type;
00181 
00182     result_type operator()(RosIntrospection::ROSType const& type) const
00183     {
00184       return type.hash();
00185     }
00186   };
00187 }
00188 
00189 
00190 #endif // ROSTYPE_H


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