-
Notifications
You must be signed in to change notification settings - Fork 235
/
sequential_writer.cpp
513 lines (436 loc) · 16.3 KB
/
sequential_writer.cpp
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
436
437
438
439
440
441
442
443
444
445
446
447
448
449
450
451
452
453
454
455
456
457
458
459
460
461
462
463
464
465
466
467
468
469
470
471
472
473
474
475
476
477
478
479
480
481
482
483
484
485
486
487
488
489
490
491
492
493
494
495
496
497
498
499
500
501
502
503
504
505
506
507
508
509
510
511
512
513
// Copyright 2018, Bosch Software Innovations GmbH.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.
#include "rosbag2_cpp/writers/sequential_writer.hpp"
#include <algorithm>
#include <chrono>
#include <memory>
#include <stdexcept>
#include <string>
#include <sstream>
#include <unordered_map>
#include <utility>
#include <vector>
#include "rcpputils/env.hpp"
#include "rcpputils/filesystem_helper.hpp"
#include "rosbag2_cpp/info.hpp"
#include "rosbag2_cpp/logging.hpp"
#include "rosbag2_cpp/service_utils.hpp"
#include "rosbag2_storage/default_storage_id.hpp"
#include "rosbag2_storage/storage_options.hpp"
namespace rosbag2_cpp
{
namespace writers
{
namespace
{
std::string strip_parent_path(const std::string & relative_path)
{
return rcpputils::fs::path(relative_path).filename().string();
}
} // namespace
SequentialWriter::SequentialWriter(
std::unique_ptr<rosbag2_storage::StorageFactoryInterface> storage_factory,
std::shared_ptr<SerializationFormatConverterFactoryInterface> converter_factory,
std::unique_ptr<rosbag2_storage::MetadataIo> metadata_io)
: storage_factory_(std::move(storage_factory)),
converter_factory_(std::move(converter_factory)),
storage_(nullptr),
metadata_io_(std::move(metadata_io)),
converter_(nullptr),
topics_names_to_info_(),
message_definitions_(),
metadata_()
{}
SequentialWriter::~SequentialWriter()
{
// Deleting all callbacks before calling close(). Calling callbacks from destructor is not safe.
// Callbacks likely was created after SequentialWriter object and may point to the already
// destructed objects.
callback_manager_.delete_all_callbacks();
close();
}
void SequentialWriter::init_metadata()
{
metadata_ = rosbag2_storage::BagMetadata{};
metadata_.storage_identifier = storage_->get_storage_identifier();
metadata_.starting_time = std::chrono::time_point<std::chrono::high_resolution_clock>(
std::chrono::nanoseconds::max());
metadata_.relative_file_paths = {strip_parent_path(storage_->get_relative_file_path())};
rosbag2_storage::FileInformation file_info{};
file_info.path = strip_parent_path(storage_->get_relative_file_path());
file_info.starting_time = std::chrono::time_point<std::chrono::high_resolution_clock>(
std::chrono::nanoseconds::max());
file_info.message_count = 0;
metadata_.custom_data = storage_options_.custom_data;
metadata_.files = {file_info};
metadata_.ros_distro = rcpputils::get_env_var("ROS_DISTRO");
if (metadata_.ros_distro.empty()) {
ROSBAG2_CPP_LOG_WARN(
"Environment variable ROS_DISTRO not set, can't store value in bag metadata.");
}
}
void SequentialWriter::open(
const rosbag2_storage::StorageOptions & storage_options,
const ConverterOptions & converter_options)
{
base_folder_ = storage_options.uri;
storage_options_ = storage_options;
if (storage_options_.storage_id.empty()) {
storage_options_.storage_id = rosbag2_storage::get_default_storage_id();
}
if (converter_options.output_serialization_format !=
converter_options.input_serialization_format)
{
converter_ = std::make_unique<Converter>(converter_options, converter_factory_);
}
rcpputils::fs::path storage_path(storage_options.uri);
if (storage_path.is_directory()) {
std::stringstream error;
error << "Bag directory already exists (" << storage_path.string() <<
"), can't overwrite existing bag";
throw std::runtime_error{error.str()};
}
bool dir_created = rcpputils::fs::create_directories(storage_path);
if (!dir_created) {
std::stringstream error;
error << "Failed to create bag directory (" << storage_path.string() << ").";
throw std::runtime_error{error.str()};
}
storage_options_.uri = format_storage_uri(base_folder_, 0);
storage_ = storage_factory_->open_read_write(storage_options_);
if (!storage_) {
throw std::runtime_error("No storage could be initialized. Abort");
}
if (storage_options_.max_bagfile_size != 0 &&
storage_options_.max_bagfile_size < storage_->get_minimum_split_file_size())
{
std::stringstream error;
error << "Invalid bag splitting size given. Please provide a value greater than " <<
storage_->get_minimum_split_file_size() << ". Specified value of " <<
storage_options.max_bagfile_size;
throw std::runtime_error{error.str()};
}
use_cache_ = storage_options.max_cache_size > 0u;
if (storage_options.snapshot_mode && !use_cache_) {
throw std::runtime_error(
"Max cache size must be greater than 0 when snapshot mode is enabled");
}
if (use_cache_) {
if (storage_options.snapshot_mode) {
message_cache_ = std::make_shared<rosbag2_cpp::cache::CircularMessageCache>(
storage_options.max_cache_size);
} else {
message_cache_ = std::make_shared<rosbag2_cpp::cache::MessageCache>(
storage_options.max_cache_size);
}
cache_consumer_ = std::make_unique<rosbag2_cpp::cache::CacheConsumer>(
message_cache_,
std::bind(&SequentialWriter::write_messages, this, std::placeholders::_1));
}
init_metadata();
storage_->update_metadata(metadata_);
}
void SequentialWriter::close()
{
if (use_cache_) {
// destructor will flush message cache
cache_consumer_.reset();
message_cache_.reset();
}
if (!base_folder_.empty()) {
finalize_metadata();
if (storage_) {
storage_->update_metadata(metadata_);
}
metadata_io_->write_metadata(base_folder_, metadata_);
}
if (storage_) {
auto info = std::make_shared<bag_events::BagSplitInfo>();
info->closed_file = storage_->get_relative_file_path();
storage_.reset(); // Destroy storage before calling WRITE_SPLIT callback to make sure that
// bag file was closed before callback call.
callback_manager_.execute_callbacks(bag_events::BagEvent::WRITE_SPLIT, info);
}
storage_factory_.reset();
}
void SequentialWriter::create_topic(const rosbag2_storage::TopicMetadata & topic_with_type)
{
if (topics_names_to_info_.find(topic_with_type.name) !=
topics_names_to_info_.end())
{
// nothing to do, topic already created
return;
}
rosbag2_storage::MessageDefinition definition;
std::string topic_type;
if (is_service_event_topic(topic_with_type.name, topic_with_type.type)) {
// change service event type to service type for next step to get message definition
topic_type = service_event_topic_type_to_service_type(topic_with_type.type);
} else {
topic_type = topic_with_type.type;
}
try {
definition = message_definitions_.get_full_text(topic_type);
} catch (DefinitionNotFoundError &) {
definition = rosbag2_storage::MessageDefinition::empty_message_definition_for(topic_type);
}
create_topic(topic_with_type, definition);
}
void SequentialWriter::create_topic(
const rosbag2_storage::TopicMetadata & topic_with_type,
const rosbag2_storage::MessageDefinition & message_definition)
{
if (topics_names_to_info_.find(topic_with_type.name) !=
topics_names_to_info_.end())
{
// nothing to do, topic already created
return;
}
if (!storage_) {
throw std::runtime_error("Bag is not open. Call open() before writing.");
}
rosbag2_storage::TopicInformation info{};
info.topic_metadata = topic_with_type;
bool insert_succeeded = false;
{
std::lock_guard<std::mutex> lock(topics_info_mutex_);
const auto insert_res = topics_names_to_info_.insert(
std::make_pair(topic_with_type.name, info));
insert_succeeded = insert_res.second;
}
if (!insert_succeeded) {
std::stringstream errmsg;
errmsg << "Failed to insert topic \"" << topic_with_type.name << "\"!";
throw std::runtime_error(errmsg.str());
}
topic_names_to_message_definitions_.insert(
std::make_pair(topic_with_type.name, message_definition));
storage_->create_topic(topic_with_type, message_definition);
if (converter_) {
converter_->add_topic(topic_with_type.name, topic_with_type.type);
}
}
void SequentialWriter::remove_topic(const rosbag2_storage::TopicMetadata & topic_with_type)
{
if (!storage_) {
throw std::runtime_error("Bag is not open. Call open() before removing.");
}
bool erased = false;
{
std::lock_guard<std::mutex> lock(topics_info_mutex_);
erased = topics_names_to_info_.erase(topic_with_type.name) > 0;
erased = erased && (topic_names_to_message_definitions_.erase(topic_with_type.name) > 0);
}
if (erased) {
storage_->remove_topic(topic_with_type);
} else {
std::stringstream errmsg;
errmsg << "Failed to remove the non-existing topic \"" <<
topic_with_type.name << "\"!";
throw std::runtime_error(errmsg.str());
}
}
std::string SequentialWriter::format_storage_uri(
const std::string & base_folder, uint64_t storage_count)
{
// Right now `base_folder_` is always just the folder name for where to install the bagfile.
// The name of the folder needs to be queried in case
// SequentialWriter is opened with a relative path.
std::stringstream storage_file_name;
storage_file_name << rcpputils::fs::path(base_folder).filename().string() << "_" << storage_count;
return (rcpputils::fs::path(base_folder) / storage_file_name.str()).string();
}
void SequentialWriter::switch_to_next_storage()
{
// consume remaining message cache
if (use_cache_) {
cache_consumer_->stop();
message_cache_->log_dropped();
}
storage_->update_metadata(metadata_);
storage_options_.uri = format_storage_uri(
base_folder_,
metadata_.relative_file_paths.size());
storage_ = storage_factory_->open_read_write(storage_options_);
storage_->update_metadata(metadata_);
if (!storage_) {
std::stringstream errmsg;
errmsg << "Failed to rollover bagfile to new file: \"" << storage_options_.uri << "\"!";
throw std::runtime_error(errmsg.str());
}
// Re-register all topics since we rolled-over to a new bagfile.
for (const auto & topic : topics_names_to_info_) {
auto const & md = topic_names_to_message_definitions_[topic.first];
storage_->create_topic(topic.second.topic_metadata, md);
}
if (use_cache_) {
// restart consumer thread for cache
cache_consumer_->start();
}
}
void SequentialWriter::split_bagfile()
{
auto info = std::make_shared<bag_events::BagSplitInfo>();
info->closed_file = storage_->get_relative_file_path();
switch_to_next_storage();
info->opened_file = storage_->get_relative_file_path();
metadata_.relative_file_paths.push_back(strip_parent_path(storage_->get_relative_file_path()));
rosbag2_storage::FileInformation file_info{};
file_info.starting_time = std::chrono::time_point<std::chrono::high_resolution_clock>(
std::chrono::nanoseconds::max());
file_info.path = strip_parent_path(storage_->get_relative_file_path());
metadata_.files.push_back(file_info);
callback_manager_.execute_callbacks(bag_events::BagEvent::WRITE_SPLIT, info);
}
void SequentialWriter::write(std::shared_ptr<const rosbag2_storage::SerializedBagMessage> message)
{
if (!storage_) {
throw std::runtime_error("Bag is not open. Call open() before writing.");
}
if (!message_within_accepted_time_range(message->receive_time_stamp)) {
return;
}
// Get TopicInformation handler for counting messages.
rosbag2_storage::TopicInformation * topic_information {nullptr};
try {
topic_information = &topics_names_to_info_.at(message->topic_name);
} catch (const std::out_of_range & /* oor */) {
std::stringstream errmsg;
errmsg << "Failed to write on topic '" << message->topic_name <<
"'. Call create_topic() before first write.";
throw std::runtime_error(errmsg.str());
}
const auto message_timestamp = std::chrono::time_point<std::chrono::high_resolution_clock>(
std::chrono::nanoseconds(message->receive_time_stamp));
if (is_first_message_) {
// Update bagfile starting time
metadata_.starting_time = message_timestamp;
is_first_message_ = false;
}
if (should_split_bagfile(message_timestamp)) {
split_bagfile();
metadata_.files.back().starting_time = message_timestamp;
}
metadata_.starting_time = std::min(metadata_.starting_time, message_timestamp);
metadata_.files.back().starting_time =
std::min(metadata_.files.back().starting_time, message_timestamp);
const auto duration = message_timestamp - metadata_.starting_time;
metadata_.duration = std::max(metadata_.duration, duration);
const auto file_duration = message_timestamp - metadata_.files.back().starting_time;
metadata_.files.back().duration =
std::max(metadata_.files.back().duration, file_duration);
auto converted_msg = get_writeable_message(message);
metadata_.files.back().message_count++;
if (storage_options_.max_cache_size == 0u) {
// If cache size is set to zero, we write to storage directly
storage_->write(converted_msg);
++topic_information->message_count;
} else {
// Otherwise, use cache buffer
message_cache_->push(converted_msg);
}
}
bool SequentialWriter::take_snapshot()
{
if (!storage_options_.snapshot_mode) {
ROSBAG2_CPP_LOG_WARN("SequentialWriter take_snaphot called when snapshot mode is disabled");
return false;
}
message_cache_->notify_data_ready();
return true;
}
std::shared_ptr<const rosbag2_storage::SerializedBagMessage>
SequentialWriter::get_writeable_message(
std::shared_ptr<const rosbag2_storage::SerializedBagMessage> message)
{
return converter_ ? converter_->convert(message) : message;
}
bool SequentialWriter::should_split_bagfile(
const std::chrono::time_point<std::chrono::high_resolution_clock> & current_time) const
{
// Assume we aren't splitting
bool should_split = false;
// Splitting by size
if (storage_options_.max_bagfile_size !=
rosbag2_storage::storage_interfaces::MAX_BAGFILE_SIZE_NO_SPLIT)
{
should_split = (storage_->get_bagfile_size() >= storage_options_.max_bagfile_size);
}
// Splitting by time
if (storage_options_.max_bagfile_duration !=
rosbag2_storage::storage_interfaces::MAX_BAGFILE_DURATION_NO_SPLIT)
{
auto max_duration_ns = std::chrono::duration_cast<std::chrono::nanoseconds>(
std::chrono::seconds(storage_options_.max_bagfile_duration));
should_split = should_split ||
((current_time - metadata_.files.back().starting_time) > max_duration_ns);
}
return should_split;
}
bool SequentialWriter::message_within_accepted_time_range(
const rcutils_time_point_value_t current_time) const
{
if (storage_options_.start_time_ns >= 0 &&
static_cast<int64_t>(current_time) < storage_options_.start_time_ns)
{
return false;
}
if (storage_options_.end_time_ns >= 0 &&
static_cast<int64_t>(current_time) > storage_options_.end_time_ns)
{
return false;
}
return true;
}
void SequentialWriter::finalize_metadata()
{
metadata_.bag_size = 0;
for (const auto & path : metadata_.relative_file_paths) {
const auto bag_path = rcpputils::fs::path{path};
if (bag_path.exists()) {
metadata_.bag_size += bag_path.file_size();
}
}
metadata_.topics_with_message_count.clear();
metadata_.topics_with_message_count.reserve(topics_names_to_info_.size());
metadata_.message_count = 0;
for (const auto & topic : topics_names_to_info_) {
metadata_.topics_with_message_count.push_back(topic.second);
metadata_.message_count += topic.second.message_count;
}
}
void SequentialWriter::write_messages(
const std::vector<std::shared_ptr<const rosbag2_storage::SerializedBagMessage>> & messages)
{
if (messages.empty()) {
return;
}
storage_->write(messages);
std::lock_guard<std::mutex> lock(topics_info_mutex_);
for (const auto & msg : messages) {
if (topics_names_to_info_.find(msg->topic_name) != topics_names_to_info_.end()) {
topics_names_to_info_[msg->topic_name].message_count++;
}
}
}
void SequentialWriter::add_event_callbacks(const bag_events::WriterEventCallbacks & callbacks)
{
if (callbacks.write_split_callback) {
callback_manager_.add_event_callback(
callbacks.write_split_callback,
bag_events::BagEvent::WRITE_SPLIT);
}
}
} // namespace writers
} // namespace rosbag2_cpp