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