Skip to content

Commit

Permalink
Update get_metadata_include_topics_with_zero_messages test after rebase
Browse files Browse the repository at this point in the history
- Parametrize get_metadata_include_topics_with_zero_messages test to run
for mcap and sqlite3 storage plugins.

Signed-off-by: Michael Orlov <[email protected]>
  • Loading branch information
MichaelOrlov committed Jun 23, 2024
1 parent 4f04dbd commit 3000974
Showing 1 changed file with 19 additions and 17 deletions.
36 changes: 19 additions & 17 deletions rosbag2_cpp/test/rosbag2_cpp/test_sequential_reader.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -243,34 +243,36 @@ TEST_P(ParametrizedTemporaryDirectoryFixture, reader_accepts_bare_file) {
EXPECT_THAT(reader.get_metadata().topics_with_message_count, SizeIs(1));
}

TEST_F(TemporaryDirectoryFixture, get_metadata_include_topics_with_zero_messages) {
TEST_P(ParametrizedTemporaryDirectoryFixture, get_metadata_include_topics_with_zero_messages) {
const auto bag_path = rcpputils::fs::path(temporary_dir_path_) / "bag_with_no_msgs";
const auto expected_bag = rcpputils::fs::path(temporary_dir_path_) / "bag_with_no_msgs.db3";
const std::string topic_name = "topic_with_0_messages";
const std::string storage_id = "sqlite3";
const auto storage_id = GetParam();
{
rosbag2_storage::TopicMetadata topic_metadata;
topic_metadata.name = topic_name;
topic_metadata.type = "std_msgs/msg/String";

rosbag2_storage::StorageFactory factory;
rosbag2_cpp::Writer writer;
rosbag2_storage::StorageOptions options;
options.uri = bag_path.string();
options.storage_id = storage_id;
auto writer = factory.open_read_write(options);
writer->create_topic(topic_metadata);
}
ASSERT_TRUE(expected_bag.exists());
{
rosbag2_storage::StorageFactory factory;
rosbag2_storage::StorageOptions options;
options.uri = expected_bag.string();
options.storage_id = storage_id;
auto reader = factory.open_read_only(options);
auto metadata = reader->get_metadata();
ASSERT_THAT(metadata.topics_with_message_count, SizeIs(1));
EXPECT_EQ(metadata.topics_with_message_count[0].message_count, 0U);
writer.open(options);
writer.create_topic(topic_metadata);
}

rosbag2_storage::MetadataIo metadata_io;
ASSERT_TRUE(metadata_io.metadata_file_exists(bag_path.string()));
auto metadata_from_yaml = metadata_io.read_metadata(bag_path.string());
auto first_storage = bag_path / metadata_from_yaml.relative_file_paths[0];

rosbag2_storage::StorageFactory factory;
rosbag2_storage::StorageOptions options;
options.uri = first_storage.string();
options.storage_id = storage_id;
auto reader = factory.open_read_only(options);
auto metadata = reader->get_metadata();
ASSERT_THAT(metadata.topics_with_message_count, SizeIs(1));
EXPECT_EQ(metadata.topics_with_message_count[0].message_count, 0U);
}

INSTANTIATE_TEST_SUITE_P(
Expand Down

0 comments on commit 3000974

Please sign in to comment.