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 #ifndef RVIZ_RPC_REQUEST_WRAPPER_H
00031 #define RVIZ_RPC_REQUEST_WRAPPER_H
00032
00033 #include "serializable_message.h"
00034
00035 #include <rve_rpc/Request.h>
00036
00037 #include <rve_common/uuid.h>
00038
00039 #include <ros/message_traits.h>
00040 #include <ros/serialization.h>
00041
00042 #include <string>
00043
00044 #include <boost/make_shared.hpp>
00045
00046 namespace rve_rpc
00047 {
00048
00049 struct RequestWrapper
00050 {
00051 RequestWrapper()
00052 : protocol(0)
00053 {
00054
00055 }
00056
00057 rve_common::UUID request_id;
00058 uint8_t protocol;
00059 std::string method;
00060
00061 SerializableMessage message;
00062 ros::SerializedMessage serialized_message;
00063
00064 template<typename M>
00065 boost::shared_ptr<M const> instantiate() const
00066 {
00067 if (message.ti && *message.ti == typeid(M))
00068 {
00069 return boost::static_pointer_cast<M const>(message.message);
00070 }
00071 else if (serialized_message.buf)
00072 {
00073 boost::shared_ptr<M> m(boost::make_shared<M>());
00074 ros::serialization::deserializeMessage(serialized_message, *m);
00075 return m;
00076 }
00077 else
00078 {
00079 ros::SerializedMessage ser_m = message.serialize(message.message);
00080 boost::shared_ptr<M> m(boost::make_shared<M>());
00081 ros::serialization::deserializeMessage(ser_m, *m);
00082 return m;
00083 }
00084 }
00085 };
00086 typedef boost::shared_ptr<RequestWrapper> RequestWrapperPtr;
00087 typedef boost::shared_ptr<RequestWrapper const> RequestWrapperConstPtr;
00088
00089 template<typename M>
00090 std::pair<RequestWrapperPtr, boost::shared_ptr<M> > makeRequest()
00091 {
00092 RequestWrapperPtr req(boost::make_shared<RequestWrapper>());
00093 boost::shared_ptr<M> msg(boost::make_shared<M>());
00094 req->message.message = msg;
00095 req->message.serialize = serialize<M>;
00096 req->message.serialized_length = serializedLength<M>;
00097 req->message.ti = &typeid(M);
00098 return std::make_pair(req, msg);
00099 }
00100
00101 }
00102
00103 namespace ros
00104 {
00105
00106 namespace message_traits
00107 {
00108
00109 template<>
00110 struct MD5Sum<rve_rpc::RequestWrapper> {
00111 static const char* value() { return MD5Sum<rve_rpc::Request>::value(); }
00112 static const char* value(const rve_rpc::RequestWrapper& w) { return value(); }
00113 };
00114
00115 template<>
00116 struct DataType<rve_rpc::RequestWrapper> {
00117 static const char* value() { return DataType<rve_rpc::Request>::value(); }
00118 static const char* value(const rve_rpc::RequestWrapper& w) { return value(); }
00119 };
00120
00121 template<>
00122 struct Definition<rve_rpc::RequestWrapper> {
00123 static const char* value() { return Definition<rve_rpc::Request>::value(); }
00124 static const char* value(const rve_rpc::RequestWrapper& w) { return value(); }
00125 };
00126
00127 }
00128
00129 namespace serialization
00130 {
00131
00132 template<>
00133 struct Serializer<rve_rpc::RequestWrapper>
00134 {
00135 template<typename Stream>
00136 inline static void write(Stream& stream, const rve_rpc::RequestWrapper& r)
00137 {
00138 stream.next(rve_msgs::UUID(r.request_id));
00139 stream.next(r.protocol);
00140 stream.next(r.method);
00141
00142 if (r.message.serialize)
00143 {
00144 SerializedMessage sm = r.message.serialize(r.message.message);
00145 uint32_t len = sm.num_bytes;
00146 memcpy(stream.advance(len), sm.buf.get(), len);
00147 }
00148 else
00149 {
00150 stream.next((uint32_t)0);
00151 }
00152 }
00153
00154 template<typename Stream>
00155 inline static void read(Stream& stream, rve_rpc::RequestWrapper& r)
00156 {
00157 rve_msgs::UUID req_id;
00158 stream.next(req_id);
00159 r.request_id = req_id;
00160 stream.next(r.protocol);
00161 stream.next(r.method);
00162 uint32_t len = 0;
00163 stream.next(len);
00164 r.serialized_message.num_bytes = len;
00165 r.serialized_message.buf.reset(new uint8_t[len]);
00166 r.serialized_message.message_start = r.serialized_message.buf.get();
00167 memcpy(r.serialized_message.buf.get(), stream.advance(len), len);
00168 }
00169
00170 inline static uint32_t serializedLength(const rve_rpc::RequestWrapper& r)
00171 {
00172 uint32_t size = 0;
00173 size += sizeof(r.request_id);
00174 size += serializationLength(r.protocol);
00175 size += serializationLength(r.method);
00176 size += 4;
00177 if (r.serialized_message.buf)
00178 {
00179 size += r.serialized_message.num_bytes;
00180 }
00181 else if (r.message.serialized_length)
00182 {
00183 size += r.message.serialized_length(r.message.message);
00184 }
00185 return size;
00186 }
00187
00188 };
00189
00190 }
00191
00192 }
00193
00194 #endif // RVIZ_RPC_REQUEST_WRAPPER_H