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_RESPONSE_WRAPPER_H
00031 #define RVIZ_RPC_RESPONSE_WRAPPER_H
00032
00033 #include "serializable_message.h"
00034
00035 #include <rve_rpc/Response.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 ResponseWrapper
00050 {
00051 ResponseWrapper()
00052 : protocol(0)
00053 , error_code(0)
00054 {}
00055
00056 rve_common::UUID request_id;
00057 uint8_t protocol;
00058 uint8_t error_code;
00059 std::string error_string;
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<ResponseWrapper> ResponseWrapperPtr;
00087 typedef boost::shared_ptr<ResponseWrapper const> ResponseWrapperConstPtr;
00088
00089 template<typename M>
00090 ResponseWrapperPtr makeResponse(const boost::shared_ptr<M>& msg)
00091 {
00092 ResponseWrapperPtr res(boost::make_shared<ResponseWrapper>());
00093 res->message.message = msg;
00094 res->message.serialize = serialize<M>;
00095 res->message.serialized_length = serializedLength<M>;
00096 res->message.ti = &typeid(M);
00097 return res;
00098 }
00099
00100 template<typename M>
00101 std::pair<ResponseWrapperPtr, boost::shared_ptr<M> > makeResponse()
00102 {
00103 boost::shared_ptr<M> msg(boost::make_shared<M>());
00104 return std::make_pair(makeResponse(msg), msg);
00105 }
00106
00107 }
00108
00109 namespace ros
00110 {
00111
00112 namespace message_traits
00113 {
00114
00115 template<>
00116 struct MD5Sum<rve_rpc::ResponseWrapper> {
00117 static const char* value() { return MD5Sum<rve_rpc::Response>::value(); }
00118 static const char* value(const rve_rpc::ResponseWrapper& w) { return value(); }
00119 };
00120
00121 template<>
00122 struct DataType<rve_rpc::ResponseWrapper> {
00123 static const char* value() { return DataType<rve_rpc::Response>::value(); }
00124 static const char* value(const rve_rpc::ResponseWrapper& w) { return value(); }
00125 };
00126
00127 template<>
00128 struct Definition<rve_rpc::ResponseWrapper> {
00129 static const char* value() { return Definition<rve_rpc::Response>::value(); }
00130 static const char* value(const rve_rpc::ResponseWrapper& w) { return value(); }
00131 };
00132
00133 }
00134
00135 namespace serialization
00136 {
00137
00138 template<>
00139 struct Serializer<rve_rpc::ResponseWrapper>
00140 {
00141 template<typename Stream>
00142 inline static void write(Stream& stream, const rve_rpc::ResponseWrapper& r)
00143 {
00144 stream.next(rve_msgs::UUID(r.request_id));
00145 stream.next(r.protocol);
00146 stream.next(r.error_code);
00147 stream.next(r.error_string);
00148
00149 if (r.message.serialize)
00150 {
00151 SerializedMessage sm = r.message.serialize(r.message.message);
00152 uint32_t len = sm.num_bytes;
00153 memcpy(stream.advance(len), sm.buf.get(), len);
00154 }
00155 else
00156 {
00157 stream.next((uint32_t)0);
00158 }
00159 }
00160
00161 template<typename Stream>
00162 inline static void read(Stream& stream, rve_rpc::ResponseWrapper& r)
00163 {
00164 rve_msgs::UUID req_id;
00165 stream.next(req_id);
00166 r.request_id = req_id;
00167 stream.next(r.protocol);
00168 stream.next(r.error_code);
00169 stream.next(r.error_string);
00170 uint32_t len = 0;
00171 stream.next(len);
00172 r.serialized_message.num_bytes = len;
00173 r.serialized_message.buf.reset(new uint8_t[len]);
00174 r.serialized_message.message_start = r.serialized_message.buf.get();
00175 memcpy(r.serialized_message.buf.get(), stream.advance(len), len);
00176 }
00177
00178 inline static uint32_t serializedLength(const rve_rpc::ResponseWrapper& r)
00179 {
00180 uint32_t size = 0;
00181 size += sizeof(r.request_id);
00182 size += serializationLength(r.protocol);
00183 size += serializationLength(r.error_code);
00184 size += serializationLength(r.error_string);
00185 size += 4;
00186 if (r.serialized_message.buf)
00187 {
00188 size += r.serialized_message.num_bytes;
00189 }
00190 else if (r.message.serialized_length)
00191 {
00192 size += r.message.serialized_length(r.message.message);
00193 }
00194 return size;
00195 }
00196
00197 };
00198
00199 }
00200
00201 }
00202
00203 #endif // RVIZ_RPC_RESPONSE_WRAPPER_H