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