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

[iron] Propagate "custom_data" and "ros_distro" in to the metadata.yaml file during re-indexing (backport #1700) #1711

Merged
merged 3 commits into from
Jun 23, 2024
Merged
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
10 changes: 10 additions & 0 deletions rosbag2_cpp/src/rosbag2_cpp/reindexer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -165,6 +165,8 @@ void Reindexer::aggregate_metadata(
const rosbag2_storage::StorageOptions & storage_options)
{
std::map<std::string, rosbag2_storage::TopicInformation> temp_topic_info;
std::chrono::time_point<std::chrono::high_resolution_clock> latest_log_start =
std::chrono::time_point<std::chrono::high_resolution_clock>::min();

// In order to most accurately reconstruct the metadata, we need to
// visit each of the contained relative files files in the bag,
Expand All @@ -191,6 +193,14 @@ void Reindexer::aggregate_metadata(
auto temp_metadata = bag_reader->get_metadata();
metadata_.storage_identifier = temp_metadata.storage_identifier;

// try to find the last log for the most complete custom data section
if (latest_log_start < temp_metadata.starting_time) {
latest_log_start = temp_metadata.starting_time;
if (!temp_metadata.custom_data.empty()) {
metadata_.custom_data = temp_metadata.custom_data;
}
}

if (temp_metadata.starting_time < metadata_.starting_time) {
metadata_.starting_time = temp_metadata.starting_time;
}
Expand Down
10 changes: 10 additions & 0 deletions rosbag2_tests/test/rosbag2_tests/test_reindexer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -80,6 +80,7 @@ class ReindexTestFixture : public ParametrizedTemporaryDirectoryFixture
rosbag2_storage::StorageOptions storage_options;
storage_options.storage_id = GetParam();
storage_options.uri = root_bag_path_.string();
storage_options.custom_data["name"] = "value";
writer.open(storage_options);
rosbag2_storage::TopicMetadata topic;
topic.name = "/test_topic";
Expand Down Expand Up @@ -132,6 +133,15 @@ TEST_P(ReindexTestFixture, test_multiple_files) {
EXPECT_EQ(generated_metadata.storage_identifier, GetParam());
EXPECT_EQ(generated_metadata.version, target_metadata.version);

if (GetParam() != "mcap") {
// Skip check for mcap storage since it doesn't store serialized metadata in bag directly on
// Iron and Humble. Backporting of the relevant #1423 is not possible without updating
// mcap vendor package to the v1.1.0 because we have dependencies from the
// mcap_reader_->metadataIndexes(); API which became available only in the
// https://github.com/foxglove/mcap/pull/902
EXPECT_EQ(generated_metadata.custom_data, target_metadata.custom_data);
}

for (const auto & gen_rel_path : generated_metadata.relative_file_paths) {
EXPECT_TRUE(
std::find(
Expand Down
Loading