Blob.h
Go to the documentation of this file.
1 //=================================================================================================
2 // Copyright (c) 2013, Johannes Meyer, TU Darmstadt
3 // All rights reserved.
4 
5 // Redistribution and use in source and binary forms, with or without
6 // modification, are permitted provided that the following conditions are met:
7 // * Redistributions of source code must retain the above copyright
8 // notice, this list of conditions and the following disclaimer.
9 // * Redistributions in binary form must reproduce the above copyright
10 // notice, this list of conditions and the following disclaimer in the
11 // documentation and/or other materials provided with the distribution.
12 // * Neither the name of the Flight Systems and Automatic Control group,
13 // TU Darmstadt, nor the names of its contributors may be used to
14 // endorse or promote products derived from this software without
15 // specific prior written permission.
16 
17 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
18 // ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
19 // WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
20 // DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER BE LIABLE FOR ANY
21 // DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
22 // (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
23 // LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
24 // ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
25 // (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
26 // SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
27 //=================================================================================================
28 
29 #ifndef BLOB_MESSAGE_BLOB_H
30 #define BLOB_MESSAGE_BLOB_H
31 
32 #include <ros/types.h>
33 #include <ros/serialization.h>
35 #include <ros/message_operations.h>
36 #include <ros/console.h>
37 
38 #include <boost/shared_ptr.hpp>
39 #include <vector>
40 
41 #include <blob/compression.h>
42 
43 namespace blob {
44 
45 class ShapeShifter;
46 
47 template <class ContainerAllocator>
48 struct Blob_
49 {
51  typedef uint8_t value_type;
52  typedef uint32_t size_type;
53 
54  typedef std::vector<value_type> Buffer;
57 
59  : compressed_(false)
60  {
61  clear();
62  }
63 
64  Blob_(const ContainerAllocator& _alloc)
65  : compressed_(false)
66  {
67  clear();
68  }
69 
70  Blob_(const void *data, size_type size, bool compressed = false)
71  : compressed_(compressed)
72  {
73  set(data, size);
74  }
75 
79 
80  // assign pointer, size and copy (if available)
82  {
83  clear();
84  pointer_ = other.pointer_;
85  size_ = other.size_;
86  copy_ = other.copy_;
87  return *this;
88  }
89 
90 public:
91  size_type size() const { return size_; }
92  const value_type *data() const { return pointer_; }
93  const value_type *begin() const { return pointer_; }
94  const value_type *end() const { return pointer_ + size_; }
95 
96  bool isCopy() const { return copy_; }
97  void setCompressed(bool compressed) { compressed_ = compressed; }
98  bool isCompressed() const { return compressed_; }
99 
100  void clear()
101  {
102  pointer_ = 0;
103  size_ = 0;
104  copy_.reset();
105  compressed_blob_.reset();
106  }
107 
108  bool empty() const
109  {
110  return (pointer_ == 0);
111  }
112 
113  void set(const void *data, size_type size)
114  {
115  clear();
116  pointer_ = reinterpret_cast<const value_type *>(data);
117  size_ = size;
118  }
119 
120  void set(ConstBufferPtr data)
121  {
122  clear();
123  copy_ = data;
124  pointer_ = data->data();
125  size_ = data->size();
126  }
127 
128  void copy()
129  {
130  if (copy_) return;
131  if (empty()) return;
132  BufferPtr copy(new Buffer(size()));
133  std::copy(begin(), end(), copy->data());
134  pointer_ = copy->data();
135  copy_ = copy;
136  }
137 
138  void copy(const value_type *data, size_type size)
139  {
140  set(data, size);
141  copy();
142  }
143 
144  ConstBufferPtr getCopy()
145  {
146  copy();
147  return copy_;
148  }
149 
150  /* ROS serialization */
151 
152  template<typename Stream>
153  void write(Stream& stream) const
154  {
155  ROS_DEBUG_NAMED("blob", "Writing a blob of size %u at address %p to the stream", size(), data());
156 
157  if (!empty() && isCompressed()) {
158  if (compress()) {
159  ROS_DEBUG_NAMED("blob", "Using compression. Compressed size %u bytes (%.1f%%)", static_cast<uint32_t>(compressed_blob_->size()), 100.0 * (1.0 - static_cast<float>(compressed_blob_->size()) / static_cast<float>(size())));
160  stream.next(static_cast<uint8_t>(true));
161  stream.next(static_cast<uint32_t>(compressed_blob_->size()));
162  std::copy(compressed_blob_->begin(), compressed_blob_->end(), stream.advance(compressed_blob_->size()));
163  return;
164  }
165  }
166 
167  stream.next(static_cast<uint8_t>(false));
168  stream.next(static_cast<uint32_t>(size()));
169  std::copy(begin(), end(), stream.advance(size()));
170  }
171 
172  template<typename Stream>
173  void read(Stream& stream)
174  {
175  uint8_t is_compressed;
176  uint32_t size;
177  stream.next(is_compressed);
178  stream.next(size);
179  ROS_DEBUG_NAMED("blob", "Reading %s blob of size %u at address %p from the stream", std::string(is_compressed ? "a compressed" : "an uncompressed").c_str(), size, stream.getData());
180 
181  if (is_compressed) {
182  if (!decompress(stream.advance(size), size)) {
183  throw ros::serialization::StreamOverrunException("Decompression error");
184  }
185  return;
186  }
187 
188  // ros::MessageDeserializer::deserialize frees the original buffer of the SerializedMessage
189  // We have to create a copy.
190  // set(stream.advance(size), size);
191  copy(stream.advance(size), size);
192  }
193 
194  uint32_t serializedLength() const
195  {
197 
198  if (!empty() && isCompressed()) {
199  if (compress()) {
200  return length + compressed_blob_->size();
201  }
202  }
203 
204  return length + size();
205  }
206 
207  /* Instantiation and Serialization */
208 
209  template <typename M>
211  if (empty()) return boost::shared_ptr<M>();
213  ros::serialization::IStream stream(const_cast<uint8_t *>(reinterpret_cast<const uint8_t *>(data())), size());
215  return m;
216  }
217 
218  template <typename M>
219  void serialize(const M& message) {
220  clear();
221  BufferPtr buffer(new Buffer(ros::serialization::serializationLength(message)));
222  ros::serialization::OStream stream(reinterpret_cast<uint8_t *>(buffer->data()), buffer->size());
223  ros::serialization::serialize(stream, message);
224  set(buffer);
225  }
226 
227  // implemented in shape_shifter.h
228  ShapeShifter asMessage() const;
229 
230  /* Compression */
231 
232  ConstBufferPtr getCompressedBlob() const {
233  compress();
234  return compressed_blob_;
235  }
236 
237  bool setFromCompressedData(const void *data, uint32_t size) {
238  return decompress(reinterpret_cast<const uint8_t *>(data), size);
239  }
240 
241 private:
242  // compress blob into compressed_blob_
243  bool compress() const
244  {
245  if (!compressed_blob_) {
246  BufferPtr temp(new Buffer());
247 
248  if (!::blob::deflate(data(), size(), *temp)) {
249  ROS_WARN_NAMED("blob", "Error during compression of a blob of size %u", size());
250  return false;
251  }
252 
253  compressed_blob_ = temp;
254  }
255 
256  return (compressed_blob_->size() < size());
257  }
258 
259  // decompress compressed_blob_ into copy_
260  bool decompress(const uint8_t *data, uint32_t size)
261  {
262  clear();
263  BufferPtr temp(new Buffer());
264 
265  if (!::blob::inflate(data, size, *temp)) {
266  ROS_WARN_NAMED("blob", "Error during decompression of a blob of size %u", size);
267  return false;
268  }
269 
270  set(temp);
271  return true;
272  }
273 
274 private:
276  const value_type *pointer_;
277  size_type size_;
278 
279  ConstBufferPtr copy_;
280  mutable ConstBufferPtr compressed_blob_;
281 }; // struct Blob_
282 
283 typedef ::blob::Blob_<std::allocator<void> > Blob;
286 
287 template<typename ContainerAllocator>
288 std::ostream& operator<<(std::ostream& s, const ::blob::Blob_<ContainerAllocator> & v)
289 {
291  return s;
292 }
293 
294 } // namespace blob
295 
296 namespace ros
297 {
298 namespace message_traits
299 {
300 
301 template <class ContainerAllocator>
302 struct IsFixedSize< ::blob::Blob_<ContainerAllocator> >
303  : FalseType
304  { };
305 
306 template <class ContainerAllocator>
307 struct IsFixedSize< ::blob::Blob_<ContainerAllocator> const>
308  : FalseType
309  { };
310 
311 template <class ContainerAllocator>
312 struct IsMessage< ::blob::Blob_<ContainerAllocator> >
313  : TrueType
314  { };
315 
316 template <class ContainerAllocator>
317 struct IsMessage< ::blob::Blob_<ContainerAllocator> const>
318  : TrueType
319  { };
320 
321 template <class ContainerAllocator>
322 struct HasHeader< ::blob::Blob_<ContainerAllocator> >
323  : FalseType
324  { };
325 
326 template <class ContainerAllocator>
327 struct HasHeader< ::blob::Blob_<ContainerAllocator> const>
328  : FalseType
329  { };
330 
331 
332 template<class ContainerAllocator>
333 struct MD5Sum< ::blob::Blob_<ContainerAllocator> >
334 {
335  static const char* value()
336  {
337  return "8115c3ed9d7b2e23c47c6ecaff2d4b13";
338  }
339 
340  static const char* value(const ::blob::Blob_<ContainerAllocator>&) { return value(); }
341  static const uint64_t static_value1 = 0x8115c3ed9d7b2e23ULL;
342  static const uint64_t static_value2 = 0xc47c6ecaff2d4b13ULL;
343 };
344 
345 template<class ContainerAllocator>
346 struct DataType< ::blob::Blob_<ContainerAllocator> >
347 {
348  static const char* value()
349  {
350  return "blob/Blob";
351  }
352 
353  static const char* value(const ::blob::Blob_<ContainerAllocator>&) { return value(); }
354 };
355 
356 template<class ContainerAllocator>
357 struct Definition< ::blob::Blob_<ContainerAllocator> >
358 {
359  static const char* value()
360  {
361  return "bool compressed\n\
362 uint8[] data\n\
363 \n\
364 ";
365  }
366 
367  static const char* value(const ::blob::Blob_<ContainerAllocator>&) { return value(); }
368 };
369 
370 } // namespace message_traits
371 } // namespace ros
372 
373 
374 namespace ros
375 {
376 namespace serialization
377 {
378 
379  template<class ContainerAllocator> struct Serializer< ::blob::Blob_<ContainerAllocator> >
380  {
381  template<typename Stream, typename T>
382  inline static void write(Stream& stream, const T& t)
383  {
384  t.write(stream);
385  }
386 
387  template<typename Stream, typename T>
388  inline static void read(Stream& stream, T& t)
389  {
390  t.read(stream);
391  }
392 
393  template<typename T>
394  inline static uint32_t serializedLength(const T& t)
395  {
396  return t.serializedLength();
397  }
398  }; // struct Blob_
399 
400 } // namespace serialization
401 } // namespace ros
402 
403 namespace ros
404 {
405 namespace message_operations
406 {
407 
408 template<class ContainerAllocator>
409 struct Printer< ::blob::Blob_<ContainerAllocator> >
410 {
411  template<typename Stream> static void stream(Stream& s, const std::string& indent, const ::blob::Blob_<ContainerAllocator>& v)
412  {
413  s << indent << "(blob)";
414  }
415 };
416 
417 } // namespace message_operations
418 } // namespace ros
419 
420 #endif // BLOB_MESSAGE_BLOB_H
Blob_()
Definition: Blob.h:58
static void stream(Stream &s, const std::string &indent, const ::blob::Blob_< ContainerAllocator > &v)
Definition: Blob.h:411
boost::shared_ptr< const Buffer > ConstBufferPtr
Definition: Blob.h:56
boost::shared_ptr< std::map< std::string, std::string > > __connection_header
Definition: Blob.h:78
#define ROS_WARN_NAMED(name,...)
void clear()
Definition: Blob.h:100
void read(Stream &stream)
Definition: Blob.h:173
boost::shared_ptr< ::blob::Blob > BlobPtr
Definition: Blob.h:284
boost::shared_ptr< ::blob::Blob_< ContainerAllocator > > Ptr
Definition: Blob.h:76
bool setFromCompressedData(const void *data, uint32_t size)
Definition: Blob.h:237
XmlRpcServer s
Blob_(const void *data, size_type size, bool compressed=false)
Definition: Blob.h:70
bool empty() const
Definition: Blob.h:108
void copy()
Definition: Blob.h:128
void setCompressed(bool compressed)
Definition: Blob.h:97
static const char * value(const ::blob::Blob_< ContainerAllocator > &)
Definition: Blob.h:340
const value_type * pointer_
Definition: Blob.h:276
size_type size_
Definition: Blob.h:277
bool compressed_
Definition: Blob.h:275
bool compress() const
Definition: Blob.h:243
std::vector< value_type > Buffer
Definition: Blob.h:54
boost::shared_ptr< M > instantiate() const
Definition: Blob.h:210
uint32_t serializedLength() const
Definition: Blob.h:194
static const char * value(const ::blob::Blob_< ContainerAllocator > &)
Definition: Blob.h:367
#define ROS_DEBUG_NAMED(name,...)
boost::shared_ptr< ::blob::Blob const > BlobConstPtr
Definition: Blob.h:285
void write(Stream &stream) const
Definition: Blob.h:153
Blob_(const ContainerAllocator &_alloc)
Definition: Blob.h:64
const value_type * data() const
Definition: Blob.h:92
void copy(const value_type *data, size_type size)
Definition: Blob.h:138
void serialize(const M &message)
Definition: Blob.h:219
void serialize(Stream &stream, const T &t)
const value_type * end() const
Definition: Blob.h:94
bool isCompressed() const
Definition: Blob.h:98
size_type size() const
Definition: Blob.h:91
bool isCopy() const
Definition: Blob.h:96
Blob_< ContainerAllocator > Type
Definition: Blob.h:50
boost::shared_ptr< Buffer > BufferPtr
Definition: Blob.h:55
ConstBufferPtr compressed_blob_
Definition: Blob.h:280
bool inflate(const uint8_t *data, uint32_t size, std::vector< uint8_t > &inflated)
Definition: compression.cpp:93
Definition: Blob.h:43
const value_type * begin() const
Definition: Blob.h:93
uint32_t size_type
Definition: Blob.h:52
ConstBufferPtr getCompressedBlob() const
Definition: Blob.h:232
uint32_t serializationLength(const T &t)
bool deflate(const uint8_t *data, uint32_t size, std::vector< uint8_t > &deflated)
Definition: compression.cpp:46
static const char * value(const ::blob::Blob_< ContainerAllocator > &)
Definition: Blob.h:353
bool decompress(const uint8_t *data, uint32_t size)
Definition: Blob.h:260
ShapeShifter asMessage() const
Definition: shape_shifter.h:96
ConstBufferPtr copy_
Definition: Blob.h:279
ConstBufferPtr getCopy()
Definition: Blob.h:144
void deserialize(Stream &stream, T &t)
::blob::Blob_< std::allocator< void > > Blob
Definition: Blob.h:283
Blob_< ContainerAllocator > & operator=(const Blob_< ContainerAllocator > &other)
Definition: Blob.h:81
uint8_t value_type
Definition: Blob.h:51
boost::shared_ptr< ::blob::Blob_< ContainerAllocator > const > ConstPtr
Definition: Blob.h:77


blob
Author(s): Johannes Meyer
autogenerated on Sat Jul 27 2019 03:35:24