Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035 #include "rosbag/chunked_file.h"
00036
00037 #include <iostream>
00038
00039 #include <boost/format.hpp>
00040 #include <boost/make_shared.hpp>
00041
00042
00043 #ifdef _WIN32
00044 # ifdef __MINGW32__
00045 # define fseeko fseeko64
00046 # define ftello ftello64
00047
00048 # else
00049 # include <io.h>
00050 # define fseeko _fseeki64
00051 # define ftello _ftelli64
00052 # define fileno _fileno
00053 # define ftruncate _chsize
00054 # endif
00055 #endif
00056
00057 using std::string;
00058 using boost::format;
00059 using boost::shared_ptr;
00060 using ros::Exception;
00061
00062 namespace rosbag {
00063
00064 ChunkedFile::ChunkedFile() :
00065 file_(NULL),
00066 offset_(0),
00067 compressed_in_(0),
00068 unused_(NULL),
00069 nUnused_(0)
00070 {
00071 stream_factory_ = boost::make_shared<StreamFactory>(this);
00072 }
00073
00074 ChunkedFile::~ChunkedFile() {
00075 close();
00076 }
00077
00078 void ChunkedFile::openReadWrite(string const& filename) { open(filename, "r+b"); }
00079 void ChunkedFile::openWrite (string const& filename) { open(filename, "w+b"); }
00080 void ChunkedFile::openRead (string const& filename) { open(filename, "rb"); }
00081
00082 void ChunkedFile::open(string const& filename, string const& mode) {
00083
00084 if (file_)
00085 throw BagIOException((format("File already open: %1%") % filename_.c_str()).str());
00086
00087
00088 if (mode == "r+b") {
00089
00090 #if defined(_MSC_VER) && (_MSC_VER >= 1400 )
00091 fopen_s( &file_, filename.c_str(), "r" );
00092 #else
00093 file_ = fopen(filename.c_str(), "r");
00094 #endif
00095 if (file_ == NULL)
00096 #if defined(_MSC_VER) && (_MSC_VER >= 1400 )
00097 fopen_s( &file_, filename.c_str(), "w+b" );
00098 #else
00099 file_ = fopen(filename.c_str(), "w+b");
00100 #endif
00101 else {
00102 fclose(file_);
00103 #if defined(_MSC_VER) && (_MSC_VER >= 1400 )
00104 fopen_s( &file_, filename.c_str(), "w+b" );
00105 #else
00106 file_ = fopen(filename.c_str(), "r+b");
00107 #endif
00108 }
00109 }
00110 else
00111 #if defined(_MSC_VER) && (_MSC_VER >= 1400 )
00112 fopen_s( &file_, filename.c_str(), mode.c_str() );
00113 #else
00114 file_ = fopen(filename.c_str(), mode.c_str());
00115 #endif
00116
00117 if (!file_)
00118 throw BagIOException((format("Error opening file: %1%") % filename.c_str()).str());
00119
00120 read_stream_ = boost::make_shared<UncompressedStream>(this);
00121 write_stream_ = boost::make_shared<UncompressedStream>(this);
00122 filename_ = filename;
00123 offset_ = ftello(file_);
00124 }
00125
00126 bool ChunkedFile::good() const {
00127 return feof(file_) == 0 && ferror(file_) == 0;
00128 }
00129
00130 bool ChunkedFile::isOpen() const { return file_ != NULL; }
00131 string ChunkedFile::getFileName() const { return filename_; }
00132
00133 void ChunkedFile::close() {
00134 if (!file_)
00135 return;
00136
00137
00138 setWriteMode(compression::Uncompressed);
00139
00140
00141 int success = fclose(file_);
00142 if (success != 0)
00143 throw BagIOException((format("Error closing file: %1%") % filename_.c_str()).str());
00144
00145 file_ = NULL;
00146 filename_.clear();
00147
00148 clearUnused();
00149 }
00150
00151
00152
00153 void ChunkedFile::setWriteMode(CompressionType type) {
00154 if (!file_)
00155 throw BagIOException("Can't set compression mode before opening a file");
00156
00157 if (type != write_stream_->getCompressionType()) {
00158 write_stream_->stopWrite();
00159 shared_ptr<Stream> stream = stream_factory_->getStream(type);
00160 stream->startWrite();
00161 write_stream_ = stream;
00162 }
00163 }
00164
00165 void ChunkedFile::setReadMode(CompressionType type) {
00166 if (!file_)
00167 throw BagIOException("Can't set compression mode before opening a file");
00168
00169 if (type != read_stream_->getCompressionType()) {
00170 read_stream_->stopRead();
00171 shared_ptr<Stream> stream = stream_factory_->getStream(type);
00172 stream->startRead();
00173 read_stream_ = stream;
00174 }
00175 }
00176
00177 void ChunkedFile::seek(uint64_t offset, int origin) {
00178 if (!file_)
00179 throw BagIOException("Can't seek - file not open");
00180
00181 setReadMode(compression::Uncompressed);
00182
00183 int success = fseeko(file_, offset, origin);
00184 if (success != 0)
00185 throw BagIOException("Error seeking");
00186
00187 offset_ = ftello(file_);
00188 }
00189
00190 uint64_t ChunkedFile::getOffset() const { return offset_; }
00191 uint32_t ChunkedFile::getCompressedBytesIn() const { return compressed_in_; }
00192
00193 void ChunkedFile::write(string const& s) { write((void*) s.c_str(), s.size()); }
00194 void ChunkedFile::write(void* ptr, size_t size) { write_stream_->write(ptr, size); }
00195 void ChunkedFile::read(void* ptr, size_t size) { read_stream_->read(ptr, size); }
00196
00197 bool ChunkedFile::truncate(uint64_t length) {
00198 int fd = fileno(file_);
00199 return ftruncate(fd, length) == 0;
00200 }
00201
00203 string ChunkedFile::getline() {
00204 char buffer[1024];
00205 if(fgets(buffer, 1024, file_))
00206 {
00207 string s(buffer);
00208 offset_ += s.size();
00209 return s;
00210 }
00211 else
00212 return string("");
00213 }
00214
00215 void ChunkedFile::decompress(CompressionType compression, uint8_t* dest, unsigned int dest_len, uint8_t* source, unsigned int source_len) {
00216 stream_factory_->getStream(compression)->decompress(dest, dest_len, source, source_len);
00217 }
00218
00219 void ChunkedFile::clearUnused() {
00220 unused_ = NULL;
00221 nUnused_ = 0;
00222 }
00223
00224 }