third-party/realsense-file/rosbag/rosbag_storage/include/rosbag/stream.h
Go to the documentation of this file.
1 /*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2008, 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 ROSBAG_STREAM_H
36 #define ROSBAG_STREAM_H
37 
38 #include <ios>
39 #include <stdint.h>
40 #include <string>
41 
42 //#include <boost/shared_ptr.hpp>
43 #include <memory>
44 #include "../../../roslz4/include/roslz4/lz4s.h"
45 
46 #include "../../../rosbag_storage/include/rosbag/exceptions.h"
47 #include "../../../rosbag_storage/include/rosbag/macros.h"
48 
49 namespace rosbag {
50 
51 namespace compression
52 {
54  {
56  BZ2 = 1,
57  LZ4 = 2,
58  };
59 }
61 
62 class ChunkedFile;
63 
65 {
66 public:
67  Stream(ChunkedFile* file);
68  virtual ~Stream();
69 
70  virtual CompressionType getCompressionType() const = 0;
71 
72  virtual void write(void* ptr, size_t size) = 0;
73  virtual void read (void* ptr, size_t size) = 0;
74 
75  virtual void decompress(uint8_t* dest, unsigned int dest_len, uint8_t* source, unsigned int source_len) = 0;
76 
77  virtual void startWrite();
78  virtual void stopWrite();
79 
80  virtual void startRead();
81  virtual void stopRead();
82 
83 protected:
84  FILE* getFilePointer();
85  uint64_t getCompressedIn();
86  void setCompressedIn(uint64_t nbytes);
87  void advanceOffset(uint64_t nbytes);
88  char* getUnused();
89  int getUnusedLength();
90  void setUnused(char* unused);
91  void setUnusedLength(int nUnused);
92  void clearUnused();
93 
94 protected:
96 };
97 
99 {
100 public:
101  StreamFactory(ChunkedFile* file);
102 
103  std::shared_ptr<Stream> getStream(CompressionType type) const;
104 
105 private:
106  std::shared_ptr<Stream> uncompressed_stream_;
107  std::shared_ptr<Stream> lz4_stream_;
108 };
109 
111 {
112 public:
114 
115  CompressionType getCompressionType() const;
116 
117  void write(void* ptr, size_t size);
118  void read(void* ptr, size_t size);
119 
120  void decompress(uint8_t* dest, unsigned int dest_len, uint8_t* source, unsigned int source_len);
121 };
122 
123 // LZ4Stream reads/writes compressed datat in the LZ4 format
124 // https://code.google.com/p/lz4/
126 {
127 public:
128  LZ4Stream(ChunkedFile* file);
129  ~LZ4Stream();
130 
131  CompressionType getCompressionType() const;
132 
133  void startWrite();
134  void write(void* ptr, size_t size);
135  void stopWrite();
136 
137  void startRead();
138  void read(void* ptr, size_t size);
139  void stopRead();
140 
141  void decompress(uint8_t* dest, unsigned int dest_len, uint8_t* source, unsigned int source_len);
142 
143 private:
144  void writeStream(int action);
145 
146  char *buff_;
150 };
151 
152 
153 
154 } // namespace rosbag
155 
156 #endif
ChunkedFile reads and writes files which contain interleaved chunks of compressed and uncompressed da...
Definition: chunked_file.h:49
unsigned char uint8_t
Definition: stdint.h:78
GLsizeiptr size
unsigned __int64 uint64_t
Definition: stdint.h:90
action
Definition: enums.py:62
Definition: bag.h:66
GLenum type
GLsizei GLsizei GLchar * source
LZ4LIB_API char * dest
Definition: lz4.h:438
#define ROSBAG_DECL
#include <ros/macros.h> // for the DECL&#39;s


librealsense2
Author(s): Sergey Dorodnicov , Doron Hirshberg , Mark Horn , Reagan Lopez , Itay Carpis
autogenerated on Mon May 3 2021 02:50:11