19
19
#include < vector>
20
20
21
21
#include " rcpputils/filesystem_helper.hpp"
22
+ #include " rosbag2_compression/zstd_decompressor.hpp"
22
23
23
24
#include " rosbag2_cpp/logging.hpp"
24
25
#include " rosbag2_cpp/readers/sequential_reader.hpp"
@@ -48,6 +49,30 @@ void SequentialReader::reset()
48
49
storage_.reset ();
49
50
}
50
51
52
+ void SequentialReader::open_storage ()
53
+ {
54
+ storage_ = storage_factory_->open_read_only (
55
+ *current_file_iterator_, metadata_.storage_identifier );
56
+ if (!storage_) {
57
+ throw std::runtime_error{" No storage could be initialized. Abort" };
58
+ }
59
+ }
60
+
61
+ void SequentialReader::setup_compression ()
62
+ {
63
+ compression_mode_ = compression_mode_from_string (metadata_.compression_mode );
64
+ if (compression_mode_ != rosbag2_cpp::CompressionMode::NONE) {
65
+ // TODO(piraka9011): Replace this with a compressor_factory.
66
+ if (metadata_.compression_format == " zstd" ) {
67
+ decompressor_ = std::make_unique<rosbag2_compression::ZstdDecompressor>();
68
+ } else {
69
+ std::stringstream err;
70
+ err << " Unsupported compression format " << metadata_.compression_format ;
71
+ throw std::runtime_error (err.str ());
72
+ }
73
+ }
74
+ }
75
+
51
76
void SequentialReader::open (
52
77
const StorageOptions & storage_options, const ConverterOptions & converter_options)
53
78
{
@@ -60,21 +85,12 @@ void SequentialReader::open(
60
85
ROSBAG2_CPP_LOG_WARN (" No file paths were found in metadata." );
61
86
return ;
62
87
}
63
-
88
+ open_storage ();
89
+ setup_compression ();
64
90
file_paths_ = metadata_.relative_file_paths ;
65
91
current_file_iterator_ = file_paths_.begin ();
66
-
67
- storage_ = storage_factory_->open_read_only (
68
- *current_file_iterator_, metadata_.storage_identifier );
69
- if (!storage_) {
70
- throw std::runtime_error (" No storage could be initialized. Abort" );
71
- }
72
92
} else {
73
- storage_ = storage_factory_->open_read_only (
74
- storage_options.uri , storage_options.storage_id );
75
- if (!storage_) {
76
- throw std::runtime_error (" No storage could be initialized. Abort" );
77
- }
93
+ open_storage ();
78
94
metadata_ = storage_->get_metadata ();
79
95
if (metadata_.relative_file_paths .empty ()) {
80
96
ROSBAG2_CPP_LOG_WARN (" No file paths were found in metadata." );
@@ -112,10 +128,19 @@ bool SequentialReader::has_next()
112
128
throw std::runtime_error (" Bag is not open. Call open() before reading." );
113
129
}
114
130
131
+ void SequentialReader::decompress_message (
132
+ rosbag2_storage::SerializedBagMessage * message)
133
+ {
134
+ if (compression_mode_ == CompressionMode::MESSAGE) {
135
+ decompressor_->decompress_serialized_bag_message (message);
136
+ }
137
+ }
138
+
115
139
std::shared_ptr<rosbag2_storage::SerializedBagMessage> SequentialReader::read_next ()
116
140
{
117
141
if (storage_) {
118
142
auto message = storage_->read_next ();
143
+ decompress_message (message.get ());
119
144
return converter_ ? converter_->convert (message) : message;
120
145
}
121
146
throw std::runtime_error (" Bag is not open. Call open() before reading." );
@@ -134,10 +159,19 @@ bool SequentialReader::has_next_file() const
134
159
return current_file_iterator_ + 1 != file_paths_.end ();
135
160
}
136
161
162
+ void SequentialReader::decompress_file (const std::string & uri)
163
+ {
164
+ if (compression_mode_ == CompressionMode::FILE) {
165
+ ROSBAG2_CPP_LOG_DEBUG_STREAM (" Decompressing " << uri);
166
+ *current_file_iterator_ = decompressor_->decompress_uri (uri);
167
+ }
168
+ }
169
+
137
170
void SequentialReader::load_next_file ()
138
171
{
139
172
assert (current_file_iterator_ != file_paths_.end ());
140
173
current_file_iterator_++;
174
+ decompress_file (*current_file_iterator_);
141
175
}
142
176
143
177
std::string SequentialReader::get_current_file () const
0 commit comments