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 <boost/flyweight.hpp>
44 #include <ros/message_traits.h>
46 
47 namespace RosIntrospection
48 {
49 
55 {
56 public:
59 
60  static bool uses_old_API_;
61 
62  // Constructor and destructor
63  ShapeShifter();
64  virtual ~ShapeShifter();
65 
66  // Helpers for inspecting ShapeShifter
67  std::string const& getDataType() const;
68  std::string const& getMD5Sum() const;
69  std::string const& getMessageDefinition() const;
70 
71  // Helper for advertising
72  ros::Publisher advertise(ros::NodeHandle& nh, const std::string& topic, uint32_t queue_size,
73  bool latch=false,
75 
77  template<class M>
78  void instantiate(M& destination) const;
79 
81  template<typename Stream>
82  void write(Stream& stream) const;
83 
84  const uint8_t* raw_data() const;
85 
86  template<typename Stream>
87  void read(Stream& stream);
88 
90  template<typename Message>
91  void direct_read(const Message& msg,bool morph);
92 
94  uint32_t size() const;
95 
96  void morph(const std::string& md5sum, const std::string& datatype_, const std::string& msg_def_);
97 
98 private:
99 
100  boost::flyweight<std::string> md5_;
101  boost::flyweight<std::string> datatype_;
102  boost::flyweight<std::string> msg_def_;
103  bool typed_;
104 
105  mutable std::vector<uint8_t> msgBuf_;
106 
107 };
108 
109 }
110 
111 
112 // Message traits allow shape shifter to work with the new serialization API
113 namespace ros {
114 namespace message_traits {
115 
116 template <> struct IsMessage<RosIntrospection::ShapeShifter> : TrueType { };
117 template <> struct IsMessage<const RosIntrospection::ShapeShifter> : TrueType { };
118 
119 template<>
120 struct MD5Sum<RosIntrospection::ShapeShifter>
121 {
122  static const char* value(const RosIntrospection::ShapeShifter& m) { return m.getMD5Sum().data(); }
123 
124  // Used statically, a ShapeShifter2 appears to be of any type
125  static const char* value() { return "*"; }
126 };
127 
128 template<>
129 struct DataType<RosIntrospection::ShapeShifter>
130 {
131  static const char* value(const RosIntrospection::ShapeShifter& m) { return m.getDataType().data(); }
132 
133  // Used statically, a ShapeShifter2 appears to be of any type
134  static const char* value() { return "*"; }
135 };
136 
137 template<>
138 struct Definition<RosIntrospection::ShapeShifter>
139 {
140  static const char* value(const RosIntrospection::ShapeShifter& m) { return m.getMessageDefinition().data(); }
141 };
142 
143 } // namespace message_traits
144 
145 
146 namespace serialization
147 {
148 
149 template<>
151 {
152  template<typename Stream>
153  inline static void write(Stream& stream, const RosIntrospection::ShapeShifter& m) {
154  m.write(stream);
155  }
156 
157  template<typename Stream>
158  inline static void read(Stream& stream, RosIntrospection::ShapeShifter& m)
159  {
160  m.read(stream);
161  }
162 
163  inline static uint32_t serializedLength(const RosIntrospection::ShapeShifter& m) {
164  return m.size();
165  }
166 };
167 
168 
169 template<>
171 {
173  {
174  std::string md5 = (*params.connection_header)["md5sum"];
175  std::string datatype = (*params.connection_header)["type"];
176  std::string msg_def = (*params.connection_header)["message_definition"];
177 
178  params.message->morph(md5, datatype, msg_def);
179  }
180 };
181 
182 } // namespace serialization
183 
184 } //namespace ros
185 
186 
187 
188 // Template implementations:
189 
190 namespace RosIntrospection
191 {
192 
193 template<class M> inline
194 void ShapeShifter::instantiate(M& destination) const
195 {
196  if (!typed_)
197  throw std::runtime_error("Tried to instantiate message from an untyped ShapeShifter2.");
198 
199  if (ros::message_traits::datatype<M>() != getDataType())
200  throw std::runtime_error("Tried to instantiate message without matching datatype.");
201 
202  if (ros::message_traits::md5sum<M>() != getMD5Sum())
203  throw std::runtime_error("Tried to instantiate message without matching md5sum.");
204 
205  ros::serialization::IStream s(msgBuf_.data(), msgBuf_.size() );
206  ros::serialization::deserialize(s, destination);
207 
208 }
209 
210 template<typename Stream> inline
211 void ShapeShifter::write(Stream& stream) const {
212  if (msgBuf_.size() > 0)
213  memcpy(stream.advance(msgBuf_.size()), msgBuf_.data(), msgBuf_.size());
214 }
215 
216 inline const uint8_t* ShapeShifter::raw_data() const {
217  return msgBuf_.data();
218 }
219 
220 inline uint32_t ShapeShifter::size() const
221 {
222  return msgBuf_.size();
223 }
224 
225 template<typename Stream> inline
226 void ShapeShifter::read(Stream& stream)
227 {
228  //allocate enough space
229  msgBuf_.resize( stream.getLength() );
230  //copy
231  memcpy(msgBuf_.data(), stream.getData(), stream.getLength());
232 }
233 
234 template<typename Message> inline
235 void ShapeShifter::direct_read(const Message& msg, bool do_morph)
236 {
237  if(do_morph)
238  {
239  this->morph(
243  }
244 
246 
247  //allocate enough space
248  msgBuf_.resize( length );
249  //copy
250  ros::serialization::OStream o_stream(msgBuf_.data(), length);
251  ros::serialization::serialize(o_stream, msg);
252 }
253 
255  : typed_(false),
256  msgBuf_()
257 {
258 }
259 
260 
262 {
263 
264 }
265 
266 
267 inline std::string const& ShapeShifter::getDataType() const { return datatype_; }
268 
269 
270 inline std::string const& ShapeShifter::getMD5Sum() const { return md5_; }
271 
272 
273 inline std::string const& ShapeShifter::getMessageDefinition() const { return msg_def_; }
274 
275 
276 inline void ShapeShifter::morph(const std::string& _md5sum, const std::string& _datatype, const std::string& _msg_def)
277 {
278  md5_ = _md5sum;
279  datatype_ = _datatype;
280  msg_def_ = _msg_def;
281  typed_ = (md5_ != "*");
282 }
283 
284 
285 inline ros::Publisher ShapeShifter::advertise(ros::NodeHandle& nh, const std::string& topic, uint32_t queue_size, bool latch,
286  const ros::SubscriberStatusCallback &connect_cb) const
287 {
288  ros::AdvertiseOptions opts(topic, queue_size, getMD5Sum(), getDataType(), getMessageDefinition(), connect_cb);
289  opts.latch = latch;
290  return nh.advertise(opts);
291 }
292 
293 } // namespace
294 
295 
296 #endif
297 
boost::flyweight< std::string > md5_
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)
boost::flyweight< std::string > datatype_
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
boost::flyweight< std::string > msg_def_
void deserialize(Stream &stream, T &t)
std::size_t length
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 Thu May 16 2019 02:39:09