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
00033
00034
00035 #ifndef TOPIC_TOOLS_SHAPE_SHIFTER_H
00036 #define TOPIC_TOOLS_SHAPE_SHIFTER_H
00037
00038 #include "ros/ros.h"
00039 #include "ros/console.h"
00040 #include "ros/assert.h"
00041 #include <vector>
00042 #include <string>
00043 #include <string.h>
00044
00045 #include <ros/message_traits.h>
00046
00047 namespace topic_tools
00048 {
00049
00050 class ShapeShifterException : public ros::Exception
00051 {
00052 public:
00053 ShapeShifterException(const std::string& msg)
00054 : ros::Exception(msg) {}
00055 };
00056
00057
00058 class ShapeShifter
00059 {
00060 public:
00061 typedef boost::shared_ptr<ShapeShifter> Ptr;
00062 typedef boost::shared_ptr<ShapeShifter const> ConstPtr;
00063
00064 static bool uses_old_API_;
00065
00066
00067 ShapeShifter();
00068 virtual ~ShapeShifter();
00069
00070
00071 std::string const& getDataType() const;
00072 std::string const& getMD5Sum() const;
00073 std::string const& getMessageDefinition() const;
00074
00075 void morph(const std::string& md5sum, const std::string& datatype, const std::string& msg_def,
00076 const std::string& latching);
00077
00078
00079 ros::Publisher advertise(ros::NodeHandle& nh, const std::string& topic, uint32_t queue_size_, bool latch=false,
00080 const ros::SubscriberStatusCallback &connect_cb=ros::SubscriberStatusCallback()) const;
00081
00083 template<class M>
00084 boost::shared_ptr<M> instantiate() const;
00085
00087 template<typename Stream>
00088 void write(Stream& stream) const;
00089
00090 template<typename Stream>
00091 void read(Stream& stream);
00092
00094 uint32_t size() const;
00095
00096 boost::shared_ptr<std::map<std::string, std::string> > __connection_header;
00097
00098 private:
00099
00100 std::string md5, datatype, msg_def, latching;
00101 bool typed;
00102
00103 uint8_t *msgBuf;
00104 uint32_t msgBufUsed;
00105 uint32_t msgBufAlloc;
00106
00107 };
00108
00109 }
00110
00111
00112
00113 namespace ros {
00114 namespace message_traits {
00115
00116 template <> struct IsMessage<topic_tools::ShapeShifter> : TrueType { };
00117 template <> struct IsMessage<const topic_tools::ShapeShifter> : TrueType { };
00118
00119 template<>
00120 struct MD5Sum<topic_tools::ShapeShifter>
00121 {
00122 static const char* value(const topic_tools::ShapeShifter& m) { return m.getMD5Sum().c_str(); }
00123
00124
00125 static const char* value() { return "*"; }
00126 };
00127
00128 template<>
00129 struct DataType<topic_tools::ShapeShifter>
00130 {
00131 static const char* value(const topic_tools::ShapeShifter& m) { return m.getDataType().c_str(); }
00132
00133
00134 static const char* value() { return "*"; }
00135 };
00136
00137 template<>
00138 struct Definition<topic_tools::ShapeShifter>
00139 {
00140 static const char* value(const topic_tools::ShapeShifter& m) { return m.getMessageDefinition().c_str(); }
00141 };
00142
00143 }
00144
00145
00146 namespace serialization
00147 {
00148
00149 template<>
00150 struct Serializer<topic_tools::ShapeShifter>
00151 {
00152 template<typename Stream>
00153 inline static void write(Stream& stream, const topic_tools::ShapeShifter& m) {
00154 m.write(stream);
00155 }
00156
00157 template<typename Stream>
00158 inline static void read(Stream& stream, topic_tools::ShapeShifter& m)
00159 {
00160 m.read(stream);
00161 }
00162
00163 inline static uint32_t serializedLength(const topic_tools::ShapeShifter& m) {
00164 return m.size();
00165 }
00166 };
00167
00168
00169 template<>
00170 struct PreDeserialize<topic_tools::ShapeShifter>
00171 {
00172 static void notify(const PreDeserializeParams<topic_tools::ShapeShifter>& params)
00173 {
00174 std::string md5 = (*params.connection_header)["md5sum"];
00175 std::string datatype = (*params.connection_header)["type"];
00176 std::string msg_def = (*params.connection_header)["message_definition"];
00177 std::string latching = (*params.connection_header)["latching"];
00178
00179 typedef std::map<std::string, std::string> map_t;
00180 boost::shared_ptr<map_t> shmap(new map_t(*params.connection_header));
00181 params.message->__connection_header = shmap;
00182 params.message->morph(md5, datatype, msg_def, latching);
00183 }
00184 };
00185
00186 }
00187
00188 }
00189
00190
00191
00192
00193
00194 namespace topic_tools
00195 {
00196
00197
00198
00199
00200 template<class M>
00201 boost::shared_ptr<M> ShapeShifter::instantiate() const
00202 {
00203 if (!typed)
00204 throw ShapeShifterException("Tried to instantiate message from an untyped shapeshifter.");
00205
00206 if (ros::message_traits::datatype<M>() != getDataType())
00207 throw ShapeShifterException("Tried to instantiate message without matching datatype.");
00208
00209 if (ros::message_traits::md5sum<M>() != getMD5Sum())
00210 throw ShapeShifterException("Tried to instantiate message without matching md5sum.");
00211
00212 boost::shared_ptr<M> p(new M());
00213
00214 ros::assignSubscriptionConnectionHeader<M>(p.get(), __connection_header);
00215
00216 ros::serialization::IStream s(msgBuf, msgBufUsed);
00217 ros::serialization::deserialize(s, *p);
00218
00219 return p;
00220 }
00221
00222 template<typename Stream>
00223 void ShapeShifter::write(Stream& stream) const {
00224 if (msgBufUsed > 0)
00225 memcpy(stream.advance(msgBufUsed), msgBuf, msgBufUsed);
00226 }
00227
00228 template<typename Stream>
00229 void ShapeShifter::read(Stream& stream)
00230 {
00231 stream.getLength();
00232 stream.getData();
00233
00234
00235 if (stream.getLength() > msgBufAlloc)
00236 {
00237 delete[] msgBuf;
00238 msgBuf = new uint8_t[stream.getLength()];
00239 msgBufAlloc = stream.getLength();
00240 }
00241 msgBufUsed = stream.getLength();
00242 memcpy(msgBuf, stream.getData(), stream.getLength());
00243 }
00244
00245 }
00246
00247
00248 #endif
00249