3 #ifndef NIMBRO_RELAY_SHAPE_SHIFTER_H
4 #define NIMBRO_RELAY_SHAPE_SHIFTER_H
7 #include "ros/console.h"
8 #include "ros/assert.h"
13 #include <ros/message_traits.h>
16 namespace nimbro_relay
19 class ShapeShifterException :
public ros::Exception
22 ShapeShifterException(
const std::string& msg)
23 : ros::Exception(msg) {}
27 class NIMBRO_RELAY_DECL ShapeShifter
30 typedef boost::shared_ptr<ShapeShifter> Ptr;
31 typedef boost::shared_ptr<ShapeShifter const> ConstPtr;
33 static bool uses_old_API_;
37 virtual ~ShapeShifter();
40 std::string
const& getDataType()
const;
41 std::string
const& getMD5Sum()
const;
42 std::string
const& getMessageDefinition()
const;
44 void morph(
const std::string& md5sum,
const std::string& datatype,
const std::string& msg_def,
45 const std::string& latching);
48 ros::Publisher advertise(ros::NodeHandle& nh,
const std::string& topic, uint32_t queue_size_,
bool latch=
false,
49 const ros::SubscriberStatusCallback &connect_cb=ros::SubscriberStatusCallback())
const;
53 boost::shared_ptr<M> instantiate()
const;
56 template<
typename Stream>
57 void write(Stream& stream)
const;
59 template<
typename Stream>
60 void read(Stream& stream);
63 uint32_t size()
const;
67 std::string md5, datatype, msg_def, latching;
81 namespace message_traits {
83 template <>
struct IsMessage<nimbro_relay::ShapeShifter> : TrueType { };
84 template <>
struct IsMessage<const nimbro_relay::ShapeShifter> : TrueType { };
87 struct MD5Sum<nimbro_relay::ShapeShifter>
89 static const char* value(
const nimbro_relay::ShapeShifter& m) {
return m.getMD5Sum().c_str(); }
92 static const char* value() {
return "*"; }
96 struct DataType<nimbro_relay::ShapeShifter>
98 static const char* value(
const nimbro_relay::ShapeShifter& m) {
return m.getDataType().c_str(); }
101 static const char* value() {
return "*"; }
105 struct Definition<nimbro_relay::ShapeShifter>
107 static const char* value(
const nimbro_relay::ShapeShifter& m) {
return m.getMessageDefinition().c_str(); }
113 namespace serialization
117 struct Serializer<nimbro_relay::ShapeShifter>
119 template<
typename Stream>
120 inline static void write(Stream& stream,
const nimbro_relay::ShapeShifter& m) {
124 template<
typename Stream>
125 inline static void read(Stream& stream, nimbro_relay::ShapeShifter& m)
130 inline static uint32_t serializedLength(
const nimbro_relay::ShapeShifter& m) {
137 struct PreDeserialize<nimbro_relay::ShapeShifter>
139 static void notify(
const PreDeserializeParams<nimbro_relay::ShapeShifter>& params)
141 std::string md5 = (*params.connection_header)[
"md5sum"];
142 std::string datatype = (*params.connection_header)[
"type"];
143 std::string msg_def = (*params.connection_header)[
"message_definition"];
144 std::string latching = (*params.connection_header)[
"latching"];
146 params.message->morph(md5, datatype, msg_def, latching);
158 namespace nimbro_relay
165 boost::shared_ptr<M> ShapeShifter::instantiate()
const
168 throw ShapeShifterException(
"Tried to instantiate message from an untyped shapeshifter.");
170 if (ros::message_traits::datatype<M>() != getDataType())
171 throw ShapeShifterException(
"Tried to instantiate message without matching datatype.");
173 if (ros::message_traits::md5sum<M>() != getMD5Sum())
174 throw ShapeShifterException(
"Tried to instantiate message without matching md5sum.");
176 boost::shared_ptr<M> p(boost::make_shared<M>());
178 ros::serialization::IStream s(msgBuf, msgBufUsed);
179 ros::serialization::deserialize(s, *p);
184 template<
typename Stream>
185 void ShapeShifter::write(Stream& stream)
const {
187 memcpy(stream.advance(msgBufUsed), msgBuf, msgBufUsed);
190 template<
typename Stream>
191 void ShapeShifter::read(Stream& stream)
197 if (stream.getLength() > msgBufAlloc)
200 msgBuf =
new uint8_t[stream.getLength()];
201 msgBufAlloc = stream.getLength();
203 msgBufUsed = stream.getLength();
204 memcpy(msgBuf, stream.getData(), stream.getLength());