message.h
Go to the documentation of this file.
00001 //=================================================================================================
00002 // Copyright (c) 2011, Johannes Meyer, TU Darmstadt
00003 // All rights reserved.
00004 
00005 // Redistribution and use in source and binary forms, with or without
00006 // modification, are permitted provided that the following conditions are met:
00007 //     * Redistributions of source code must retain the above copyright
00008 //       notice, this list of conditions and the following disclaimer.
00009 //     * Redistributions in binary form must reproduce the above copyright
00010 //       notice, this list of conditions and the following disclaimer in the
00011 //       documentation and/or other materials provided with the distribution.
00012 //     * Neither the name of the Flight Systems and Automatic Control group,
00013 //       TU Darmstadt, nor the names of its contributors may be used to
00014 //       endorse or promote products derived from this software without
00015 //       specific prior written permission.
00016 
00017 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
00018 // ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
00019 // WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
00020 // DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER BE LIABLE FOR ANY
00021 // DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
00022 // (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00023 // LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
00024 // ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
00025 // (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
00026 // SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
00027 //=================================================================================================
00028 
00029 #ifndef CPP_INTROSPECTION_MESSAGE_H
00030 #define CPP_INTROSPECTION_MESSAGE_H
00031 
00032 #include <introspection/forwards.h>
00033 #include <introspection/field.h>
00034 
00035 #include <std_msgs/Header.h>
00036 #include <ros/time.h>
00037 
00038 namespace cpp_introspection {
00039 
00040   class Message
00041   {
00042   public:
00043     virtual ~Message() {}
00044 
00045     virtual PackagePtr package() const = 0;
00046     virtual const char* getPackageName() const = 0;
00047 
00048     virtual const char* getName() const = 0;
00049     virtual const char* getDataType() const = 0;
00050     virtual const char* getMD5Sum() const = 0;
00051     virtual const char* getDefinition() const = 0;
00052     virtual const std::type_info& getTypeId() const = 0;
00053 
00054     virtual bool isMessage() const { return true; }
00055     virtual bool isSimple() const = 0;
00056     virtual bool isFixedSize() const = 0;
00057     virtual bool hasHeader() const = 0;
00058 
00059     template <typename T> bool hasType() const { return getTypeId() == typeid(T); }
00060 
00061     virtual std_msgs::Header* getHeader(const VoidPtr& instance) const = 0;
00062     virtual const std_msgs::Header* getHeader(const VoidConstPtr& instance) const = 0;
00063     virtual std::string* getFrameId(const VoidPtr& instance) const = 0;
00064     virtual const std::string* getFrameId(const VoidConstPtr& instance) const = 0;
00065     virtual ros::Time* getTimeStamp(const VoidPtr& instance) const = 0;
00066     virtual const ros::Time* getTimeStamp(const VoidConstPtr& instance) const = 0;
00067 
00068     virtual const V_Field& fields() const = 0;
00069     virtual FieldWPtr field(const std::string& name) const = 0;
00070     virtual const V_FieldName& getFieldNames() const = 0;
00071 
00072     V_string getFields(bool expand = false, const std::string& separator = ".", const std::string& prefix = std::string()) const;
00073     V_string& getFields(V_string& fields, bool expand = false, const std::string& separator = ".", const std::string& prefix = std::string()) const;
00074     V_string getTypes(bool expand = false) const;
00075     V_string& getTypes(V_string& types, bool expand = false) const;
00076     std::vector<boost::any> getValues(bool expand = false) const;
00077     std::vector<boost::any>& getValues(std::vector<boost::any>& values, bool expand = false) const;
00078 
00079     virtual VoidPtr createInstance() const = 0;
00080     virtual void serialize(ros::serialization::OStream& stream, const VoidConstPtr& instance = VoidConstPtr()) const = 0;
00081     virtual ros::SerializedMessage serialize(const VoidConstPtr& instance = VoidConstPtr()) const = 0;
00082     virtual std::size_t serializationLength(const VoidConstPtr& instance = VoidConstPtr()) const = 0;
00083     virtual VoidPtr deserialize(ros::serialization::IStream& stream, const VoidPtr& instance = VoidPtr()) const = 0;
00084 
00085     virtual bool hasInstance() const { return false; }
00086     virtual VoidPtr getInstance() const { return VoidPtr(); }
00087     virtual VoidConstPtr getConstInstance() const { return VoidConstPtr(); }
00088     template <typename T> boost::shared_ptr<T> getInstanceAs() const { assert(getTypeId() == typeid(T)); return boost::shared_static_cast<T>(getInstance()); }
00089     template <typename T> boost::shared_ptr<T const> getConstInstanceAs() const { assert(getTypeId() == typeid(T)); return boost::shared_static_cast<T const>(getConstInstance()); }
00090 
00091     virtual MessagePtr introspect(const VoidPtr& instance) const = 0;
00092     virtual MessagePtr introspect(void *instance) const = 0;
00093     virtual MessagePtr introspect(const VoidConstPtr& instance) const = 0;
00094     virtual MessagePtr introspect(void const *instance) const = 0;
00095     virtual MessagePtr introspect() const { return introspect(createInstance()); }
00096 
00097     template <typename T> typename T::Ptr      narrow(const VoidPtr& instance) const      { return boost::shared_static_cast<T>(instance); }
00098     template <typename T> typename T::ConstPtr narrow(const VoidConstPtr& instance) const { return boost::shared_static_cast<T const>(instance); }
00099 
00100     typedef V_Field::iterator iterator;
00101     typedef V_Field::const_iterator const_iterator;
00102     const_iterator begin() const { return fields().begin(); }
00103     const_iterator end() const { return fields().end(); }
00104     std::size_t size() const { return fields().size(); }
00105   };
00106 
00107   MessagePtr messageByDataType(const std::string& data_type, const std::string& package = std::string());
00108   static inline MessagePtr messageByDataType(const char* data_type, const char* package) { return messageByDataType(std::string(data_type), std::string(package)); }
00109   MessagePtr messageByMD5Sum(const std::string& md5sum);
00110   static inline MessagePtr messageByMD5Sum(const char* md5sum) { return messageByMD5Sum(std::string(md5sum)); }
00111   MessagePtr messageByTypeId(const std::type_info& type_info);
00112 
00113   MessagePtr expand(const MessagePtr& message, const std::string &separator = ".", const std::string &prefix = "");
00114 
00115 } // namespace cpp_introspection
00116 
00117 namespace ros {
00118 namespace serialization {
00119 
00120   template<>
00121   struct Serializer<cpp_introspection::Message>
00122   {
00123     template<typename Stream>
00124     inline static void write(Stream& stream, const cpp_introspection::Message& message) {
00125       if (!message.hasInstance()) throw std::runtime_error("Tried to serialize a message without an instance");
00126       message.serialize(stream, message.getConstInstance());
00127     }
00128 
00129     inline static uint32_t serializedLength(const cpp_introspection::Message& message) {
00130       if (!message.hasInstance()) throw std::runtime_error("Tried to serialize a message without an instance");
00131       return message.serializationLength(message.getConstInstance());
00132     }
00133   };
00134 
00135 }
00136 }
00137 
00138 namespace ros {
00139 namespace message_traits {
00140 
00141   template<> struct MD5Sum<cpp_introspection::Message>
00142   {
00143     static const char* value(const cpp_introspection::Message& message) { return message.getMD5Sum(); }
00144   };
00145   template<> struct DataType<cpp_introspection::Message>
00146   {
00147     static const char* value(const cpp_introspection::Message& message) { return message.getDataType(); }
00148   };
00149   template<> struct Definition<cpp_introspection::Message>
00150   {
00151     static const char* value(const cpp_introspection::Message& message) { return message.getDefinition(); }
00152   };
00153 
00154 }
00155 }
00156 
00157 #endif // CPP_INTROSPECTION_MESSAGE_H


cpp_introspection
Author(s): Johannes Meyer
autogenerated on Sat Jun 8 2019 19:46:00