Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

[jazzy] Bugfix: Update metadata with new file_info before saving it the first time in the file (backport #1843) #1853

Open
wants to merge 1 commit into
base: jazzy
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -392,7 +392,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 @@ -334,6 +334,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 @@ -353,14 +361,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
Loading