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 <ros/ros.h>
00040
00041 using std::string;
00042
00043 namespace rosbag {
00044
00045 BZ2Stream::BZ2Stream(ChunkedFile* file) :
00046 Stream(file),
00047 verbosity_(0),
00048 block_size_100k_(9),
00049 work_factor_(30),
00050 bzfile_(NULL),
00051 bzerror_(0)
00052 { }
00053
00054 CompressionType BZ2Stream::getCompressionType() const {
00055 return compression::BZ2;
00056 }
00057
00058 void BZ2Stream::startWrite() {
00059 bzfile_ = BZ2_bzWriteOpen(&bzerror_, getFilePointer(), block_size_100k_, verbosity_, work_factor_);
00060
00061 switch (bzerror_) {
00062 case BZ_OK: break;
00063 default: {
00064 BZ2_bzWriteClose(&bzerror_, bzfile_, 0, NULL, NULL);
00065 throw BagException("Error opening file for writing compressed stream");
00066 }
00067 }
00068
00069 setCompressedIn(0);
00070 }
00071
00072 void BZ2Stream::write(void* ptr, size_t size) {
00073 BZ2_bzWrite(&bzerror_, bzfile_, ptr, size);
00074
00075 switch (bzerror_) {
00076 case BZ_IO_ERROR: throw BagException("BZ_IO_ERROR: error writing the compressed file");
00077 }
00078
00079 setCompressedIn(getCompressedIn() + size);
00080 }
00081
00082 void BZ2Stream::stopWrite() {
00083 unsigned int nbytes_in;
00084 unsigned int nbytes_out;
00085 BZ2_bzWriteClose(&bzerror_, bzfile_, 0, &nbytes_in, &nbytes_out);
00086
00087 switch (bzerror_) {
00088 case BZ_IO_ERROR: throw BagIOException("BZ_IO_ERROR");
00089 }
00090
00091 advanceOffset(nbytes_out);
00092 setCompressedIn(0);
00093 }
00094
00095 void BZ2Stream::startRead() {
00096 bzfile_ = BZ2_bzReadOpen(&bzerror_, getFilePointer(), verbosity_, 0, getUnused(), getUnusedLength());
00097
00098 switch (bzerror_) {
00099 case BZ_OK: break;
00100 default: {
00101 BZ2_bzReadClose(&bzerror_, bzfile_);
00102 throw BagException("Error opening file for reading compressed stream");
00103 }
00104 }
00105
00106 clearUnused();
00107 }
00108
00109 void BZ2Stream::read(void* ptr, size_t size) {
00110 BZ2_bzRead(&bzerror_, bzfile_, ptr, size);
00111
00112 advanceOffset(size);
00113
00114 switch (bzerror_) {
00115 case BZ_OK: return;
00116 case BZ_STREAM_END:
00117 if (getUnused() || getUnusedLength() > 0)
00118 ROS_ERROR("unused data already available");
00119 else {
00120 char* unused;
00121 int nUnused;
00122 BZ2_bzReadGetUnused(&bzerror_, bzfile_, (void**) &unused, &nUnused);
00123 setUnused(unused);
00124 setUnusedLength(nUnused);
00125 }
00126 return;
00127 case BZ_IO_ERROR: throw BagIOException("BZ_IO_ERROR: error reading from compressed stream"); break;
00128 case BZ_UNEXPECTED_EOF: throw BagIOException("BZ_UNEXPECTED_EOF: compressed stream ended before logical end-of-stream detected"); break;
00129 case BZ_DATA_ERROR: throw BagIOException("BZ_DATA_ERROR: data integrity error detected in compressed stream"); break;
00130 case BZ_DATA_ERROR_MAGIC: throw BagIOException("BZ_DATA_ERROR_MAGIC: stream does not begin with requisite header bytes"); break;
00131 case BZ_MEM_ERROR: throw BagIOException("BZ_MEM_ERROR: insufficient memory available"); break;
00132 }
00133 }
00134
00135 void BZ2Stream::stopRead() {
00136 BZ2_bzReadClose(&bzerror_, bzfile_);
00137
00138 switch (bzerror_) {
00139 case BZ_IO_ERROR: throw BagIOException("BZ_IO_ERROR");
00140 }
00141 }
00142
00143 void BZ2Stream::decompress(uint8_t* dest, unsigned int dest_len, uint8_t* source, unsigned int source_len) {
00144 int result = BZ2_bzBuffToBuffDecompress((char*) dest, &dest_len, (char*) source, source_len, 0, verbosity_);
00145
00146 switch (result) {
00147 case BZ_OK: break;
00148 case BZ_CONFIG_ERROR: throw BagException("library has been mis-compiled"); break;
00149 case BZ_PARAM_ERROR: throw BagException("dest is NULL or destLen is NULL or small != 0 && small != 1 or verbosity < 0 or verbosity > 4"); break;
00150 case BZ_MEM_ERROR: throw BagException("insufficient memory is available"); break;
00151 case BZ_OUTBUFF_FULL: throw BagException("size of the compressed data exceeds *destLen"); break;
00152 case BZ_DATA_ERROR: throw BagException("data integrity error was detected in the compressed data"); break;
00153 case BZ_DATA_ERROR_MAGIC: throw BagException("compressed data doesn't begin with the right magic bytes"); break;
00154 case BZ_UNEXPECTED_EOF: throw BagException("compressed data ends unexpectedly"); break;
00155 }
00156 }
00157
00158 }