35 #ifndef TOPIC_TOOLS_SHAPE_SHIFTER_H 36 #define TOPIC_TOOLS_SHAPE_SHIFTER_H 72 std::string
const& getDataType()
const;
73 std::string
const& getMD5Sum()
const;
74 std::string
const& getMessageDefinition()
const;
76 void morph(
const std::string& md5sum,
const std::string& datatype,
const std::string& msg_def,
77 const std::string& latching);
88 template<
typename Stream>
89 void write(Stream& stream)
const;
91 template<
typename Stream>
92 void read(Stream& stream);
95 uint32_t size()
const;
113 namespace message_traits {
124 static const char*
value() {
return "*"; }
133 static const char*
value() {
return "*"; }
145 namespace serialization
151 template<
typename Stream>
156 template<
typename Stream>
178 params.
message->morph(md5, datatype, msg_def, latching);
202 if (ros::message_traits::datatype<M>() != getDataType())
205 if (ros::message_traits::md5sum<M>() != getMD5Sum())
216 template<
typename Stream>
219 memcpy(stream.advance(msgBufUsed), msgBuf, msgBufUsed);
222 template<
typename Stream>
229 if (stream.getLength() > msgBufAlloc)
232 msgBuf =
new uint8_t[stream.getLength()];
233 msgBufAlloc = stream.getLength();
235 msgBufUsed = stream.getLength();
236 memcpy(msgBuf, stream.getData(), stream.getLength());
boost::function< void(const SingleSubscriberPublisher &)> SubscriberStatusCallback
Exception(const std::string &what)
boost::shared_ptr< M > message
boost::shared_ptr< std::map< std::string, std::string > > connection_header
void deserialize(Stream &stream, T &t)