Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032 #ifndef TYPED_MESSAGE_H
00033 #define TYPED_MESSAGE_H
00034
00035 #ifndef FLATHEADERS
00036 #include "simple_message/simple_message.h"
00037 #include "simple_message/byte_array.h"
00038 #else
00039 #include "simple_message.h"
00040 #include "byte_array.h"
00041 #endif
00042
00043
00044 namespace industrial
00045 {
00046 namespace typed_message
00047 {
00048
00074 class TypedMessage : public industrial::simple_serialize::SimpleSerialize
00075 {
00076
00077 public:
00083 virtual bool init(industrial::simple_message::SimpleMessage & msg)=0;
00084
00089 virtual void init()=0;
00090
00096 virtual bool toRequest(industrial::simple_message::SimpleMessage & msg)
00097 {
00098 industrial::byte_array::ByteArray data;
00099 data.load(*this);
00100 return msg.init(this->getMessageType(),
00101 industrial::simple_message::CommTypes::SERVICE_REQUEST,
00102 industrial::simple_message::ReplyTypes::INVALID, data);
00103 }
00104
00110 virtual bool toReply(industrial::simple_message::SimpleMessage & msg,
00111 industrial::simple_message::ReplyType reply)
00112 {
00113 industrial::byte_array::ByteArray data;
00114 data.load(*this);
00115 return msg.init(this->getMessageType(),
00116 industrial::simple_message::CommTypes::SERVICE_REPLY,
00117 reply, data);
00118 }
00124 virtual bool toTopic(industrial::simple_message::SimpleMessage & msg)
00125 {
00126 industrial::byte_array::ByteArray data;
00127 data.load(*this);
00128 return msg.init(this->getMessageType(),
00129 industrial::simple_message::CommTypes::TOPIC,
00130 industrial::simple_message::ReplyTypes::INVALID, data);
00131 }
00137 int getMessageType() const
00138 {
00139 return message_type_;
00140 }
00141
00142 protected:
00143
00149 void setMessageType(int message_type = industrial::simple_message::StandardMsgTypes::INVALID)
00150 {
00151 this->message_type_ = message_type;
00152 }
00153
00154 private:
00155
00160 int message_type_;
00161
00162 };
00163
00164 }
00165 }
00166
00167 #endif