Skip to content

Commit

Permalink
Bugfix: Update metadata with new file_info before saving it first time
Browse files Browse the repository at this point in the history
Signed-off-by: Michael Orlov <[email protected]>
  • Loading branch information
MichaelOrlov committed Oct 26, 2024
1 parent cb7d362 commit 24c824c
Show file tree
Hide file tree
Showing 3 changed files with 10 additions and 10 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -391,7 +391,7 @@ TEST_F(SequentialCompressionWriterTest, writer_call_metadata_update_on_bag_split
EXPECT_EQ(compression_mode, rosbag2_compression::CompressionMode::MESSAGE);
EXPECT_EQ(v_intercepted_update_metadata_[0].message_count, 0u); // On opening first bag file
EXPECT_EQ(v_intercepted_update_metadata_[1].files.size(), 1u); // On closing first bag file
EXPECT_EQ(v_intercepted_update_metadata_[2].files.size(), 1u); // On opening second bag file
EXPECT_EQ(v_intercepted_update_metadata_[2].files.size(), 2u); // On opening second bag file
EXPECT_EQ(v_intercepted_update_metadata_[3].files.size(), 2u); // On writer destruction
EXPECT_EQ(v_intercepted_update_metadata_[3].message_count, 2 * kNumMessagesToWrite);
}
Expand Down
16 changes: 8 additions & 8 deletions rosbag2_cpp/src/rosbag2_cpp/writers/sequential_writer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -332,6 +332,14 @@ void SequentialWriter::switch_to_next_storage()

throw std::runtime_error(errmsg.str());
}

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);
metadata_.relative_file_paths.push_back(file_info.path);

storage_->update_metadata(metadata_);
// Re-register all topics since we rolled-over to a new bagfile.
for (const auto & topic : topics_names_to_info_) {
Expand All @@ -351,14 +359,6 @@ std::string SequentialWriter::split_bagfile_local(bool execute_callbacks)
switch_to_next_storage();
auto 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);

if (execute_callbacks) {
execute_bag_split_callbacks(closed_file, opened_file);
}
Expand Down
2 changes: 1 addition & 1 deletion rosbag2_cpp/test/rosbag2_cpp/test_sequential_writer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -226,7 +226,7 @@ TEST_F(SequentialWriterTest, sequantial_writer_call_metadata_update_on_bag_split
EXPECT_TRUE(v_intercepted_update_metadata_[0].compression_mode.empty());
EXPECT_EQ(v_intercepted_update_metadata_[0].message_count, 0u); // On opening first bag file
EXPECT_EQ(v_intercepted_update_metadata_[1].files.size(), 1u); // On closing first bag file
EXPECT_EQ(v_intercepted_update_metadata_[2].files.size(), 1u); // On opening second bag file
EXPECT_EQ(v_intercepted_update_metadata_[2].files.size(), 2u); // On opening second bag file
EXPECT_EQ(v_intercepted_update_metadata_[3].files.size(), 2u); // On writer destruction
EXPECT_EQ(v_intercepted_update_metadata_[3].message_count, 2 * kNumMessagesToWrite);
}
Expand Down

0 comments on commit 24c824c

Please sign in to comment.