Blob.h
Go to the documentation of this file.
00001 //=================================================================================================
00002 // Copyright (c) 2013, Johannes Meyer, TU Darmstadt
00003 // All rights reserved.
00004 
00005 // Redistribution and use in source and binary forms, with or without
00006 // modification, are permitted provided that the following conditions are met:
00007 //     * Redistributions of source code must retain the above copyright
00008 //       notice, this list of conditions and the following disclaimer.
00009 //     * Redistributions in binary form must reproduce the above copyright
00010 //       notice, this list of conditions and the following disclaimer in the
00011 //       documentation and/or other materials provided with the distribution.
00012 //     * Neither the name of the Flight Systems and Automatic Control group,
00013 //       TU Darmstadt, nor the names of its contributors may be used to
00014 //       endorse or promote products derived from this software without
00015 //       specific prior written permission.
00016 
00017 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
00018 // ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
00019 // WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
00020 // DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER BE LIABLE FOR ANY
00021 // DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
00022 // (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00023 // LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
00024 // ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
00025 // (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
00026 // SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
00027 //=================================================================================================
00028 
00029 #ifndef BLOB_MESSAGE_BLOB_H
00030 #define BLOB_MESSAGE_BLOB_H
00031 
00032 #include <ros/types.h>
00033 #include <ros/serialization.h>
00034 #include <ros/builtin_message_traits.h>
00035 #include <ros/message_operations.h>
00036 #include <ros/console.h>
00037 
00038 #include <boost/shared_ptr.hpp>
00039 #include <vector>
00040 
00041 #include <blob/compression.h>
00042 
00043 namespace blob {
00044 
00045 class ShapeShifter;
00046 
00047 template <class ContainerAllocator>
00048 struct Blob_
00049 {
00050   typedef Blob_<ContainerAllocator> Type;
00051   typedef uint8_t value_type;
00052   typedef uint32_t size_type;
00053 
00054   typedef std::vector<value_type> Buffer;
00055   typedef boost::shared_ptr<Buffer> BufferPtr;
00056   typedef boost::shared_ptr<const Buffer> ConstBufferPtr;
00057 
00058   Blob_()
00059     : compressed_(false)
00060   {
00061     clear();
00062   }
00063 
00064   Blob_(const ContainerAllocator& _alloc)
00065     : compressed_(false)
00066   {
00067     clear();
00068   }
00069 
00070   Blob_(const void *data, size_type size, bool compressed = false)
00071     : compressed_(compressed)
00072   {
00073     set(data, size);
00074   }
00075 
00076   typedef boost::shared_ptr< ::blob::Blob_<ContainerAllocator> > Ptr;
00077   typedef boost::shared_ptr< ::blob::Blob_<ContainerAllocator> const> ConstPtr;
00078   boost::shared_ptr<std::map<std::string, std::string> > __connection_header;
00079 
00080   // assign pointer, size and copy (if available)
00081   Blob_<ContainerAllocator>& operator=(const Blob_<ContainerAllocator>& other)
00082   {
00083     clear();
00084     pointer_ = other.pointer_;
00085     size_ = other.size_;
00086     copy_ = other.copy_;
00087     return *this;
00088   }
00089 
00090 public:
00091   size_type size()          const { return size_; }
00092   const value_type *data()  const { return pointer_; }
00093   const value_type *begin() const { return pointer_; }
00094   const value_type *end()   const { return pointer_ + size_; }
00095 
00096   bool isCopy() const { return copy_; }
00097   void setCompressed(bool compressed) { compressed_ = compressed; }
00098   bool isCompressed() const { return compressed_; }
00099 
00100   void clear()
00101   {
00102     pointer_ = 0;
00103     size_ = 0;
00104     copy_.reset();
00105     compressed_blob_.reset();
00106   }
00107 
00108   bool empty() const
00109   {
00110     return (pointer_ == 0);
00111   }
00112 
00113   void set(const void *data, size_type size)
00114   {
00115     clear();
00116     pointer_ = reinterpret_cast<const value_type *>(data);
00117     size_ = size;
00118   }
00119 
00120   void set(ConstBufferPtr data)
00121   {
00122     clear();
00123     copy_ = data;
00124     pointer_ = data->data();
00125     size_ = data->size();
00126   }
00127 
00128   void copy()
00129   {
00130     if (copy_) return;
00131     if (empty()) return;
00132     BufferPtr copy(new Buffer(size()));
00133     std::copy(begin(), end(), copy->data());
00134     pointer_ = copy->data();
00135     copy_ = copy;
00136   }
00137 
00138   void copy(const value_type *data, size_type size)
00139   {
00140     set(data, size);
00141     copy();
00142   }
00143 
00144   ConstBufferPtr getCopy()
00145   {
00146     copy();
00147     return copy_;
00148   }
00149 
00150   /* ROS serialization */
00151 
00152   template<typename Stream>
00153   void write(Stream& stream) const
00154   {
00155     ROS_DEBUG_NAMED("blob", "Writing a blob of size %u at address %p to the stream", size(), data());
00156 
00157     if (!empty() && isCompressed()) {
00158       if (compress()) {
00159         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())));
00160         stream.next(true);
00161         stream.next(static_cast<uint32_t>(compressed_blob_->size()));
00162         std::copy(compressed_blob_->begin(), compressed_blob_->end(), stream.advance(compressed_blob_->size()));
00163         return;
00164       }
00165     }
00166 
00167     stream.next(false);
00168     stream.next(static_cast<uint32_t>(size()));
00169     std::copy(begin(), end(), stream.advance(size()));
00170   }
00171 
00172   template<typename Stream>
00173   void read(Stream& stream)
00174   {
00175     bool is_compressed;
00176     uint32_t size;
00177     stream.next(is_compressed);
00178     stream.next(size);
00179     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());
00180 
00181     if (is_compressed) {
00182       if (!decompress(stream.advance(size), size)) {
00183         throw ros::serialization::StreamOverrunException("Decompression error");
00184       }
00185       return;
00186     }
00187 
00188     // ros::MessageDeserializer::deserialize frees the original buffer of the SerializedMessage
00189     // We have to create a copy.
00190     // set(stream.advance(size), size);
00191     copy(stream.advance(size), size);
00192   }
00193 
00194   uint32_t serializedLength() const
00195   {
00196     uint32_t length = ros::serialization::serializationLength(true) + ros::serialization::serializationLength(size());
00197 
00198     if (!empty() && isCompressed()) {
00199       if (compress()) {
00200         return length + compressed_blob_->size();
00201       }
00202     }
00203 
00204     return length + size();
00205   }
00206 
00207   /* Instantiation and Serialization */
00208 
00209   template <typename M>
00210   boost::shared_ptr<M> instantiate() const {
00211     if (empty()) return boost::shared_ptr<M>();
00212     boost::shared_ptr<typename boost::remove_const<M>::type> m(new M());
00213     ros::serialization::IStream stream(const_cast<uint8_t *>(reinterpret_cast<const uint8_t *>(data())), size());
00214     ros::serialization::deserialize(stream, *m);
00215     return m;
00216   }
00217 
00218   template <typename M>
00219   void serialize(const M& message) {
00220     clear();
00221     BufferPtr buffer(new Buffer(ros::serialization::serializationLength(message)));
00222     ros::serialization::OStream stream(reinterpret_cast<uint8_t *>(buffer->data()), buffer->size());
00223     ros::serialization::serialize(stream, message);
00224     set(buffer);
00225   }
00226 
00227   // implemented in shape_shifter.h
00228   ShapeShifter asMessage() const;
00229 
00230   /* Compression */
00231 
00232   ConstBufferPtr getCompressedBlob() const {
00233     compress();
00234     return compressed_blob_;
00235   }
00236 
00237   bool setFromCompressedData(const void *data, uint32_t size) {
00238     return decompress(reinterpret_cast<const uint8_t *>(data), size);
00239   }
00240 
00241 private:
00242   // compress blob into compressed_blob_
00243   bool compress() const
00244   {
00245     if (!compressed_blob_) {
00246       BufferPtr temp(new Buffer());
00247 
00248       if (!::blob::deflate(data(), size(), *temp)) {
00249         ROS_WARN_NAMED("blob", "Error during compression of a blob of size %u", size());
00250         return false;
00251       }
00252 
00253       compressed_blob_ = temp;
00254     }
00255 
00256     return (compressed_blob_->size() < size());
00257   }
00258 
00259   // decompress compressed_blob_ into copy_
00260   bool decompress(const uint8_t *data, uint32_t size)
00261   {
00262     clear();
00263     BufferPtr temp(new Buffer());
00264 
00265     if (!::blob::inflate(data, size, *temp)) {
00266       ROS_WARN_NAMED("blob", "Error during decompression of a blob of size %u", size);
00267       return false;
00268     }
00269 
00270     set(temp);
00271     return true;
00272   }
00273 
00274 private:
00275   bool compressed_;
00276   const value_type *pointer_;
00277   size_type size_;
00278 
00279   ConstBufferPtr copy_;
00280   mutable ConstBufferPtr compressed_blob_;
00281 }; // struct Blob_
00282 
00283 typedef ::blob::Blob_<std::allocator<void> > Blob;
00284 typedef boost::shared_ptr< ::blob::Blob > BlobPtr;
00285 typedef boost::shared_ptr< ::blob::Blob const> BlobConstPtr;
00286 
00287 template<typename ContainerAllocator>
00288 std::ostream& operator<<(std::ostream& s, const ::blob::Blob_<ContainerAllocator> & v)
00289 {
00290   ros::message_operations::Printer< ::blob::Blob_<ContainerAllocator> >::stream(s, "", v);
00291   return s;
00292 }
00293 
00294 } // namespace blob
00295 
00296 namespace ros
00297 {
00298 namespace message_traits
00299 {
00300 
00301 template <class ContainerAllocator>
00302 struct IsFixedSize< ::blob::Blob_<ContainerAllocator> >
00303   : FalseType
00304   { };
00305 
00306 template <class ContainerAllocator>
00307 struct IsFixedSize< ::blob::Blob_<ContainerAllocator> const>
00308   : FalseType
00309   { };
00310 
00311 template <class ContainerAllocator>
00312 struct IsMessage< ::blob::Blob_<ContainerAllocator> >
00313   : TrueType
00314   { };
00315 
00316 template <class ContainerAllocator>
00317 struct IsMessage< ::blob::Blob_<ContainerAllocator> const>
00318   : TrueType
00319   { };
00320 
00321 template <class ContainerAllocator>
00322 struct HasHeader< ::blob::Blob_<ContainerAllocator> >
00323   : FalseType
00324   { };
00325 
00326 template <class ContainerAllocator>
00327 struct HasHeader< ::blob::Blob_<ContainerAllocator> const>
00328   : FalseType
00329   { };
00330 
00331 
00332 template<class ContainerAllocator>
00333 struct MD5Sum< ::blob::Blob_<ContainerAllocator> >
00334 {
00335   static const char* value()
00336   {
00337     return "8115c3ed9d7b2e23c47c6ecaff2d4b13";
00338   }
00339 
00340   static const char* value(const ::blob::Blob_<ContainerAllocator>&) { return value(); }
00341   static const uint64_t static_value1 = 0x8115c3ed9d7b2e23ULL;
00342   static const uint64_t static_value2 = 0xc47c6ecaff2d4b13ULL;
00343 };
00344 
00345 template<class ContainerAllocator>
00346 struct DataType< ::blob::Blob_<ContainerAllocator> >
00347 {
00348   static const char* value()
00349   {
00350     return "blob/Blob";
00351   }
00352 
00353   static const char* value(const ::blob::Blob_<ContainerAllocator>&) { return value(); }
00354 };
00355 
00356 template<class ContainerAllocator>
00357 struct Definition< ::blob::Blob_<ContainerAllocator> >
00358 {
00359   static const char* value()
00360   {
00361     return "bool compressed\n\
00362 uint8[] data\n\
00363 \n\
00364 ";
00365   }
00366 
00367   static const char* value(const ::blob::Blob_<ContainerAllocator>&) { return value(); }
00368 };
00369 
00370 } // namespace message_traits
00371 } // namespace ros
00372 
00373 
00374 namespace ros
00375 {
00376 namespace serialization
00377 {
00378 
00379   template<class ContainerAllocator> struct Serializer< ::blob::Blob_<ContainerAllocator> >
00380   {
00381     template<typename Stream, typename T>
00382     inline static void write(Stream& stream, const T& t)
00383     {
00384       t.write(stream);
00385     }
00386 
00387     template<typename Stream, typename T>
00388     inline static void read(Stream& stream, T& t)
00389     {
00390       t.read(stream);
00391     }
00392 
00393     template<typename T>
00394     inline static uint32_t serializedLength(const T& t)
00395     {
00396       return t.serializedLength();
00397     }
00398   }; // struct Blob_
00399 
00400 } // namespace serialization
00401 } // namespace ros
00402 
00403 namespace ros
00404 {
00405 namespace message_operations
00406 {
00407 
00408 template<class ContainerAllocator>
00409 struct Printer< ::blob::Blob_<ContainerAllocator> >
00410 {
00411   template<typename Stream> static void stream(Stream& s, const std::string& indent, const ::blob::Blob_<ContainerAllocator>& v)
00412   {
00413     s << indent << "(blob)";
00414   }
00415 };
00416 
00417 } // namespace message_operations
00418 } // namespace ros
00419 
00420 #endif // BLOB_MESSAGE_BLOB_H


blob
Author(s): Johannes Meyer
autogenerated on Mon Oct 6 2014 07:55:44