shape_shifter.hpp
Go to the documentation of this file.
1 /*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright 2016-2017 Davide Faconti
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 
36 #ifndef ROS_INTROPSECTION_SHAPE_SHIFTER2_H
37 #define ROS_INTROPSECTION_SHAPE_SHIFTER2_H
38 
39 #include "ros/ros.h"
40 #include "ros/console.h"
41 #include "ros/assert.h"
42 #include <vector>
43 #include <ros/message_traits.h>
45 
46 namespace RosIntrospection
47 {
48 
54 {
55 public:
58 
59  static bool uses_old_API_;
60 
61  // Constructor and destructor
62  ShapeShifter();
63  virtual ~ShapeShifter();
64 
65  // Helpers for inspecting ShapeShifter
66  std::string const& getDataType() const;
67  std::string const& getMD5Sum() const;
68  std::string const& getMessageDefinition() const;
69 
70  // Helper for advertising
71  ros::Publisher advertise(ros::NodeHandle& nh, const std::string& topic, uint32_t queue_size,
72  bool latch=false,
74 
76  template<class M>
77  void instantiate(M& destination) const;
78 
80  template<typename Stream>
81  void write(Stream& stream) const;
82 
83  const uint8_t* raw_data() const;
84 
85  template<typename Stream>
86  void read(Stream& stream);
87 
89  template<typename Message>
90  void direct_read(const Message& msg,bool morph);
91 
93  uint32_t size() const;
94 
95  void morph(const std::string& md5sum, const std::string& datatype_, const std::string& msg_def_);
96 
97 private:
98 
99  std::string md5_;
100  std::string datatype_;
101  std::string msg_def_;
102  bool typed_;
103 
104  mutable std::vector<uint8_t> msgBuf_;
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<RosIntrospection::ShapeShifter> : TrueType { };
116 template <> struct IsMessage<const RosIntrospection::ShapeShifter> : TrueType { };
117 
118 template<>
119 struct MD5Sum<RosIntrospection::ShapeShifter>
120 {
121  static const char* value(const RosIntrospection::ShapeShifter& m) { return m.getMD5Sum().data(); }
122 
123  // Used statically, a ShapeShifter2 appears to be of any type
124  static const char* value() { return "*"; }
125 };
126 
127 template<>
128 struct DataType<RosIntrospection::ShapeShifter>
129 {
130  static const char* value(const RosIntrospection::ShapeShifter& m) { return m.getDataType().data(); }
131 
132  // Used statically, a ShapeShifter2 appears to be of any type
133  static const char* value() { return "*"; }
134 };
135 
136 template<>
137 struct Definition<RosIntrospection::ShapeShifter>
138 {
139  static const char* value(const RosIntrospection::ShapeShifter& m) { return m.getMessageDefinition().data(); }
140 };
141 
142 } // namespace message_traits
143 
144 
145 namespace serialization
146 {
147 
148 template<>
150 {
151  template<typename Stream>
152  inline static void write(Stream& stream, const RosIntrospection::ShapeShifter& m) {
153  m.write(stream);
154  }
155 
156  template<typename Stream>
157  inline static void read(Stream& stream, RosIntrospection::ShapeShifter& m)
158  {
159  m.read(stream);
160  }
161 
162  inline static uint32_t serializedLength(const RosIntrospection::ShapeShifter& m) {
163  return m.size();
164  }
165 };
166 
167 
168 template<>
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 
177  params.message->morph(md5, datatype, msg_def);
178  }
179 };
180 
181 } // namespace serialization
182 
183 } //namespace ros
184 
185 
186 
187 // Template implementations:
188 
189 namespace RosIntrospection
190 {
191 
192 template<class M> inline
193 void ShapeShifter::instantiate(M& destination) const
194 {
195  if (!typed_)
196  throw std::runtime_error("Tried to instantiate message from an untyped ShapeShifter2.");
197 
198  if (ros::message_traits::datatype<M>() != getDataType())
199  throw std::runtime_error("Tried to instantiate message without matching datatype.");
200 
201  if (ros::message_traits::md5sum<M>() != getMD5Sum())
202  throw std::runtime_error("Tried to instantiate message without matching md5sum.");
203 
204  ros::serialization::IStream s(msgBuf_.data(), msgBuf_.size() );
205  ros::serialization::deserialize(s, destination);
206 
207 }
208 
209 template<typename Stream> inline
210 void ShapeShifter::write(Stream& stream) const {
211  if (msgBuf_.size() > 0)
212  memcpy(stream.advance(msgBuf_.size()), msgBuf_.data(), msgBuf_.size());
213 }
214 
215 inline const uint8_t* ShapeShifter::raw_data() const {
216  return msgBuf_.data();
217 }
218 
219 inline uint32_t ShapeShifter::size() const
220 {
221  return msgBuf_.size();
222 }
223 
224 template<typename Stream> inline
225 void ShapeShifter::read(Stream& stream)
226 {
227  //allocate enough space
228  msgBuf_.resize( stream.getLength() );
229  //copy
230  memcpy(msgBuf_.data(), stream.getData(), stream.getLength());
231 }
232 
233 template<typename Message> inline
234 void ShapeShifter::direct_read(const Message& msg, bool do_morph)
235 {
236  if(do_morph)
237  {
238  this->morph(
242  }
243 
244  auto length = ros::serialization::serializationLength(msg);
245 
246  //allocate enough space
247  msgBuf_.resize( length );
248  //copy
249  ros::serialization::OStream o_stream(msgBuf_.data(), length);
250  ros::serialization::serialize(o_stream, msg);
251 }
252 
254  : typed_(false),
255  msgBuf_()
256 {
257 }
258 
259 
261 {
262 
263 }
264 
265 
266 inline std::string const& ShapeShifter::getDataType() const { return datatype_; }
267 
268 
269 inline std::string const& ShapeShifter::getMD5Sum() const { return md5_; }
270 
271 
272 inline std::string const& ShapeShifter::getMessageDefinition() const { return msg_def_; }
273 
274 
275 inline void ShapeShifter::morph(const std::string& _md5sum, const std::string& _datatype, const std::string& _msg_def)
276 {
277  md5_ = _md5sum;
278  datatype_ = _datatype;
279  msg_def_ = _msg_def;
280  typed_ = (md5_ != "*");
281 }
282 
283 
284 inline ros::Publisher ShapeShifter::advertise(ros::NodeHandle& nh, const std::string& topic, uint32_t queue_size, bool latch,
285  const ros::SubscriberStatusCallback &connect_cb) const
286 {
287  ros::AdvertiseOptions opts(topic, queue_size, getMD5Sum(), getDataType(), getMessageDefinition(), connect_cb);
288  opts.latch = latch;
289  return nh.advertise(opts);
290 }
291 
292 } // namespace
293 
294 
295 #endif
296 
void direct_read(const Message &msg, bool morph)
! Directly serialize the contentof a message into this ShapeShifter.
const uint8_t * raw_data() const
boost::function< void(const SingleSubscriberPublisher &)> SubscriberStatusCallback
static const char * value(const RosIntrospection::ShapeShifter &m)
std::vector< uint8_t > msgBuf_
XmlRpcServer s
The ShapeShifter class is a type erased container for ROS Messages. It can be used also to create gen...
static void notify(const PreDeserializeParams< RosIntrospection::ShapeShifter > &params)
void instantiate(M &destination) const
Call to try instantiating as a particular type.
void morph(const std::string &md5sum, const std::string &datatype_, const std::string &msg_def_)
std::string const & getMD5Sum() const
static void read(Stream &stream, RosIntrospection::ShapeShifter &m)
const char * datatype()
uint32_t size() const
Return the size of the serialized message.
void serialize(Stream &stream, const T &t)
ros::Publisher advertise(ros::NodeHandle &nh, const std::string &topic, uint32_t queue_size, bool latch=false, const ros::SubscriberStatusCallback &connect_cb=ros::SubscriberStatusCallback()) const
static uint32_t serializedLength(const RosIntrospection::ShapeShifter &m)
static const char * value(const RosIntrospection::ShapeShifter &m)
std::string const & getDataType() const
void write(Stream &stream) const
Write serialized message contents out to a stream.
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
boost::shared_ptr< ShapeShifter > Ptr
boost::shared_ptr< ShapeShifter const > ConstPtr
std::string const & getMessageDefinition() const
uint32_t serializationLength(const T &t)
boost::shared_ptr< std::map< std::string, std::string > > connection_header
void deserialize(Stream &stream, T &t)
static const char * value(const RosIntrospection::ShapeShifter &m)
static void write(Stream &stream, const RosIntrospection::ShapeShifter &m)


ros_type_introspection
Author(s): Davide Faconti
autogenerated on Sun Sep 6 2020 03:19:54