DataTypeRegistry.h
Go to the documentation of this file.
00001 /******************************************************************************
00002  * Copyright (C) 2014 by Ralf Kaestner                                        *
00003  * ralf.kaestner@gmail.com                                                    *
00004  *                                                                            *
00005  * This program is free software; you can redistribute it and/or modify       *
00006  * it under the terms of the Lesser GNU General Public License as published by*
00007  * the Free Software Foundation; either version 3 of the License, or          *
00008  * (at your option) any later version.                                        *
00009  *                                                                            *
00010  * This program is distributed in the hope that it will be useful,            *
00011  * but WITHOUT ANY WARRANTY; without even the implied warranty of             *
00012  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the               *
00013  * Lesser GNU General Public License for more details.                        *
00014  *                                                                            *
00015  * You should have received a copy of the Lesser GNU General Public License   *
00016  * along with this program. If not, see <http://www.gnu.org/licenses/>.       *
00017  ******************************************************************************/
00018 
00023 #ifndef VARIANT_TOPIC_TOOLS_DATA_TYPE_REGISTRY_H
00024 #define VARIANT_TOPIC_TOOLS_DATA_TYPE_REGISTRY_H
00025 
00026 #include <typeinfo>
00027 
00028 #include <boost/unordered_map.hpp>
00029 #include <boost/type_traits.hpp>
00030 
00031 #include <variant_topic_tools/DataTypeTraits.h>
00032 #include <variant_topic_tools/Forwards.h>
00033 #include <variant_topic_tools/MessageFieldCollection.h>
00034 #include <variant_topic_tools/TypeInfoHash.h>
00035 
00036 namespace variant_topic_tools {
00039   class DataTypeRegistry {
00040   friend class DataType;
00041   public:
00044     DataTypeRegistry();
00045     
00048     ~DataTypeRegistry();
00049 
00059     DataType getDataType(const std::string& identifier);
00060 
00067     DataType getDataType(const std::string& identifier) const;
00068     
00074     DataType getDataType(const std::type_info& typeInfo) const;
00075     
00083     template <typename T> DataType getDataType();
00084     
00088     template <typename T> DataType getDataType() const;
00089     
00092     void write(std::ostream& stream) const;
00093     
00097     DataType operator[](const std::string& identifier);
00098     
00102     DataType operator[](const std::string& identifier) const;
00103     
00107     DataType operator[](const std::type_info& typeInfo) const;
00108     
00112     ArrayDataType addArrayDataType(const DataType& memberType, size_t
00113       numMembers = 0);
00114     
00118     template <typename T> ArrayDataType addArrayDataType();
00119     
00124     template <typename T, size_t N> ArrayDataType addArrayDataType();
00125     
00128     template <typename T> BuiltinDataType addBuiltinDataType(const
00129       std::string& identifier);
00130     
00136     MessageDataType addMessageDataType(const std::string& identifier,
00137       const MessageFieldCollection<MessageConstant>&
00138       constantMembers = MessageFieldCollection<MessageConstant>(),
00139       const MessageFieldCollection<MessageVariable>&
00140       variableMembers = MessageFieldCollection<MessageVariable>());
00141     
00145     MessageDataType addMessageDataType(const std::string&
00146       identifier, const std::string& definition);
00147     
00151     template <typename T> MessageDataType addMessageDataType();
00152     
00155     void addDataType(const DataType& dataType);
00156     
00160     template <typename T> void addDataType();
00161     
00164     void removeDataType(const DataType& dataType);
00165     
00168     void clear();
00169     
00170   protected:
00173     class Impl {
00174     public:
00177       Impl();
00178       
00181       ~Impl();
00182       
00185       boost::unordered_map<std::string, DataType> dataTypesByIdentifier;
00186       
00189       boost::unordered_multimap<const std::type_info*, DataType, TypeInfoHash>
00190         dataTypesByInfo;
00191    };
00192     
00196     typedef boost::shared_ptr<Impl> ImplPtr;
00197     
00201     typedef boost::weak_ptr<Impl> ImplWPtr;
00202     
00205     static ImplPtr impl;
00206     
00210     template <typename T> static BuiltinDataType createDataType(typename
00211       boost::enable_if<type_traits::IsBuiltin<T> >::type* = 0);
00212     
00216     template <typename T> static ArrayDataType createDataType(typename
00217       boost::enable_if<type_traits::IsArray<T> >::type* = 0);
00218     
00222     template <typename T> static MessageDataType createDataType(typename
00223       boost::enable_if<type_traits::IsMessage<T> >::type* = 0);      
00224   };
00225     
00228   std::ostream& operator<<(std::ostream& stream, const DataTypeRegistry&
00229     dataTypeRegistry);
00230 };
00231 
00232 #include <variant_topic_tools/DataTypeRegistry.tpp>
00233 
00234 #endif


variant_topic_tools
Author(s): Ralf Kaestner
autogenerated on Tue Jul 9 2019 03:18:42