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 : public ros::Message
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
00077
00078 ros::Publisher advertise(ros::NodeHandle& nh, const std::string& topic, uint32_t queue_size_, bool latch=false) const;
00079
00081 template<class M>
00082 boost::shared_ptr<M> instantiate() const;
00083
00085 template<typename Stream>
00086 void write(Stream& stream) const;
00087
00088 template<typename Stream>
00089 void read(Stream& stream);
00090
00092 uint32_t size() const;
00093
00094
00095 ROS_DEPRECATED virtual const std::string __getDataType() const;
00096 ROS_DEPRECATED virtual const std::string __getMD5Sum() const;
00097 ROS_DEPRECATED virtual const std::string __getMessageDefinition() const;
00098
00099 ROS_DEPRECATED static const std::string __s_getDataType();
00100 ROS_DEPRECATED static const std::string __s_getMD5Sum();
00101 ROS_DEPRECATED static const std::string __s_getMessageDefinition();
00102
00103 ROS_DEPRECATED uint32_t serializationLength() const { return msgBufUsed; }
00104 ROS_DEPRECATED virtual uint8_t *serialize(uint8_t *writePtr, uint32_t) const;
00105 ROS_DEPRECATED virtual uint8_t *deserialize(uint8_t *readPtr);
00106
00107 private:
00108
00109 std::string md5, datatype, msg_def;
00110 bool typed;
00111
00112 uint8_t *msgBuf;
00113 uint32_t msgBufUsed;
00114 uint32_t msgBufAlloc;
00115
00116 };
00117
00118 }
00119
00120
00121
00122 namespace ros {
00123 namespace message_traits {
00124
00125 template<>
00126 struct MD5Sum<topic_tools::ShapeShifter>
00127 {
00128 static const char* value(const topic_tools::ShapeShifter& m) { return m.getMD5Sum().c_str(); }
00129
00130
00131 static const char* value() { return "*"; }
00132 };
00133
00134 template<>
00135 struct DataType<topic_tools::ShapeShifter>
00136 {
00137 static const char* value(const topic_tools::ShapeShifter& m) { return m.getDataType().c_str(); }
00138
00139
00140 static const char* value() { return "*"; }
00141 };
00142
00143 template<>
00144 struct Definition<topic_tools::ShapeShifter>
00145 {
00146 static const char* value(const topic_tools::ShapeShifter& m) { return m.getMessageDefinition().c_str(); }
00147 };
00148
00149 }
00150
00151
00152 namespace serialization
00153 {
00154
00155 template<>
00156 struct Serializer<topic_tools::ShapeShifter>
00157 {
00158 template<typename Stream>
00159 inline static void write(Stream& stream, const topic_tools::ShapeShifter& m) {
00160 m.write(stream);
00161 }
00162
00163 template<typename Stream>
00164 inline static void read(Stream& stream, topic_tools::ShapeShifter& m)
00165 {
00166 m.read(stream);
00167 }
00168
00169 inline static uint32_t serializedLength(const topic_tools::ShapeShifter& m) {
00170 return m.size();
00171 }
00172 };
00173
00174
00175 template<>
00176 struct PreDeserialize<topic_tools::ShapeShifter>
00177 {
00178 static void notify(const PreDeserializeParams<topic_tools::ShapeShifter>& params)
00179 {
00180 std::string md5 = (*params.connection_header)["md5sum"];
00181 std::string datatype = (*params.connection_header)["type"];
00182 std::string msg_def = (*params.connection_header)["message_definition"];
00183
00184 params.message->morph(md5, datatype, msg_def);
00185 }
00186 };
00187
00188 }
00189
00190 }
00191
00192
00193
00194
00195
00196 namespace topic_tools
00197 {
00198
00199 template<class M>
00200 boost::shared_ptr<M> ShapeShifter::instantiate() const
00201 {
00202 if (!typed)
00203 throw ShapeShifterException("Tried to instantiate message from an untyped shapeshifter.");
00204
00205 if (ros::message_traits::datatype<M>() != getDataType())
00206 throw ShapeShifterException("Tried to instantiate message without matching datatype.");
00207
00208 if (ros::message_traits::md5sum<M>() != getMD5Sum())
00209 throw ShapeShifterException("Tried to instantiate message without matching md5sum.");
00210
00211 boost::shared_ptr<M> p(new M());
00212
00213 ros::assignSubscriptionConnectionHeader<M>(p.get(), __connection_header);
00214
00215 ros::serialization::IStream s(msgBuf, msgBufUsed);
00216 ros::serialization::deserialize(s, *p);
00217
00218 return p;
00219 }
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