NimbRo ROS Soccer Package
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Macros Groups Pages
shape_shifter.h
1 //It is a modified version of https://github.com/ros/ros_comm/
2 // Author: Hafez Farazi <farazi@ais.uni-bonn.de>
3 #ifndef NIMBRO_RELAY_SHAPE_SHIFTER_H
4 #define NIMBRO_RELAY_SHAPE_SHIFTER_H
5 
6 #include "ros/ros.h"
7 #include "ros/console.h"
8 #include "ros/assert.h"
9 #include <vector>
10 #include <string>
11 #include <string.h>
12 
13 #include <ros/message_traits.h>
14 #include "macros.h"
15 
16 namespace nimbro_relay
17 {
18 
19 class ShapeShifterException : public ros::Exception
20 {
21 public:
22  ShapeShifterException(const std::string& msg)
23  : ros::Exception(msg) {}
24 };
25 
26 
27 class NIMBRO_RELAY_DECL ShapeShifter
28 {
29 public:
30  typedef boost::shared_ptr<ShapeShifter> Ptr;
31  typedef boost::shared_ptr<ShapeShifter const> ConstPtr;
32 
33  static bool uses_old_API_;
34 
35  // Constructor and destructor
36  ShapeShifter();
37  virtual ~ShapeShifter();
38 
39  // Helpers for inspecting shapeshifter
40  std::string const& getDataType() const;
41  std::string const& getMD5Sum() const;
42  std::string const& getMessageDefinition() const;
43 
44  void morph(const std::string& md5sum, const std::string& datatype, const std::string& msg_def,
45  const std::string& latching);
46 
47  // Helper for advertising
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;
50 
52  template<class M>
53  boost::shared_ptr<M> instantiate() const;
54 
56  template<typename Stream>
57  void write(Stream& stream) const;
58 
59  template<typename Stream>
60  void read(Stream& stream);
61 
63  uint32_t size() const;
64 
65 private:
66 
67  std::string md5, datatype, msg_def, latching;
68  bool typed;
69 
70  uint8_t *msgBuf;
71  uint32_t msgBufUsed;
72  uint32_t msgBufAlloc;
73 
74 };
75 
76 }
77 
78 
79 // Message traits allow shape shifter to work with the new serialization API
80 namespace ros {
81 namespace message_traits {
82 
83 template <> struct IsMessage<nimbro_relay::ShapeShifter> : TrueType { };
84 template <> struct IsMessage<const nimbro_relay::ShapeShifter> : TrueType { };
85 
86 template<>
87 struct MD5Sum<nimbro_relay::ShapeShifter>
88 {
89  static const char* value(const nimbro_relay::ShapeShifter& m) { return m.getMD5Sum().c_str(); }
90 
91  // Used statically, a shapeshifter appears to be of any type
92  static const char* value() { return "*"; }
93 };
94 
95 template<>
96 struct DataType<nimbro_relay::ShapeShifter>
97 {
98  static const char* value(const nimbro_relay::ShapeShifter& m) { return m.getDataType().c_str(); }
99 
100  // Used statically, a shapeshifter appears to be of any type
101  static const char* value() { return "*"; }
102 };
103 
104 template<>
105 struct Definition<nimbro_relay::ShapeShifter>
106 {
107  static const char* value(const nimbro_relay::ShapeShifter& m) { return m.getMessageDefinition().c_str(); }
108 };
109 
110 } // namespace message_traits
111 
112 
113 namespace serialization
114 {
115 
116 template<>
117 struct Serializer<nimbro_relay::ShapeShifter>
118 {
119  template<typename Stream>
120  inline static void write(Stream& stream, const nimbro_relay::ShapeShifter& m) {
121  m.write(stream);
122  }
123 
124  template<typename Stream>
125  inline static void read(Stream& stream, nimbro_relay::ShapeShifter& m)
126  {
127  m.read(stream);
128  }
129 
130  inline static uint32_t serializedLength(const nimbro_relay::ShapeShifter& m) {
131  return m.size();
132  }
133 };
134 
135 
136 template<>
137 struct PreDeserialize<nimbro_relay::ShapeShifter>
138 {
139  static void notify(const PreDeserializeParams<nimbro_relay::ShapeShifter>& params)
140  {
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"];
145 
146  params.message->morph(md5, datatype, msg_def, latching);
147  }
148 };
149 
150 } // namespace serialization
151 
152 } //namespace ros
153 
154 
155 
156 // Template implementations:
157 
158 namespace nimbro_relay
159 {
160 
161  //
162  // only used in testing, seemingly
163  //
164 template<class M>
165 boost::shared_ptr<M> ShapeShifter::instantiate() const
166 {
167  if (!typed)
168  throw ShapeShifterException("Tried to instantiate message from an untyped shapeshifter.");
169 
170  if (ros::message_traits::datatype<M>() != getDataType())
171  throw ShapeShifterException("Tried to instantiate message without matching datatype.");
172 
173  if (ros::message_traits::md5sum<M>() != getMD5Sum())
174  throw ShapeShifterException("Tried to instantiate message without matching md5sum.");
175 
176  boost::shared_ptr<M> p(boost::make_shared<M>());
177 
178  ros::serialization::IStream s(msgBuf, msgBufUsed);
179  ros::serialization::deserialize(s, *p);
180 
181  return p;
182 }
183 
184 template<typename Stream>
185 void ShapeShifter::write(Stream& stream) const {
186  if (msgBufUsed > 0)
187  memcpy(stream.advance(msgBufUsed), msgBuf, msgBufUsed);
188 }
189 
190 template<typename Stream>
191 void ShapeShifter::read(Stream& stream)
192 {
193  stream.getLength();
194  stream.getData();
195 
196  // stash this message in our buffer
197  if (stream.getLength() > msgBufAlloc)
198  {
199  delete[] msgBuf;
200  msgBuf = new uint8_t[stream.getLength()];
201  msgBufAlloc = stream.getLength();
202  }
203  msgBufUsed = stream.getLength();
204  memcpy(msgBuf, stream.getData(), stream.getLength());
205 }
206 
207 } // namespace nimbro_relay
208 
209 
210 #endif
211