chunked_file.cpp
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 #include "rosbag/chunked_file.h"
36 
37 #include <iostream>
38 
39 #include <boost/format.hpp>
40 #include <boost/make_shared.hpp>
41 
42 //#include <ros/ros.h>
43 #ifdef _WIN32
44 # ifdef __MINGW32__
45 # define fseeko fseeko64
46 # define ftello ftello64
47 // not sure if we need a ftruncate here yet or not
48 # else
49 # include <io.h>
50 # define fseeko _fseeki64
51 # define ftello _ftelli64
52 # define fileno _fileno
53 # define ftruncate _chsize
54 # endif
55 #endif
56 
57 using std::string;
58 using boost::format;
59 using boost::shared_ptr;
60 using ros::Exception;
61 
62 namespace rosbag {
63 
65  file_(NULL),
66  offset_(0),
67  compressed_in_(0),
68  unused_(NULL),
69  nUnused_(0)
70 {
71  stream_factory_ = boost::make_shared<StreamFactory>(this);
72 }
73 
75  close();
76 }
77 
78 void ChunkedFile::openReadWrite(string const& filename) { open(filename, "r+b"); }
79 void ChunkedFile::openWrite (string const& filename) { open(filename, "w+b"); }
80 void ChunkedFile::openRead (string const& filename) { open(filename, "rb"); }
81 
82 void ChunkedFile::open(string const& filename, string const& mode) {
83  // Check if file is already open
84  if (file_)
85  throw BagIOException((format("File already open: %1%") % filename_.c_str()).str());
86 
87  // Open the file
88  if (mode == "r+b") {
89  // check if file already exists
90  #if defined(_MSC_VER) && (_MSC_VER >= 1400 )
91  fopen_s( &file_, filename.c_str(), "r" );
92  #else
93  file_ = fopen(filename.c_str(), "r");
94  #endif
95  if (file_ == NULL)
96  // create an empty file and open it for update
97  #if defined(_MSC_VER) && (_MSC_VER >= 1400 )
98  fopen_s( &file_, filename.c_str(), "w+b" );
99  #else
100  file_ = fopen(filename.c_str(), "w+b");
101  #endif
102  else {
103  if (fclose(file_) != 0)
104  throw BagIOException((format("Error closing file: %1%") % filename.c_str()).str());
105 
106  // open existing file for update
107  #if defined(_MSC_VER) && (_MSC_VER >= 1400 )
108  fopen_s( &file_, filename.c_str(), "r+b" );
109  #else
110  file_ = fopen(filename.c_str(), "r+b");
111  #endif
112  }
113  }
114  else
115  #if defined(_MSC_VER) && (_MSC_VER >= 1400 )
116  fopen_s( &file_, filename.c_str(), mode.c_str() );
117  #else
118  file_ = fopen(filename.c_str(), mode.c_str());
119  #endif
120 
121  if (!file_)
122  throw BagIOException((format("Error opening file: %1%") % filename.c_str()).str());
123 
124  read_stream_ = boost::make_shared<UncompressedStream>(this);
125  write_stream_ = boost::make_shared<UncompressedStream>(this);
126  filename_ = filename;
127  offset_ = ftello(file_);
128 }
129 
130 bool ChunkedFile::good() const {
131  return feof(file_) == 0 && ferror(file_) == 0;
132 }
133 
134 bool ChunkedFile::isOpen() const { return file_ != NULL; }
135 string ChunkedFile::getFileName() const { return filename_; }
136 
138  if (!file_)
139  return;
140 
141  // Close any compressed stream by changing to uncompressed mode
143 
144  // Close the file
145  int success = fclose(file_);
146  if (success != 0)
147  throw BagIOException((format("Error closing file: %1%") % filename_.c_str()).str());
148 
149  file_ = NULL;
150  filename_.clear();
151 
152  clearUnused();
153  offset_ = 0;
154  compressed_in_ = 0;
155 }
156 
157 // Read/write modes
158 
160  if (!file_)
161  throw BagIOException("Can't set compression mode before opening a file");
162 
163  if (type != write_stream_->getCompressionType()) {
164  write_stream_->stopWrite();
165  shared_ptr<Stream> stream = stream_factory_->getStream(type);
166  stream->startWrite();
167  write_stream_ = stream;
168  }
169 }
170 
172  if (!file_)
173  throw BagIOException("Can't set compression mode before opening a file");
174 
175  if (type != read_stream_->getCompressionType()) {
176  read_stream_->stopRead();
177  shared_ptr<Stream> stream = stream_factory_->getStream(type);
178  stream->startRead();
179  read_stream_ = stream;
180  }
181 }
182 
183 void ChunkedFile::seek(uint64_t offset, int origin) {
184  if (!file_)
185  throw BagIOException("Can't seek - file not open");
186 
188 
189  int success = fseeko(file_, offset, origin);
190  if (success != 0)
191  throw BagIOException("Error seeking");
192 
193  offset_ = ftello(file_);
194 }
195 
196 uint64_t ChunkedFile::getOffset() const { return offset_; }
198 
199 void ChunkedFile::write(string const& s) { write((void*) s.c_str(), s.size()); }
200 void ChunkedFile::write(void* ptr, size_t size) { write_stream_->write(ptr, size); }
201 void ChunkedFile::read(void* ptr, size_t size) { read_stream_->read(ptr, size); }
202 
203 bool ChunkedFile::truncate(uint64_t length) {
204  int fd = fileno(file_);
205  return ftruncate(fd, length) == 0;
206 }
207 
210  char buffer[1024];
211  if(fgets(buffer, 1024, file_))
212  {
213  string s(buffer);
214  offset_ += s.size();
215  return s;
216  }
217  else
218  return string("");
219 }
220 
221 void ChunkedFile::decompress(CompressionType compression, uint8_t* dest, unsigned int dest_len, uint8_t* source, unsigned int source_len) {
222  stream_factory_->getStream(compression)->decompress(dest, dest_len, source, source_len);
223 }
224 
226  unused_ = NULL;
227  nUnused_ = 0;
228 }
229 
231  using std::swap;
232  using boost::swap;
233  swap(filename_, other.filename_);
234  swap(file_, other.file_);
235  swap(offset_, other.offset_);
237  swap(unused_, other.unused_);
238  swap(nUnused_, other.nUnused_);
239 
241 
245 
247  FileAccessor::setFile(*other.stream_factory_->getStream(compression::BZ2), &other);
248  FileAccessor::setFile(*other.stream_factory_->getStream(compression::LZ4), &other);
249 
252  FileAccessor::setFile(*other.read_stream_, &other);
253 
256  FileAccessor::setFile(*other.write_stream_, &other);
257 }
258 
259 } // namespace rosbag
void openRead(std::string const &filename)
open file for reading
void setReadMode(CompressionType type)
void read(void *ptr, size_t size)
read size bytes from the file into ptr
void open(std::string const &filename, std::string const &mode)
bool isOpen() const
return true if file is open for reading or writing
ChunkedFile reads and writes files which contain interleaved chunks of compressed and uncompressed da...
Definition: chunked_file.h:51
void write(std::string const &s)
XmlRpcServer s
bool truncate(uint64_t length)
void seek(uint64_t offset, int origin=std::ios_base::beg)
seek to given offset from origin
void close()
close the file
bool good() const
return true if hasn&#39;t reached end-of-file and no error
void swap(Bag &a, Bag &b)
Definition: bag.h:674
std::string getFileName() const
return path of currently open file
void swap(ChunkedFile &other)
uint64_t offset_
current position in the file
Definition: chunked_file.h:94
uint64_t getOffset() const
return current offset from the beginning of the file
void setWriteMode(CompressionType type)
uint32_t getCompressedBytesIn() const
return the number of bytes written to current compressed stream
int nUnused_
number of bytes of extra data read by compressed stream
Definition: chunked_file.h:97
Exception thrown when on IO problems.
Definition: exceptions.h:50
std::string getline()
boost::shared_ptr< StreamFactory > stream_factory_
Definition: chunked_file.h:99
boost::shared_ptr< Stream > write_stream_
Definition: chunked_file.h:102
static void setFile(Stream &a, ChunkedFile *file)
Definition: stream.h:118
uint64_t compressed_in_
number of bytes written to current compressed stream
Definition: chunked_file.h:95
std::string filename_
path to file
Definition: chunked_file.h:92
void openWrite(std::string const &filename)
open file for writing
FILE * file_
file pointer
Definition: chunked_file.h:93
void decompress(CompressionType compression, uint8_t *dest, unsigned int dest_len, uint8_t *source, unsigned int source_len)
void openReadWrite(std::string const &filename)
open file for reading & writing
boost::shared_ptr< Stream > read_stream_
Definition: chunked_file.h:101
char * unused_
extra data read by compressed stream
Definition: chunked_file.h:96


rosbag_storage
Author(s): Dirk Thomas
autogenerated on Mon Feb 28 2022 23:33:55