shape_shifter.h
Go to the documentation of this file.
1 /*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2009, Willow Garage, Inc.
5 * All rights reserved.
6 *
7 * Redistribution and use in source and binary forms, with or without
8 * modification, are permitted provided that the following conditions
9 * are met:
10 *
11 * * Redistributions of source code must retain the above copyright
12 * notice, this list of conditions and the following disclaimer.
13 * * Redistributions in binary form must reproduce the above
14 * copyright notice, this list of conditions and the following
15 * disclaimer in the documentation and/or other materials provided
16 * with the distribution.
17 * * Neither the name of Willow Garage, Inc. nor the names of its
18 * contributors may be used to endorse or promote products derived
19 * from this software without specific prior written permission.
20 *
21 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32 * POSSIBILITY OF SUCH DAMAGE.
33 ********************************************************************/
34 
35 #ifndef TOPIC_TOOLS_SHAPE_SHIFTER_H
36 #define TOPIC_TOOLS_SHAPE_SHIFTER_H
37 
38 #include "ros/ros.h"
39 #include "ros/console.h"
40 #include "ros/assert.h"
41 #include <vector>
42 #include <string>
43 #include <string.h>
44 
45 #include <ros/message_traits.h>
46 #include "macros.h"
47 
48 namespace topic_tools
49 {
50 
52 {
53 public:
54  ShapeShifterException(const std::string& msg)
55  : ros::Exception(msg) {}
56 };
57 
58 
60 {
61 public:
64 
65  static bool uses_old_API_;
66 
67  // Constructor and destructor
68  ShapeShifter();
69  virtual ~ShapeShifter();
70 
71  // Helpers for inspecting shapeshifter
72  std::string const& getDataType() const;
73  std::string const& getMD5Sum() const;
74  std::string const& getMessageDefinition() const;
75 
76  void morph(const std::string& md5sum, const std::string& datatype, const std::string& msg_def,
77  const std::string& latching);
78 
79  // Helper for advertising
80  ros::Publisher advertise(ros::NodeHandle& nh, const std::string& topic, uint32_t queue_size_, bool latch=false,
82 
84  template<class M>
85  boost::shared_ptr<M> instantiate() const;
86 
88  template<typename Stream>
89  void write(Stream& stream) const;
90 
91  template<typename Stream>
92  void read(Stream& stream);
93 
95  uint32_t size() const;
96 
97 private:
98 
99  std::string md5, datatype, msg_def, latching;
100  bool typed;
101 
102  uint8_t *msgBuf;
103  uint32_t msgBufUsed;
104  uint32_t msgBufAlloc;
105 
106 };
107 
108 }
109 
110 
111 // Message traits allow shape shifter to work with the new serialization API
112 namespace ros {
113 namespace message_traits {
114 
115 template <> struct IsMessage<topic_tools::ShapeShifter> : TrueType { };
116 template <> struct IsMessage<const topic_tools::ShapeShifter> : TrueType { };
117 
118 template<>
119 struct MD5Sum<topic_tools::ShapeShifter>
120 {
121  static const char* value(const topic_tools::ShapeShifter& m) { return m.getMD5Sum().c_str(); }
122 
123  // Used statically, a shapeshifter appears to be of any type
124  static const char* value() { return "*"; }
125 };
126 
127 template<>
128 struct DataType<topic_tools::ShapeShifter>
129 {
130  static const char* value(const topic_tools::ShapeShifter& m) { return m.getDataType().c_str(); }
131 
132  // Used statically, a shapeshifter appears to be of any type
133  static const char* value() { return "*"; }
134 };
135 
136 template<>
137 struct Definition<topic_tools::ShapeShifter>
138 {
139  static const char* value(const topic_tools::ShapeShifter& m) { return m.getMessageDefinition().c_str(); }
140 };
141 
142 } // namespace message_traits
143 
144 
145 namespace serialization
146 {
147 
148 template<>
149 struct Serializer<topic_tools::ShapeShifter>
150 {
151  template<typename Stream>
152  inline static void write(Stream& stream, const topic_tools::ShapeShifter& m) {
153  m.write(stream);
154  }
155 
156  template<typename Stream>
157  inline static void read(Stream& stream, topic_tools::ShapeShifter& m)
158  {
159  m.read(stream);
160  }
161 
162  inline static uint32_t serializedLength(const topic_tools::ShapeShifter& m) {
163  return m.size();
164  }
165 };
166 
167 
168 template<>
169 struct PreDeserialize<topic_tools::ShapeShifter>
170 {
172  {
173  std::string md5 = (*params.connection_header)["md5sum"];
174  std::string datatype = (*params.connection_header)["type"];
175  std::string msg_def = (*params.connection_header)["message_definition"];
176  std::string latching = (*params.connection_header)["latching"];
177 
178  params.message->morph(md5, datatype, msg_def, latching);
179  }
180 };
181 
182 } // namespace serialization
183 
184 } //namespace ros
185 
186 
187 
188 // Template implementations:
189 
190 namespace topic_tools
191 {
192 
193  //
194  // only used in testing, seemingly
195  //
196 template<class M>
198 {
199  if (!typed)
200  throw ShapeShifterException("Tried to instantiate message from an untyped shapeshifter.");
201 
202  if (ros::message_traits::datatype<M>() != getDataType())
203  throw ShapeShifterException("Tried to instantiate message without matching datatype.");
204 
205  if (ros::message_traits::md5sum<M>() != getMD5Sum())
206  throw ShapeShifterException("Tried to instantiate message without matching md5sum.");
207 
208  boost::shared_ptr<M> p(boost::make_shared<M>());
209 
210  ros::serialization::IStream s(msgBuf, msgBufUsed);
212 
213  return p;
214 }
215 
216 template<typename Stream>
217 void ShapeShifter::write(Stream& stream) const {
218  if (msgBufUsed > 0)
219  memcpy(stream.advance(msgBufUsed), msgBuf, msgBufUsed);
220 }
221 
222 template<typename Stream>
223 void ShapeShifter::read(Stream& stream)
224 {
225  stream.getLength();
226  stream.getData();
227 
228  // stash this message in our buffer
229  if (stream.getLength() > msgBufAlloc)
230  {
231  delete[] msgBuf;
232  msgBuf = new uint8_t[stream.getLength()];
233  msgBufAlloc = stream.getLength();
234  }
235  msgBufUsed = stream.getLength();
236  memcpy(msgBuf, stream.getData(), stream.getLength());
237 }
238 
239 } // namespace topic_tools
240 
241 
242 #endif
243 
boost::function< void(const SingleSubscriberPublisher &)> SubscriberStatusCallback
std::string const & getDataType() const
boost::shared_ptr< ShapeShifter const > ConstPtr
Definition: shape_shifter.h:63
uint32_t size() const
Return the size of the serialized message.
void write(Stream &stream) const
Write serialized message contents out to a stream.
static uint32_t serializedLength(const topic_tools::ShapeShifter &m)
static const char * value(const topic_tools::ShapeShifter &m)
XmlRpcServer s
static void write(Stream &stream, const topic_tools::ShapeShifter &m)
#define TOPIC_TOOLS_DECL
Definition: macros.h:42
static const char * value(const topic_tools::ShapeShifter &m)
const char * datatype()
Exception(const std::string &what)
static const char * value(const topic_tools::ShapeShifter &m)
ShapeShifterException(const std::string &msg)
Definition: shape_shifter.h:54
std::string const & getMD5Sum() const
std::string const & getMessageDefinition() const
boost::shared_ptr< M > instantiate() const
Call to try instantiating as a particular type.
boost::shared_ptr< ShapeShifter > Ptr
Definition: shape_shifter.h:62
void read(Stream &stream)
boost::shared_ptr< std::map< std::string, std::string > > connection_header
static void read(Stream &stream, topic_tools::ShapeShifter &m)
void deserialize(Stream &stream, T &t)
static void notify(const PreDeserializeParams< topic_tools::ShapeShifter > &params)


topic_tools
Author(s): Morgan Quigley, Brian Gerkey, Dirk Thomas
autogenerated on Mon Nov 2 2020 03:52:58