From 1564687de2d10d5bce32dcb9b38ec5c9239416a4 Mon Sep 17 00:00:00 2001 From: Michael Orlov Date: Mon, 5 Feb 2024 18:06:53 -0800 Subject: [PATCH] Add topic_id returned by storage to the TopicMetadata (#1538) * Add topic_id returned by storage to the TopicMetadata - Rationale. To be able to distinguish topics by unique topic ID rather than by topic name in the future. Signed-off-by: Michael Orlov * Map inner int64_t topic_id to the external uint16_t topic_id in sqlite3 Signed-off-by: Michael Orlov * Change TopicMetadata::id type to uint16_t Signed-off-by: Michael Orlov * Use atomic for last_extern_topic_id_ Co-authored-by: Tomoya Fujita Signed-off-by: Michael Orlov --------- Signed-off-by: Michael Orlov Co-authored-by: Tomoya Fujita --- .../test_sequential_compression_reader.cpp | 2 +- .../test_sequential_compression_writer.cpp | 10 +- rosbag2_cpp/test/rosbag2_cpp/fake_data.cpp | 1 + rosbag2_cpp/test/rosbag2_cpp/test_info.cpp | 12 +- .../rosbag2_cpp/test_multifile_reader.cpp | 2 +- .../rosbag2_cpp/test_sequential_writer.cpp | 24 +-- .../test_storage_without_metadata_file.cpp | 16 +- .../src/data_generator_executable.cpp | 1 + .../src/data_generator_node.cpp | 1 + .../data_generator_executable.py | 1 + .../data_generator_node.py | 1 + .../simple_bag_recorder.py | 1 + rosbag2_py/src/rosbag2_py/_storage.cpp | 5 +- rosbag2_py/test/test_compression.py | 1 + rosbag2_py/test/test_sequential_writer.py | 2 +- rosbag2_py/test/test_storage.py | 3 + .../rosbag2_storage/topic_metadata.hpp | 4 +- .../test_metadata_serialization.cpp | 10 +- rosbag2_storage_mcap/src/mcap_storage.cpp | 1 + .../test_mcap_storage.cpp | 37 ++-- .../sqlite_statement_wrapper.hpp | 2 +- .../sqlite_storage.hpp | 12 +- .../sqlite_wrapper.hpp | 2 +- .../sqlite_statement_wrapper.cpp | 3 +- .../sqlite_storage.cpp | 194 ++++++++++-------- .../sqlite_wrapper.cpp | 2 +- .../storage_test_fixture.hpp | 2 +- .../test_sqlite_storage.cpp | 33 +-- .../test_rosbag2_storage_api.cpp | 1 + .../src/rosbag2_transport/recorder.cpp | 1 + .../rosbag2_play_duration_until_fixture.hpp | 5 +- .../test/rosbag2_transport/test_burst.cpp | 16 +- .../test_keyboard_controls.cpp | 4 +- .../test/rosbag2_transport/test_play.cpp | 32 ++- .../rosbag2_transport/test_play_callbacks.cpp | 2 +- .../rosbag2_transport/test_play_duration.cpp | 6 +- .../test/rosbag2_transport/test_play_loop.cpp | 4 +- .../test/rosbag2_transport/test_play_next.cpp | 14 +- .../test_play_publish_clock.cpp | 2 +- .../test/rosbag2_transport/test_play_seek.cpp | 2 +- .../rosbag2_transport/test_play_services.cpp | 2 +- .../rosbag2_transport/test_play_timing.cpp | 2 +- .../test_play_topic_remap.cpp | 2 +- .../rosbag2_transport/test_play_until.cpp | 8 +- .../rosbag2_transport/test_player_stop.cpp | 2 +- 45 files changed, 271 insertions(+), 219 deletions(-) diff --git a/rosbag2_compression/test/rosbag2_compression/test_sequential_compression_reader.cpp b/rosbag2_compression/test/rosbag2_compression/test_sequential_compression_reader.cpp index d715c9a8b3..d3332aff64 100644 --- a/rosbag2_compression/test/rosbag2_compression/test_sequential_compression_reader.cpp +++ b/rosbag2_compression/test/rosbag2_compression/test_sequential_compression_reader.cpp @@ -54,7 +54,7 @@ class SequentialCompressionReaderTest : public Test rcpputils::fs::remove_all(tmp_dir_); storage_options_.uri = tmp_dir_.string(); topic_with_type_ = rosbag2_storage::TopicMetadata{ - "topic", "test_msgs/BasicTypes", storage_serialization_format_, {}, ""}; + 0U, "topic", "test_msgs/BasicTypes", storage_serialization_format_, {}, ""}; auto topics_and_types = std::vector{topic_with_type_}; auto message = std::make_shared(); message->topic_name = topic_with_type_.name; diff --git a/rosbag2_compression/test/rosbag2_compression/test_sequential_compression_writer.cpp b/rosbag2_compression/test/rosbag2_compression/test_sequential_compression_writer.cpp index da611b5ab8..9cb3140240 100644 --- a/rosbag2_compression/test/rosbag2_compression/test_sequential_compression_writer.cpp +++ b/rosbag2_compression/test/rosbag2_compression/test_sequential_compression_writer.cpp @@ -258,7 +258,7 @@ TEST_F(SequentialCompressionWriterTest, writer_creates_correct_metadata_relative tmp_dir_storage_options_.max_bagfile_size = 1; writer_->open(tmp_dir_storage_options_); - writer_->create_topic({test_topic_name, test_topic_type, "", {}, ""}); + writer_->create_topic({0u, test_topic_name, test_topic_type, "", {}, ""}); auto message = std::make_shared(); message->topic_name = test_topic_name; @@ -301,7 +301,7 @@ TEST_F(SequentialCompressionWriterTest, writer_call_metadata_update_on_open_and_ EXPECT_CALL(*storage_, update_metadata(_)).Times(2); writer_->open(tmp_dir_storage_options_); - writer_->create_topic({test_topic_name, test_topic_type, "", {}, ""}); + writer_->create_topic({0u, test_topic_name, test_topic_type, "", {}, ""}); auto message = std::make_shared(); message->topic_name = test_topic_name; @@ -340,7 +340,7 @@ TEST_F(SequentialCompressionWriterTest, writer_call_metadata_update_on_bag_split EXPECT_CALL(*storage_, update_metadata(_)).Times(4); writer_->open(tmp_dir_storage_options_); - writer_->create_topic({test_topic_name, test_topic_type, "", {}, ""}); + writer_->create_topic({0u, test_topic_name, test_topic_type, "", {}, ""}); auto message = std::make_shared(); message->topic_name = test_topic_name; @@ -388,7 +388,7 @@ TEST_P(SequentialCompressionWriterTest, writer_writes_with_compression_queue_siz initializeWriter(compression_options); writer_->open(tmp_dir_storage_options_); - writer_->create_topic({test_topic_name, test_topic_type, "", {}, ""}); + writer_->create_topic({0u, test_topic_name, test_topic_type, "", {}, ""}); auto message = std::make_shared(); message->topic_name = test_topic_name; @@ -441,7 +441,7 @@ TEST_P(SequentialCompressionWriterTest, writer_sets_threads_priority) std::make_unique(detected_thread_priority)); writer_->open(tmp_dir_storage_options_); - writer_->create_topic({test_topic_name, test_topic_type, "", {}, ""}); + writer_->create_topic({0u, test_topic_name, test_topic_type, "", {}, ""}); auto message = std::make_shared(); message->topic_name = test_topic_name; diff --git a/rosbag2_cpp/test/rosbag2_cpp/fake_data.cpp b/rosbag2_cpp/test/rosbag2_cpp/fake_data.cpp index 08e4354817..a426a5f414 100644 --- a/rosbag2_cpp/test/rosbag2_cpp/fake_data.cpp +++ b/rosbag2_cpp/test/rosbag2_cpp/fake_data.cpp @@ -34,6 +34,7 @@ void write_sample_split_bag( writer.create_topic( { + 0u, topic_name, "test_msgs/msg/ByteMultiArray", "cdr", diff --git a/rosbag2_cpp/test/rosbag2_cpp/test_info.cpp b/rosbag2_cpp/test/rosbag2_cpp/test_info.cpp index 2ba7701a50..a4fa57985a 100644 --- a/rosbag2_cpp/test/rosbag2_cpp/test_info.cpp +++ b/rosbag2_cpp/test/rosbag2_cpp/test_info.cpp @@ -86,7 +86,7 @@ TEST_P(ParametrizedTemporaryDirectoryFixture, read_metadata_supports_version_2) { const auto actual_first_topic = metadata.topics_with_message_count[0]; const auto expected_first_topic = - rosbag2_storage::TopicInformation{{"topic1", "type1", "rmw1", {}, ""}, 100}; + rosbag2_storage::TopicInformation{{0u, "topic1", "type1", "rmw1", {}, ""}, 100}; EXPECT_EQ(actual_first_topic.topic_metadata, expected_first_topic.topic_metadata); EXPECT_EQ(actual_first_topic.message_count, expected_first_topic.message_count); @@ -95,7 +95,7 @@ TEST_P(ParametrizedTemporaryDirectoryFixture, read_metadata_supports_version_2) { const auto actual_second_topic = metadata.topics_with_message_count[1]; const auto expected_second_topic = - rosbag2_storage::TopicInformation{{"topic2", "type2", "rmw2", {}, ""}, 200}; + rosbag2_storage::TopicInformation{{0u, "topic2", "type2", "rmw2", {}, ""}, 200}; EXPECT_EQ(actual_second_topic.topic_metadata, expected_second_topic.topic_metadata); EXPECT_EQ(actual_second_topic.message_count, expected_second_topic.message_count); @@ -192,7 +192,7 @@ TEST_P(ParametrizedTemporaryDirectoryFixture, read_metadata_supports_version_6) { const auto actual_first_topic = metadata.topics_with_message_count[0]; const auto expected_first_topic = - rosbag2_storage::TopicInformation{{"topic1", "type1", "rmw1", {}, ""}, 100}; + rosbag2_storage::TopicInformation{{0u, "topic1", "type1", "rmw1", {}, ""}, 100}; EXPECT_EQ(actual_first_topic.topic_metadata, expected_first_topic.topic_metadata); EXPECT_EQ(actual_first_topic.message_count, expected_first_topic.message_count); @@ -201,7 +201,7 @@ TEST_P(ParametrizedTemporaryDirectoryFixture, read_metadata_supports_version_6) { const auto actual_second_topic = metadata.topics_with_message_count[1]; const auto expected_second_topic = - rosbag2_storage::TopicInformation{{"topic2", "type2", "rmw2", {}, ""}, 200}; + rosbag2_storage::TopicInformation{{0u, "topic2", "type2", "rmw2", {}, ""}, 200}; EXPECT_EQ(actual_second_topic.topic_metadata, expected_second_topic.topic_metadata); EXPECT_EQ(actual_second_topic.message_count, expected_second_topic.message_count); @@ -262,7 +262,7 @@ TEST_P( EXPECT_THAT(read_metadata.topics_with_message_count, SizeIs(2u)); auto actual_first_topic = read_metadata.topics_with_message_count[0]; rosbag2_storage::TopicInformation expected_first_topic = - {{"topic1", "type1", "rmw1", {}, ""}, 100}; + {{0u, "topic1", "type1", "rmw1", {}, ""}, 100}; EXPECT_THAT( actual_first_topic.topic_metadata.name, Eq(expected_first_topic.topic_metadata.name)); @@ -275,7 +275,7 @@ TEST_P( EXPECT_THAT(actual_first_topic.message_count, Eq(expected_first_topic.message_count)); auto actual_second_topic = read_metadata.topics_with_message_count[1]; rosbag2_storage::TopicInformation expected_second_topic = - {{"topic2", "type2", "rmw2", {}, ""}, 200}; + {{0u, "topic2", "type2", "rmw2", {}, ""}, 200}; EXPECT_THAT( actual_second_topic.topic_metadata.name, Eq(expected_second_topic.topic_metadata.name)); diff --git a/rosbag2_cpp/test/rosbag2_cpp/test_multifile_reader.cpp b/rosbag2_cpp/test/rosbag2_cpp/test_multifile_reader.cpp index 6537ec6004..3e41c43621 100644 --- a/rosbag2_cpp/test/rosbag2_cpp/test_multifile_reader.cpp +++ b/rosbag2_cpp/test/rosbag2_cpp/test_multifile_reader.cpp @@ -53,7 +53,7 @@ class MultifileReaderTest : public Test auto metadata = get_metadata(); auto topic_with_type = rosbag2_storage::TopicMetadata{ - "topic", "test_msgs/BasicTypes", storage_serialization_format_, {}, ""}; + 0u, "topic", "test_msgs/BasicTypes", storage_serialization_format_, {}, ""}; auto topics_and_types = std::vector{topic_with_type}; metadata.topics_with_message_count.push_back({topic_with_type, 10}); diff --git a/rosbag2_cpp/test/rosbag2_cpp/test_sequential_writer.cpp b/rosbag2_cpp/test/rosbag2_cpp/test_sequential_writer.cpp index 41871b1ee1..cb27d87cab 100644 --- a/rosbag2_cpp/test/rosbag2_cpp/test_sequential_writer.cpp +++ b/rosbag2_cpp/test/rosbag2_cpp/test_sequential_writer.cpp @@ -130,7 +130,7 @@ TEST_F( auto message = std::make_shared(); message->topic_name = "test_topic"; writer_->open(storage_options_, {input_format, storage_serialization_format}); - writer_->create_topic({"test_topic", "test_msgs/BasicTypes", "", {}, ""}); + writer_->create_topic({0u, "test_topic", "test_msgs/BasicTypes", "", {}, ""}); writer_->write(message); } @@ -147,7 +147,7 @@ TEST_F(SequentialWriterTest, write_does_not_use_converters_if_input_and_output_f auto message = std::make_shared(); message->topic_name = "test_topic"; writer_->open(storage_options_, {storage_serialization_format, storage_serialization_format}); - writer_->create_topic({"test_topic", "test_msgs/BasicTypes", "", {}, ""}); + writer_->create_topic({0u, "test_topic", "test_msgs/BasicTypes", "", {}, ""}); writer_->write(message); } @@ -175,7 +175,7 @@ TEST_F(SequentialWriterTest, sequantial_writer_call_metadata_update_on_open_and_ std::string rmw_format = "rmw_format"; writer_->open(storage_options_, {rmw_format, rmw_format}); - writer_->create_topic({test_topic_name, test_topic_type, "", {}, ""}); + writer_->create_topic({0u, test_topic_name, test_topic_type, "", {}, ""}); auto message = std::make_shared(); message->topic_name = test_topic_name; @@ -204,7 +204,7 @@ TEST_F(SequentialWriterTest, sequantial_writer_call_metadata_update_on_bag_split std::string rmw_format = "rmw_format"; writer_->open(storage_options_, {rmw_format, rmw_format}); - writer_->create_topic({test_topic_name, test_topic_type, "", {}, ""}); + writer_->create_topic({0u, test_topic_name, test_topic_type, "", {}, ""}); auto message = std::make_shared(); message->topic_name = test_topic_name; @@ -283,7 +283,7 @@ TEST_F(SequentialWriterTest, bagfile_size_is_checked_on_every_write) { storage_options_.max_bagfile_size = max_bagfile_size; writer_->open(storage_options_, {rmw_format, rmw_format}); - writer_->create_topic({"test_topic", "test_msgs/BasicTypes", "", {}, ""}); + writer_->create_topic({0u, "test_topic", "test_msgs/BasicTypes", "", {}, ""}); for (auto i = 0; i < counter; ++i) { writer_->write(message); @@ -333,7 +333,7 @@ TEST_F(SequentialWriterTest, writer_splits_when_storage_bagfile_size_gt_max_bagf storage_options_.max_bagfile_size = max_bagfile_size; writer_->open(storage_options_, {rmw_format, rmw_format}); - writer_->create_topic({"test_topic", "test_msgs/BasicTypes", "", {}, ""}); + writer_->create_topic({0u, "test_topic", "test_msgs/BasicTypes", "", {}, ""}); for (auto i = 0; i < message_count; ++i) { writer_->write(message); @@ -411,7 +411,7 @@ TEST_F( storage_options_.snapshot_mode = false; writer_->open(storage_options_, {rmw_format, rmw_format}); - writer_->create_topic({"test_topic", "test_msgs/BasicTypes", "", {}, ""}); + writer_->create_topic({0u, "test_topic", "test_msgs/BasicTypes", "", {}, ""}); auto timeout = std::chrono::seconds(2); for (auto i = 1u; i < message_count; ++i) { @@ -491,7 +491,7 @@ TEST_F(SequentialWriterTest, do_not_use_cache_if_cache_size_is_zero) { storage_options_.max_cache_size = max_cache_size; writer_->open(storage_options_, {rmw_format, rmw_format}); - writer_->create_topic({"test_topic", "test_msgs/BasicTypes", "", {}, ""}); + writer_->create_topic({0u, "test_topic", "test_msgs/BasicTypes", "", {}, ""}); for (auto i = 0u; i < counter; ++i) { writer_->write(message); @@ -525,7 +525,7 @@ TEST_F(SequentialWriterTest, snapshot_mode_write_on_trigger) msg_content.c_str(), msg_length); writer_->open(storage_options_, {rmw_format, rmw_format}); - writer_->create_topic({"test_topic", "test_msgs/BasicTypes", "", {}, ""}); + writer_->create_topic({0u, "test_topic", "test_msgs/BasicTypes", "", {}, ""}); for (auto i = 0u; i < 100; ++i) { writer_->write(message); @@ -561,7 +561,7 @@ TEST_F(SequentialWriterTest, snapshot_mode_not_triggered_no_storage_write) msg_content.c_str(), msg_length); writer_->open(storage_options_, {rmw_format, rmw_format}); - writer_->create_topic({"test_topic", "test_msgs/BasicTypes", "", {}, ""}); + writer_->create_topic({0u, "test_topic", "test_msgs/BasicTypes", "", {}, ""}); for (auto i = 0u; i < 100; ++i) { writer_->write(message); @@ -630,7 +630,7 @@ TEST_F(SequentialWriterTest, split_event_calls_callback) writer_->add_event_callbacks(callbacks); writer_->open(storage_options_, {"rmw_format", "rmw_format"}); - writer_->create_topic({"test_topic", "test_msgs/BasicTypes", "", {}, ""}); + writer_->create_topic({0u, "test_topic", "test_msgs/BasicTypes", "", {}, ""}); for (auto i = 0; i < message_count; ++i) { writer_->write(message); @@ -689,7 +689,7 @@ TEST_F(SequentialWriterTest, split_event_calls_on_writer_close) writer_->add_event_callbacks(callbacks); writer_->open(storage_options_, {"rmw_format", "rmw_format"}); - writer_->create_topic({"test_topic", "test_msgs/BasicTypes", "", {}, ""}); + writer_->create_topic({0u, "test_topic", "test_msgs/BasicTypes", "", {}, ""}); for (auto i = 0; i < message_count; ++i) { writer_->write(message); diff --git a/rosbag2_cpp/test/rosbag2_cpp/test_storage_without_metadata_file.cpp b/rosbag2_cpp/test/rosbag2_cpp/test_storage_without_metadata_file.cpp index e605403df8..8b8ace9d3d 100644 --- a/rosbag2_cpp/test/rosbag2_cpp/test_storage_without_metadata_file.cpp +++ b/rosbag2_cpp/test/rosbag2_cpp/test_storage_without_metadata_file.cpp @@ -52,18 +52,10 @@ class StorageWithoutMetadataFileTest : public Test TEST_F(StorageWithoutMetadataFileTest, open_uses_storage_id_from_storage_options) { { - auto topic_with_type = rosbag2_storage::TopicMetadata{ - "topic", - "test_msgs/BasicTypes", - kRmwFormat, - {}, - "" - }; - - auto topic_information = rosbag2_storage::TopicInformation{ - topic_with_type, - 1 - }; + auto topic_with_type = + rosbag2_storage::TopicMetadata{0u, "topic", "test_msgs/BasicTypes", kRmwFormat, {}, ""}; + + auto topic_information = rosbag2_storage::TopicInformation{topic_with_type, 1}; rosbag2_storage::BagMetadata metadata; metadata.relative_file_paths = {"TestPath"}; diff --git a/rosbag2_examples/rosbag2_examples_cpp/src/data_generator_executable.cpp b/rosbag2_examples/rosbag2_examples_cpp/src/data_generator_executable.cpp index 0e00134d2f..06b07df169 100644 --- a/rosbag2_examples/rosbag2_examples_cpp/src/data_generator_executable.cpp +++ b/rosbag2_examples/rosbag2_examples_cpp/src/data_generator_executable.cpp @@ -34,6 +34,7 @@ int main(int, char **) writer_->create_topic( { + 0u, "synthetic", "example_interfaces/msg/Int32", rmw_get_serialization_format(), diff --git a/rosbag2_examples/rosbag2_examples_cpp/src/data_generator_node.cpp b/rosbag2_examples/rosbag2_examples_cpp/src/data_generator_node.cpp index 787995fc28..049ea70d29 100644 --- a/rosbag2_examples/rosbag2_examples_cpp/src/data_generator_node.cpp +++ b/rosbag2_examples/rosbag2_examples_cpp/src/data_generator_node.cpp @@ -35,6 +35,7 @@ class DataGenerator : public rclcpp::Node writer_->create_topic( { + 0u, "synthetic", "example_interfaces/msg/Int32", rmw_get_serialization_format(), diff --git a/rosbag2_examples/rosbag2_examples_py/rosbag2_examples_py/data_generator_executable.py b/rosbag2_examples/rosbag2_examples_py/rosbag2_examples_py/data_generator_executable.py index 1b9fe5df0c..df1de00840 100644 --- a/rosbag2_examples/rosbag2_examples_py/rosbag2_examples_py/data_generator_executable.py +++ b/rosbag2_examples/rosbag2_examples_py/rosbag2_examples_py/data_generator_executable.py @@ -28,6 +28,7 @@ def main(args=None): writer.open(storage_options, converter_options) topic_info = rosbag2_py._storage.TopicMetadata( + id=0, name='synthetic', type='example_interfaces/msg/Int32', serialization_format='cdr') diff --git a/rosbag2_examples/rosbag2_examples_py/rosbag2_examples_py/data_generator_node.py b/rosbag2_examples/rosbag2_examples_py/rosbag2_examples_py/data_generator_node.py index 6c006f85f5..d6f8c5a4df 100644 --- a/rosbag2_examples/rosbag2_examples_py/rosbag2_examples_py/data_generator_node.py +++ b/rosbag2_examples/rosbag2_examples_py/rosbag2_examples_py/data_generator_node.py @@ -33,6 +33,7 @@ def __init__(self): self.writer.open(storage_options, converter_options) topic_info = rosbag2_py._storage.TopicMetadata( + id=0, name='synthetic', type='example_interfaces/msg/Int32', serialization_format='cdr') diff --git a/rosbag2_examples/rosbag2_examples_py/rosbag2_examples_py/simple_bag_recorder.py b/rosbag2_examples/rosbag2_examples_py/rosbag2_examples_py/simple_bag_recorder.py index 451f6d306a..7890d69887 100644 --- a/rosbag2_examples/rosbag2_examples_py/rosbag2_examples_py/simple_bag_recorder.py +++ b/rosbag2_examples/rosbag2_examples_py/rosbag2_examples_py/simple_bag_recorder.py @@ -31,6 +31,7 @@ def __init__(self): self.writer.open(storage_options, converter_options) topic_info = rosbag2_py._storage.TopicMetadata( + id=0, name='chatter', type='std_msgs/msg/String', serialization_format='cdr') diff --git a/rosbag2_py/src/rosbag2_py/_storage.cpp b/rosbag2_py/src/rosbag2_py/_storage.cpp index db0c150db3..6e794e89fb 100644 --- a/rosbag2_py/src/rosbag2_py/_storage.cpp +++ b/rosbag2_py/src/rosbag2_py/_storage.cpp @@ -209,12 +209,15 @@ PYBIND11_MODULE(_storage, m) { pybind11::class_(m, "TopicMetadata") .def( - pybind11::init, std::string>(), + pybind11::init, + std::string>(), + pybind11::arg("id"), pybind11::arg("name"), pybind11::arg("type"), pybind11::arg("serialization_format"), pybind11::arg("offered_qos_profiles") = std::vector(), pybind11::arg("type_description_hash") = "") + .def_readwrite("id", &rosbag2_storage::TopicMetadata::id) .def_readwrite("name", &rosbag2_storage::TopicMetadata::name) .def_readwrite("type", &rosbag2_storage::TopicMetadata::type) .def_readwrite( diff --git a/rosbag2_py/test/test_compression.py b/rosbag2_py/test/test_compression.py index 4deaa9b1af..b4b2ac627f 100644 --- a/rosbag2_py/test/test_compression.py +++ b/rosbag2_py/test/test_compression.py @@ -82,6 +82,7 @@ def test_sequential_compression(tmp_path, storage_id): topic_name = '/chatter' topic_metadata = TopicMetadata( + id=0, name=topic_name, type='std_msgs/msg/String', serialization_format='cdr') diff --git a/rosbag2_py/test/test_sequential_writer.py b/rosbag2_py/test/test_sequential_writer.py index 5d585ad982..e35b38b7bd 100644 --- a/rosbag2_py/test/test_sequential_writer.py +++ b/rosbag2_py/test/test_sequential_writer.py @@ -34,7 +34,7 @@ def create_topic(writer, topic_name, topic_type, serialization_format='cdr'): :return: """ topic_name = topic_name - topic = rosbag2_py.TopicMetadata(name=topic_name, type=topic_type, + topic = rosbag2_py.TopicMetadata(id=0, name=topic_name, type=topic_type, serialization_format=serialization_format) writer.create_topic(topic) diff --git a/rosbag2_py/test/test_storage.py b/rosbag2_py/test/test_storage.py index 39c6995b05..2b805e112f 100644 --- a/rosbag2_py/test/test_storage.py +++ b/rosbag2_py/test/test_storage.py @@ -58,6 +58,7 @@ def test_storage_filter_ctor(self): def test_topic_metadata_ctor(self): topic_metadata = TopicMetadata( + id=0, name='topic', type='msgs/Msg', serialization_format='format' @@ -67,6 +68,7 @@ def test_topic_metadata_ctor(self): def test_topic_information_ctor(self): topic_information = TopicInformation( topic_metadata=TopicMetadata( + id=0, name='topic', type='msgs/Msg', serialization_format='format'), @@ -85,6 +87,7 @@ def test_bag_metadata_ctor_named_args(self): message_count=12) topic_information = TopicInformation( topic_metadata=TopicMetadata( + id=0, name='topic', type='msgs/Msg', serialization_format='format'), diff --git a/rosbag2_storage/include/rosbag2_storage/topic_metadata.hpp b/rosbag2_storage/include/rosbag2_storage/topic_metadata.hpp index fec92b6127..abad1f31e4 100644 --- a/rosbag2_storage/include/rosbag2_storage/topic_metadata.hpp +++ b/rosbag2_storage/include/rosbag2_storage/topic_metadata.hpp @@ -24,6 +24,7 @@ namespace rosbag2_storage struct TopicMetadata { + uint16_t id = 0; // Topic id returned by storage std::string name; std::string type; std::string serialization_format; @@ -33,7 +34,8 @@ struct TopicMetadata bool operator==(const rosbag2_storage::TopicMetadata & rhs) const { - return name == rhs.name && + return id == rhs.id && + name == rhs.name && type == rhs.type && serialization_format == rhs.serialization_format && type_description_hash == rhs.type_description_hash; diff --git a/rosbag2_storage/test/rosbag2_storage/test_metadata_serialization.cpp b/rosbag2_storage/test/rosbag2_storage/test_metadata_serialization.cpp index 277f6e18b6..c43daefeda 100644 --- a/rosbag2_storage/test/rosbag2_storage/test_metadata_serialization.cpp +++ b/rosbag2_storage/test/rosbag2_storage/test_metadata_serialization.cpp @@ -54,8 +54,8 @@ TEST_F(MetadataFixture, test_writing_and_reading_yaml) metadata.starting_time = std::chrono::time_point(std::chrono::nanoseconds(1000000)); metadata.message_count = 50; - metadata.topics_with_message_count.push_back({{"topic1", "type1", "rmw1", {}, ""}, 100}); - metadata.topics_with_message_count.push_back({{"topic2", "type2", "rmw2", {}, ""}, 200}); + metadata.topics_with_message_count.push_back({{0u, "topic1", "type1", "rmw1", {}, ""}, 100}); + metadata.topics_with_message_count.push_back({{0u, "topic2", "type2", "rmw2", {}, ""}, 200}); metadata_io_->write_metadata(temporary_dir_path_, metadata); auto read_metadata = metadata_io_->read_metadata(temporary_dir_path_); @@ -106,7 +106,7 @@ TEST_F(MetadataFixture, metadata_reads_v3_check_offered_qos_profiles_empty) BagMetadata metadata{}; metadata.version = 3; metadata.topics_with_message_count.push_back( - {{"topic", "type", "rmw", offered_qos_profiles, ""}, message_count}); + {{0u, "topic", "type", "rmw", offered_qos_profiles, ""}, message_count}); metadata_io_->write_metadata(temporary_dir_path_, metadata); auto read_metadata = metadata_io_->read_metadata(temporary_dir_path_); ASSERT_THAT( @@ -126,7 +126,7 @@ TEST_F(MetadataFixture, metadata_reads_v4_fills_offered_qos_profiles) BagMetadata metadata{}; metadata.version = 4; metadata.topics_with_message_count.push_back( - {{"topic", "type", "rmw", offered_qos_profiles, ""}, message_count}); + {{0u, "topic", "type", "rmw", offered_qos_profiles, ""}, message_count}); metadata_io_->write_metadata(temporary_dir_path_, metadata); auto read_metadata = metadata_io_->read_metadata(temporary_dir_path_); ASSERT_THAT( @@ -156,7 +156,7 @@ TEST_F(MetadataFixture, metadata_reads_v7_topic_type_hash) BagMetadata metadata{}; metadata.version = 7; metadata.topics_with_message_count.push_back( - {{"topic", "type", "rmw", {rclcpp::QoS(1)}, type_description_hash}, 1}); + {{0u, "topic", "type", "rmw", {rclcpp::QoS(1)}, type_description_hash}, 1}); metadata_io_->write_metadata(temporary_dir_path_, metadata); auto read_metadata = metadata_io_->read_metadata(temporary_dir_path_); diff --git a/rosbag2_storage_mcap/src/mcap_storage.cpp b/rosbag2_storage_mcap/src/mcap_storage.cpp index 4fe6895b22..bb56ab8e1b 100644 --- a/rosbag2_storage_mcap/src/mcap_storage.cpp +++ b/rosbag2_storage_mcap/src/mcap_storage.cpp @@ -441,6 +441,7 @@ void MCAPStorage::read_metadata() // Create a TopicInformation for this topic rosbag2_storage::TopicInformation topic_info{}; + topic_info.topic_metadata.id = channel.id; topic_info.topic_metadata.name = channel.topic; topic_info.topic_metadata.serialization_format = channel.messageEncoding; topic_info.topic_metadata.type = schema_ptr->name; diff --git a/rosbag2_storage_mcap/test/rosbag2_storage_mcap/test_mcap_storage.cpp b/rosbag2_storage_mcap/test/rosbag2_storage_mcap/test_mcap_storage.cpp index 719546d887..55f90657e5 100644 --- a/rosbag2_storage_mcap/test/rosbag2_storage_mcap/test_mcap_storage.cpp +++ b/rosbag2_storage_mcap/test/rosbag2_storage_mcap/test_mcap_storage.cpp @@ -96,10 +96,10 @@ TEST_F(McapStorageTestFixture, can_store_and_read_metadata_correctly) std::vector string_messages = {"first message", "second message", "third message"}; std::vector topics = {"topic1", "topic2"}; - rosbag2_storage::TopicMetadata topic_metadata_1 = { - topics[0], "std_msgs/msg/String", "cdr", {rclcpp::QoS(1)}, "type_hash1"}; - rosbag2_storage::TopicMetadata topic_metadata_2 = { - topics[1], "std_msgs/msg/String", "cdr", {rclcpp::QoS(2)}, "type_hash2"}; + rosbag2_storage::TopicMetadata topic_metadata_1 = {0, topics[0], "std_msgs/msg/String", + "cdr", {rclcpp::QoS(1)}, "type_hash1"}; + rosbag2_storage::TopicMetadata topic_metadata_2 = {0, topics[1], "std_msgs/msg/String", + "cdr", {rclcpp::QoS(2)}, "type_hash2"}; std::vector> @@ -116,8 +116,8 @@ TEST_F(McapStorageTestFixture, can_store_and_read_metadata_correctly) { auto writer = factory.open_read_write(options); - writer->create_topic({"topic1", "type1", "rmw1", {rclcpp::QoS(1)}, "type_hash1"}, {}); - writer->create_topic({"topic2", "type2", "rmw2", {rclcpp::QoS(2)}, "type_hash2"}, {}); + writer->create_topic({0u, "topic1", "type1", "rmw1", {rclcpp::QoS(1)}, "type_hash1"}, {}); + writer->create_topic({0u, "topic2", "type2", "rmw2", {rclcpp::QoS(2)}, "type_hash2"}, {}); (void)write_messages_to_mcap(messages, writer); auto metadata = writer->get_metadata(); metadata.ros_distro = "rolling"; @@ -133,16 +133,17 @@ TEST_F(McapStorageTestFixture, can_store_and_read_metadata_correctly) EXPECT_THAT(metadata.storage_identifier, Eq("mcap")); EXPECT_THAT(metadata.relative_file_paths, ElementsAreArray({expected_bag.generic_string()})); - EXPECT_THAT( - metadata.topics_with_message_count, - UnorderedElementsAreArray({ - rosbag2_storage::TopicInformation{ - rosbag2_storage::TopicMetadata{"topic2", "type2", "rmw2", {rclcpp::QoS(2)}, "type_hash2"}, - 1u}, - rosbag2_storage::TopicInformation{ - rosbag2_storage::TopicMetadata{"topic1", "type1", "rmw1", {rclcpp::QoS(1)}, "type_hash1"}, - 2u}, - })); + EXPECT_THAT(metadata.topics_with_message_count, + UnorderedElementsAreArray({ + rosbag2_storage::TopicInformation{ + rosbag2_storage::TopicMetadata{ + 2u, "topic2", "type2", "rmw2", {rclcpp::QoS(2)}, "type_hash2"}, + 1u}, + rosbag2_storage::TopicInformation{ + rosbag2_storage::TopicMetadata{ + 1u, "topic1", "type1", "rmw1", {rclcpp::QoS(1)}, "type_hash1"}, + 2u}, + })); EXPECT_THAT(metadata.message_count, Eq(3u)); const auto current_distro = "rolling"; @@ -225,7 +226,7 @@ TEST_F(TemporaryDirectoryFixture, can_write_and_read_basic_mcap_file) EXPECT_THAT(topics_and_types, ElementsAreArray({rosbag2_storage::TopicMetadata{ - topic_name, "std_msgs/msg/String", "cdr", {rclcpp::QoS(1)}, "type_hash1"}})); + 1u, topic_name, "std_msgs/msg/String", "cdr", {rclcpp::QoS(1)}, "type_hash1"}})); const auto metadata = reader->get_metadata(); @@ -234,7 +235,7 @@ TEST_F(TemporaryDirectoryFixture, can_write_and_read_basic_mcap_file) EXPECT_THAT(metadata.topics_with_message_count, ElementsAreArray({rosbag2_storage::TopicInformation{ rosbag2_storage::TopicMetadata{ - topic_name, "std_msgs/msg/String", "cdr", {rclcpp::QoS(1)}, "type_hash1"}, + 1u, topic_name, "std_msgs/msg/String", "cdr", {rclcpp::QoS(1)}, "type_hash1"}, 1u}})); EXPECT_THAT(metadata.message_count, Eq(1u)); diff --git a/rosbag2_storage_sqlite3/include/rosbag2_storage_sqlite3/sqlite_statement_wrapper.hpp b/rosbag2_storage_sqlite3/include/rosbag2_storage_sqlite3/sqlite_statement_wrapper.hpp index c01ec88d4c..b9b0be1087 100644 --- a/rosbag2_storage_sqlite3/include/rosbag2_storage_sqlite3/sqlite_statement_wrapper.hpp +++ b/rosbag2_storage_sqlite3/include/rosbag2_storage_sqlite3/sqlite_statement_wrapper.hpp @@ -202,7 +202,7 @@ class ROSBAG2_STORAGE_DEFAULT_PLUGINS_PUBLIC SqliteStatementWrapper bool is_query_ok(int return_code); void obtain_column_value(size_t index, int & value) const; - void obtain_column_value(size_t index, rcutils_time_point_value_t & value) const; + void obtain_column_value(size_t index, int64_t & value) const; void obtain_column_value(size_t index, double & value) const; void obtain_column_value(size_t index, std::string & value) const; void obtain_column_value(size_t index, std::shared_ptr & value) const; diff --git a/rosbag2_storage_sqlite3/include/rosbag2_storage_sqlite3/sqlite_storage.hpp b/rosbag2_storage_sqlite3/include/rosbag2_storage_sqlite3/sqlite_storage.hpp index 8d6c808836..7908e4f109 100644 --- a/rosbag2_storage_sqlite3/include/rosbag2_storage_sqlite3/sqlite_storage.hpp +++ b/rosbag2_storage_sqlite3/include/rosbag2_storage_sqlite3/sqlite_storage.hpp @@ -115,6 +115,10 @@ class ROSBAG2_STORAGE_DEFAULT_PLUGINS_PUBLIC SqliteStorage private: void initialize(); + void add_topic_to_metadata( + int64_t inner_topic_id, std::string topic_name, std::string topic_type, std::string ser_format, + int64_t msg_count, const std::string & offered_qos_profiles_str, + const std::string & type_hash); void read_metadata(); void prepare_for_writing(); void prepare_for_reading(); @@ -127,6 +131,8 @@ class ROSBAG2_STORAGE_DEFAULT_PLUGINS_PUBLIC SqliteStorage int read_db_schema_version(); uint64_t get_page_size() const; uint64_t read_total_page_count_locked() const RCPPUTILS_TSA_REQUIRES(db_read_write_mutex_); + uint16_t get_extern_topic_id(int64_t inner_topic_id) const; + uint16_t get_or_generate_extern_topic_id(int64_t inner_topic_id); using ReadQueryResult = SqliteStatementWrapper::QueryResult< std::shared_ptr, rcutils_time_point_value_t, std::string, int>; @@ -138,9 +144,11 @@ class ROSBAG2_STORAGE_DEFAULT_PLUGINS_PUBLIC SqliteStorage ReadQueryResult message_result_ {nullptr}; ReadQueryResult::Iterator current_message_row_ { nullptr, SqliteStatementWrapper::QueryResult<>::Iterator::POSITION_END}; - std::unordered_map topics_ RCPPUTILS_TSA_GUARDED_BY(db_read_write_mutex_); - std::unordered_map msg_definitions_ RCPPUTILS_TSA_GUARDED_BY( + std::unordered_map topics_ RCPPUTILS_TSA_GUARDED_BY(db_read_write_mutex_); + std::unordered_map msg_definitions_ RCPPUTILS_TSA_GUARDED_BY( db_read_write_mutex_); + std::unordered_map inner_to_extern_topic_id_map_; + std::atomic last_extern_topic_id_{0}; // 0 corresponds to the invalid topic_id std::vector all_topics_and_types_; std::string relative_path_; std::atomic_bool active_transaction_ {false}; diff --git a/rosbag2_storage_sqlite3/include/rosbag2_storage_sqlite3/sqlite_wrapper.hpp b/rosbag2_storage_sqlite3/include/rosbag2_storage_sqlite3/sqlite_wrapper.hpp index 583c9d0117..30e8561b54 100644 --- a/rosbag2_storage_sqlite3/include/rosbag2_storage_sqlite3/sqlite_wrapper.hpp +++ b/rosbag2_storage_sqlite3/include/rosbag2_storage_sqlite3/sqlite_wrapper.hpp @@ -50,7 +50,7 @@ class ROSBAG2_STORAGE_DEFAULT_PLUGINS_PUBLIC SqliteWrapper SqliteStatement prepare_statement(const std::string & query); std::string query_pragma_value(const std::string & key); - size_t get_last_insert_id(); + int64_t get_last_insert_id(); operator bool(); diff --git a/rosbag2_storage_sqlite3/src/rosbag2_storage_sqlite3/sqlite_statement_wrapper.cpp b/rosbag2_storage_sqlite3/src/rosbag2_storage_sqlite3/sqlite_statement_wrapper.cpp index 6bd816ace1..7b12256838 100644 --- a/rosbag2_storage_sqlite3/src/rosbag2_storage_sqlite3/sqlite_statement_wrapper.cpp +++ b/rosbag2_storage_sqlite3/src/rosbag2_storage_sqlite3/sqlite_statement_wrapper.cpp @@ -156,8 +156,7 @@ void SqliteStatementWrapper::obtain_column_value(size_t index, int & value) cons value = sqlite3_column_int(statement_, static_cast(index)); } -void -SqliteStatementWrapper::obtain_column_value(size_t index, rcutils_time_point_value_t & value) const +void SqliteStatementWrapper::obtain_column_value(size_t index, int64_t & value) const { value = sqlite3_column_int64(statement_, static_cast(index)); } diff --git a/rosbag2_storage_sqlite3/src/rosbag2_storage_sqlite3/sqlite_storage.cpp b/rosbag2_storage_sqlite3/src/rosbag2_storage_sqlite3/sqlite_storage.cpp index bf8d012084..f4a1e0179e 100644 --- a/rosbag2_storage_sqlite3/src/rosbag2_storage_sqlite3/sqlite_storage.cpp +++ b/rosbag2_storage_sqlite3/src/rosbag2_storage_sqlite3/sqlite_storage.cpp @@ -611,48 +611,51 @@ void SqliteStorage::fill_topics_and_types() if (database_->field_exists("topics", "offered_qos_profiles")) { if (database_->field_exists("topics", "type_description_hash")) { auto statement = database_->prepare_statement( - "SELECT name, type, serialization_format, offered_qos_profiles, type_description_hash" + "SELECT id, name, type, serialization_format, offered_qos_profiles, type_description_hash" " FROM topics ORDER BY id;"); auto query_results = statement->execute_query< - std::string, std::string, std::string, std::string, std::string>(); + int64_t, std::string, std::string, std::string, std::string, std::string>(); - for (auto result : query_results) { + for (const auto & [inner_topic_id, topic_name, topic_type, ser_format, + offered_qos_profiles_str, type_hash] : query_results) + { auto offered_qos_profiles = rosbag2_storage::to_rclcpp_qos_vector( // Before db_schema_version_ = 3 we didn't store metadata in the database and real // metadata_.version will be lower than 9 - std::get<3>(result), (db_schema_version_ >= 3) ? metadata_.version : 8); + offered_qos_profiles_str, (db_schema_version_ >= 3) ? metadata_.version : 8); all_topics_and_types_.push_back( - { - std::get<0>(result), - std::get<1>(result), - std::get<2>(result), - offered_qos_profiles, - std::get<4>(result)}); + {get_or_generate_extern_topic_id(inner_topic_id), topic_name, topic_type, ser_format, + offered_qos_profiles, type_hash}); } - } else { + } else { // Without type_hash auto statement = database_->prepare_statement( - "SELECT name, type, serialization_format, offered_qos_profiles FROM topics ORDER BY id;"); + "SELECT id, name, type, serialization_format, offered_qos_profiles FROM topics " + "ORDER BY id;"); auto query_results = statement->execute_query< - std::string, std::string, std::string, std::string>(); + int64_t, std::string, std::string, std::string, std::string>(); - for (auto result : query_results) { + for (const auto & [inner_topic_id, topic_name, topic_type, ser_format, + offered_qos_profiles_str] : query_results) + { auto offered_qos_profiles = rosbag2_storage::to_rclcpp_qos_vector( // Before db_schema_version_ = 3 we didn't store metadata in the database and real // metadata_.version will be lower than 9 - std::get<3>(result), (db_schema_version_ >= 3) ? metadata_.version : 8); + offered_qos_profiles_str, (db_schema_version_ >= 3) ? metadata_.version : 8); all_topics_and_types_.push_back( - {std::get<0>(result), std::get<1>(result), std::get<2>(result), offered_qos_profiles, - ""}); + {get_or_generate_extern_topic_id(inner_topic_id), topic_name, topic_type, ser_format, + offered_qos_profiles, ""}); } } - } else { + } else { // No offered_qos_profiles and no type_hash auto statement = database_->prepare_statement( - "SELECT name, type, serialization_format FROM topics ORDER BY id;"); - auto query_results = statement->execute_query(); + "SELECT id, name, type, serialization_format FROM topics ORDER BY id;"); + auto query_results = + statement->execute_query(); - for (auto result : query_results) { + for (const auto & [inner_topic_id, topic_name, topic_type, ser_format] : query_results) { all_topics_and_types_.push_back( - {std::get<0>(result), std::get<1>(result), std::get<2>(result), {}, ""}); + {get_or_generate_extern_topic_id(inner_topic_id), topic_name, topic_type, ser_format, + {}, ""}); } } } @@ -672,6 +675,26 @@ uint64_t SqliteStorage::get_minimum_split_file_size() const return MIN_SPLIT_FILE_SIZE; } +void SqliteStorage::add_topic_to_metadata( + int64_t inner_topic_id, std::string topic_name, std::string topic_type, std::string ser_format, + int64_t msg_count, const std::string & offered_qos_profiles_str, const std::string & type_hash) +{ + auto offered_qos_profiles = rosbag2_storage::to_rclcpp_qos_vector( + // Before db_schema_version_ = 3 we didn't store metadata in the database and real + // metadata_.version will be lower than 9 + offered_qos_profiles_str, (db_schema_version_ >= 3) ? metadata_.version : 8); + metadata_.topics_with_message_count.push_back( + { + { + get_or_generate_extern_topic_id(inner_topic_id), topic_name, topic_type, ser_format, + offered_qos_profiles, type_hash + }, + static_cast(msg_count) + }); + + metadata_.message_count += msg_count; +} + void SqliteStorage::read_metadata() { std::vector metadata_from_table; @@ -705,83 +728,67 @@ void SqliteStorage::read_metadata() if (database_->field_exists("topics", "offered_qos_profiles")) { if (database_->field_exists("topics", "type_description_hash")) { std::string query = - "SELECT name, type, serialization_format, COUNT(messages.id), MIN(messages.timestamp), " - "MAX(messages.timestamp), offered_qos_profiles, type_description_hash " - "FROM messages JOIN topics on topics.id = messages.topic_id " + "SELECT messages.topic_id, name, type, serialization_format, COUNT(messages.id), " + "MIN(messages.timestamp), MAX(messages.timestamp), offered_qos_profiles, " + "type_description_hash FROM messages JOIN topics on topics.id = messages.topic_id " "GROUP BY topics.name;"; auto statement = database_->prepare_statement(query); auto query_results = statement->execute_query< - std::string, std::string, std::string, int, rcutils_time_point_value_t, + int64_t, std::string, std::string, std::string, int64_t, rcutils_time_point_value_t, rcutils_time_point_value_t, std::string, std::string>(); - for (auto result : query_results) { - auto offered_qos_profiles = rosbag2_storage::to_rclcpp_qos_vector( - // Before db_schema_version_ = 3 we didn't store metadata in the database and real - // metadata_.version will be lower than 9 - std::get<6>(result), (db_schema_version_ >= 3) ? metadata_.version : 8); - metadata_.topics_with_message_count.push_back( - { - {std::get<0>(result), std::get<1>(result), std::get<2>( - result), offered_qos_profiles, std::get<7>(result)}, - static_cast(std::get<3>(result)) - }); - - metadata_.message_count += std::get<3>(result); - min_time = std::get<4>(result) < min_time ? std::get<4>(result) : min_time; - max_time = std::get<5>(result) > max_time ? std::get<5>(result) : max_time; + for (const auto & [inner_topic_id, topic_name, topic_type, ser_format, msg_count, + min_recv_timestamp, max_recv_timestamp, offered_qos_profiles_str, type_hash] : + query_results) + { + add_topic_to_metadata( + inner_topic_id, topic_name, topic_type, ser_format, msg_count, + offered_qos_profiles_str, type_hash); + + min_time = min_recv_timestamp < min_time ? min_recv_timestamp : min_time; + max_time = max_recv_timestamp > max_time ? max_recv_timestamp : max_time; } - } else { + } else { // Without type_hash std::string query = - "SELECT name, type, serialization_format, COUNT(messages.id), MIN(messages.timestamp), " - "MAX(messages.timestamp), offered_qos_profiles " + "SELECT messages.topic_id, name, type, serialization_format, COUNT(messages.id), " + "MIN(messages.timestamp), MAX(messages.timestamp), offered_qos_profiles " "FROM messages JOIN topics on topics.id = messages.topic_id " "GROUP BY topics.name;"; auto statement = database_->prepare_statement(query); - auto query_results = statement->execute_query< - std::string, std::string, std::string, int, rcutils_time_point_value_t, - rcutils_time_point_value_t, std::string>(); - - for (auto result : query_results) { - auto offered_qos_profiles = rosbag2_storage::to_rclcpp_qos_vector( - // Before db_schema_version_ = 3 we didn't store metadata in the database and real - // metadata_.version will be lower than 9 - std::get<6>(result), (db_schema_version_ >= 3) ? metadata_.version : 8); - metadata_.topics_with_message_count.push_back( - { - {std::get<0>(result), std::get<1>(result), std::get<2>( - result), offered_qos_profiles, ""}, - static_cast(std::get<3>(result)) - }); - - metadata_.message_count += std::get<3>(result); - min_time = std::get<4>(result) < min_time ? std::get<4>(result) : min_time; - max_time = std::get<5>(result) > max_time ? std::get<5>(result) : max_time; + auto query_results = + statement->execute_query(); + + for (const auto & [inner_topic_id, topic_name, topic_type, ser_format, msg_count, + min_recv_timestamp, max_recv_timestamp, offered_qos_profiles_str] : query_results) + { + add_topic_to_metadata( + inner_topic_id, topic_name, topic_type, ser_format, msg_count, + offered_qos_profiles_str, ""); + + min_time = min_recv_timestamp < min_time ? min_recv_timestamp : min_time; + max_time = max_recv_timestamp > max_time ? max_recv_timestamp : max_time; } } - } else { + } else { // No offered_qos_profiles and no type_hash std::string query = - "SELECT name, type, serialization_format, COUNT(messages.id), MIN(messages.timestamp), " - "MAX(messages.timestamp) " + "SELECT messages.topic_id, name, type, serialization_format, COUNT(messages.id), " + "MIN(messages.timestamp), MAX(messages.timestamp) " "FROM messages JOIN topics on topics.id = messages.topic_id " "GROUP BY topics.name;"; auto statement = database_->prepare_statement(query); - auto query_results = statement->execute_query< - std::string, std::string, std::string, int, rcutils_time_point_value_t, - rcutils_time_point_value_t>(); + auto query_results = statement->execute_query(); - for (auto result : query_results) { - metadata_.topics_with_message_count.push_back( - { - {std::get<0>(result), std::get<1>(result), std::get<2>( - result), {}, ""}, - static_cast(std::get<3>(result)) - }); - - metadata_.message_count += std::get<3>(result); - min_time = std::get<4>(result) < min_time ? std::get<4>(result) : min_time; - max_time = std::get<5>(result) > max_time ? std::get<5>(result) : max_time; + for (const auto & [inner_topic_id, topic_name, topic_type, ser_format, msg_count, + min_recv_timestamp, max_recv_timestamp] : query_results) + { + add_topic_to_metadata(inner_topic_id, topic_name, topic_type, ser_format, msg_count, "", ""); + + min_time = min_recv_timestamp < min_time ? min_recv_timestamp : min_time; + max_time = max_recv_timestamp > max_time ? max_recv_timestamp : max_time; } } @@ -908,6 +915,33 @@ uint64_t SqliteStorage::get_page_size() const return std::get<0>(*page_size_query_result_begin); } +uint16_t SqliteStorage::get_extern_topic_id(int64_t inner_topic_id) const +{ + auto iter = inner_to_extern_topic_id_map_.find(inner_topic_id); + if (iter != inner_to_extern_topic_id_map_.end()) { + return iter->second; + } else { + return 0; // 0 corresponds to the invalid topic_id + } +} + +uint16_t SqliteStorage::get_or_generate_extern_topic_id(int64_t inner_topic_id) +{ + uint16_t extern_topic_id = get_extern_topic_id(inner_topic_id); + if (extern_topic_id == 0) { + if (last_extern_topic_id_ == std::numeric_limits::max()) { + ROSBAG2_STORAGE_DEFAULT_PLUGINS_LOG_ERROR_STREAM( + "External topic_id reached maximum allowed value" << + std::to_string(std::numeric_limits::max())); + throw std::range_error("External topic_id reached maximum allowed value"); + } + last_extern_topic_id_.fetch_add(1, std::memory_order_relaxed); + extern_topic_id = last_extern_topic_id_; + inner_to_extern_topic_id_map_[inner_topic_id] = extern_topic_id; + } + return extern_topic_id; +} + } // namespace rosbag2_storage_plugins #include "pluginlib/class_list_macros.hpp" // NOLINT diff --git a/rosbag2_storage_sqlite3/src/rosbag2_storage_sqlite3/sqlite_wrapper.cpp b/rosbag2_storage_sqlite3/src/rosbag2_storage_sqlite3/sqlite_wrapper.cpp index 8e21f275fd..9e1702c1dc 100644 --- a/rosbag2_storage_sqlite3/src/rosbag2_storage_sqlite3/sqlite_wrapper.cpp +++ b/rosbag2_storage_sqlite3/src/rosbag2_storage_sqlite3/sqlite_wrapper.cpp @@ -172,7 +172,7 @@ SqliteStatement SqliteWrapper::prepare_statement(const std::string & query) return std::make_shared(db_ptr, query); } -size_t SqliteWrapper::get_last_insert_id() +int64_t SqliteWrapper::get_last_insert_id() { return sqlite3_last_insert_rowid(db_ptr); } diff --git a/rosbag2_storage_sqlite3/test/rosbag2_storage_sqlite3/storage_test_fixture.hpp b/rosbag2_storage_sqlite3/test/rosbag2_storage_sqlite3/storage_test_fixture.hpp index aacd3d8b26..c2ab38a769 100644 --- a/rosbag2_storage_sqlite3/test/rosbag2_storage_sqlite3/storage_test_fixture.hpp +++ b/rosbag2_storage_sqlite3/test/rosbag2_storage_sqlite3/storage_test_fixture.hpp @@ -109,7 +109,7 @@ class StorageTestFixture : public TemporaryDirectoryFixture std::string topic_name = std::get<2>(msg); std::string type_name = std::get<3>(msg); std::string rmw_format = std::get<4>(msg); - rw_storage.create_topic({topic_name, type_name, rmw_format, {}, ""}, {}); + rw_storage.create_topic({0u, topic_name, type_name, rmw_format, {}, ""}, {}); auto bag_message = std::make_shared(); bag_message->serialized_data = make_serialized_message(std::get<0>(msg)); bag_message->time_stamp = std::get<1>(msg); diff --git a/rosbag2_storage_sqlite3/test/rosbag2_storage_sqlite3/test_sqlite_storage.cpp b/rosbag2_storage_sqlite3/test/rosbag2_storage_sqlite3/test_sqlite_storage.cpp index 75fff7b304..8546b35fa7 100644 --- a/rosbag2_storage_sqlite3/test/rosbag2_storage_sqlite3/test_sqlite_storage.cpp +++ b/rosbag2_storage_sqlite3/test/rosbag2_storage_sqlite3/test_sqlite_storage.cpp @@ -174,8 +174,10 @@ TEST_F(StorageTestFixture, get_all_topics_and_types_returns_the_correct_vector) (std::filesystem::path(temporary_dir_path_) / "rosbag").generic_string(); writable_storage->open({read_write_filename, kPluginID}); - writable_storage->create_topic({"topic1", "type1", "rmw1", {rclcpp::QoS(1)}, "type_hash1"}, {}); - writable_storage->create_topic({"topic2", "type2", "rmw2", {rclcpp::QoS(2)}, "type_hash2"}, {}); + writable_storage->create_topic( + {0u, "topic1", "type1", "rmw1", {rclcpp::QoS(1)}, "type_hash1"}, {}); + writable_storage->create_topic( + {0u, "topic2", "type2", "rmw2", {rclcpp::QoS(2)}, "type_hash2"}, {}); const auto read_only_filename = writable_storage->get_relative_file_path(); @@ -190,8 +192,8 @@ TEST_F(StorageTestFixture, get_all_topics_and_types_returns_the_correct_vector) EXPECT_THAT( topics_and_types, ElementsAreArray( { - rosbag2_storage::TopicMetadata{"topic1", "type1", "rmw1", {rclcpp::QoS(1)}, "type_hash1"}, - rosbag2_storage::TopicMetadata{"topic2", "type2", "rmw2", {rclcpp::QoS(2)}, "type_hash2"} + rosbag2_storage::TopicMetadata{1u, "topic1", "type1", "rmw1", {rclcpp::QoS(1)}, "type_hash1"}, + rosbag2_storage::TopicMetadata{2u, "topic2", "type2", "rmw2", {rclcpp::QoS(2)}, "type_hash2"} })); } @@ -207,10 +209,10 @@ TEST_F(StorageTestFixture, get_all_message_definitions_returns_the_correct_vecto writable_storage->open({read_write_filename, kPluginID}); writable_storage->create_topic( - {"topic1", "type1", "rmw1", {rclcpp::QoS(1)}, "type_hash1"}, + {0u, "topic1", "type1", "rmw1", {rclcpp::QoS(1)}, "type_hash1"}, msg_definition); writable_storage->create_topic( - {"topic2", "type2", "rmw2", {rclcpp::QoS(2)}, "type_hash2"}, + {0u, "topic2", "type2", "rmw2", {rclcpp::QoS(2)}, "type_hash2"}, msg_definition); const auto read_only_filename = writable_storage->get_relative_file_path(); @@ -240,8 +242,10 @@ TEST_F(StorageTestFixture, get_metadata_returns_correct_struct) { auto read_write_filename = (std::filesystem::path(temporary_dir_path_) / "rosbag").generic_string(); writable_storage->open({read_write_filename, kPluginID}); - writable_storage->create_topic({"topic1", "type1", "rmw1", {rclcpp::QoS(1)}, "type_hash1"}, {}); - writable_storage->create_topic({"topic2", "type2", "rmw2", {rclcpp::QoS(2)}, "type_hash2"}, {}); + writable_storage->create_topic( + {0u, "topic1", "type1", "rmw1", {rclcpp::QoS(1)}, "type_hash1"}, {}); + writable_storage->create_topic( + {0u, "topic2", "type2", "rmw2", {rclcpp::QoS(2)}, "type_hash2"}, {}); std::vector string_messages = {"first message", "second message", "third message"}; std::vector topics = {"topic1", "topic2"}; @@ -270,9 +274,9 @@ TEST_F(StorageTestFixture, get_metadata_returns_correct_struct) { metadata.topics_with_message_count, ElementsAreArray( { rosbag2_storage::TopicInformation{rosbag2_storage::TopicMetadata{ - "topic1", "type1", "rmw1", {rclcpp::QoS(1)}, "type_hash1"}, 2u}, + 1u, "topic1", "type1", "rmw1", {rclcpp::QoS(1)}, "type_hash1"}, 2u}, rosbag2_storage::TopicInformation{rosbag2_storage::TopicMetadata{ - "topic2", "type2", "rmw2", {rclcpp::QoS(2)}, "type_hash2"}, 1u} + 2u, "topic2", "type2", "rmw2", {rclcpp::QoS(2)}, "type_hash2"}, 1u} })); EXPECT_THAT(metadata.message_count, Eq(3u)); EXPECT_THAT( @@ -310,9 +314,9 @@ TEST_F(StorageTestFixture, get_metadata_returns_correct_struct_for_prefoxy_db_sc metadata.topics_with_message_count, ElementsAreArray( { rosbag2_storage::TopicInformation{rosbag2_storage::TopicMetadata{ - "topic1", "type1", "rmw_format", {}, ""}, 2u}, + 1u, "topic1", "type1", "rmw_format", {}, ""}, 2u}, rosbag2_storage::TopicInformation{rosbag2_storage::TopicMetadata{ - "topic2", "type2", "rmw_format", {}, ""}, 1u} + 2u, "topic2", "type2", "rmw_format", {}, ""}, 1u} })); EXPECT_THAT(metadata.message_count, Eq(3u)); EXPECT_THAT( @@ -411,8 +415,9 @@ TEST_F(StorageTestFixture, remove_topics_and_types_returns_the_empty_vector) { (std::filesystem::path(temporary_dir_path_) / "rosbag").generic_string(); writable_storage->open({read_write_filename, kPluginID}); - writable_storage->create_topic({"topic1", "type1", "rmw1", {}, "hash"}, {}); - writable_storage->remove_topic({"topic1", "type1", "rmw1", {}, "hash"}); + rosbag2_storage::TopicMetadata topic_metadata{0u, "topic1", "type1", "rmw1", {}, "hash"}; + writable_storage->create_topic(topic_metadata, {}); + writable_storage->remove_topic(topic_metadata); const auto read_only_filename = writable_storage->get_relative_file_path(); diff --git a/rosbag2_tests/test/rosbag2_tests/test_rosbag2_storage_api.cpp b/rosbag2_tests/test/rosbag2_tests/test_rosbag2_storage_api.cpp index f4fd7d5373..2ca5f65be4 100644 --- a/rosbag2_tests/test/rosbag2_tests/test_rosbag2_storage_api.cpp +++ b/rosbag2_tests/test/rosbag2_tests/test_rosbag2_storage_api.cpp @@ -100,6 +100,7 @@ class Rosbag2StorageAPITests : public rosbag2_test_common::ParametrizedTemporary "std_msgs/msg/String", "ros2msg", "string data", type_description_hash}; rosbag2_storage::TopicMetadata topic_metadata = { + 0u, topics[topic_idx], "std_msgs/msg/String", "cdr", diff --git a/rosbag2_transport/src/rosbag2_transport/recorder.cpp b/rosbag2_transport/src/rosbag2_transport/recorder.cpp index 597b1b9a52..8d93e5a752 100644 --- a/rosbag2_transport/src/rosbag2_transport/recorder.cpp +++ b/rosbag2_transport/src/rosbag2_transport/recorder.cpp @@ -488,6 +488,7 @@ void RecorderImpl::subscribe_topics( auto endpoint_infos = node->get_publishers_info_by_topic(topic_with_type.first); subscribe_topic( { + 0u, topic_with_type.first, topic_with_type.second, serialization_format_, diff --git a/rosbag2_transport/test/rosbag2_transport/rosbag2_play_duration_until_fixture.hpp b/rosbag2_transport/test/rosbag2_transport/rosbag2_play_duration_until_fixture.hpp index 95d4f8e314..84c443f775 100644 --- a/rosbag2_transport/test/rosbag2_transport/rosbag2_play_duration_until_fixture.hpp +++ b/rosbag2_transport/test/rosbag2_transport/rosbag2_play_duration_until_fixture.hpp @@ -91,8 +91,9 @@ class RosBag2PlayDurationAndUntilTestFixture : public RosBag2PlayTestFixture std::vector get_topic_types() { - return {{kTopic1Name_, "test_msgs/BasicTypes", "", {}, ""}, - {kTopic2Name_, "test_msgs/Arrays", "", {}, ""}}; + return { + {1u, kTopic1Name_, "test_msgs/BasicTypes", "", {}, ""}, + {2u, kTopic2Name_, "test_msgs/Arrays", "", {}, ""}}; } std::vector> diff --git a/rosbag2_transport/test/rosbag2_transport/test_burst.cpp b/rosbag2_transport/test/rosbag2_transport/test_burst.cpp index 0d53e32aae..5988fdd598 100644 --- a/rosbag2_transport/test/rosbag2_transport/test_burst.cpp +++ b/rosbag2_transport/test/rosbag2_transport/test_burst.cpp @@ -35,7 +35,7 @@ TEST_F(RosBag2PlayTestFixture, burst_with_false_preconditions) { primitive_message->int32_value = 42; auto topic_types = std::vector{ - {"topic1", "test_msgs/BasicTypes", "", {}, ""}}; + {1u, "topic1", "test_msgs/BasicTypes", "", {}, ""}}; std::vector> messages = {serialize_test_message("topic1", 2100, primitive_message)}; @@ -56,7 +56,7 @@ TEST_F(RosBag2PlayTestFixture, burst_bursts_requested_messages_without_delays) { primitive_message->int32_value = 42; auto topic_types = std::vector{ - {"topic1", "test_msgs/BasicTypes", "", {}, ""}}; + {1u, "topic1", "test_msgs/BasicTypes", "", {}, ""}}; std::vector> messages = { @@ -110,7 +110,7 @@ TEST_F(RosBag2PlayTestFixture, burst_stops_at_end_of_file) { primitive_message->int32_value = 42; auto topic_types = std::vector{ - {"topic1", "test_msgs/BasicTypes", "", {}, ""}}; + {1u, "topic1", "test_msgs/BasicTypes", "", {}, ""}}; std::vector> messages = { @@ -157,7 +157,7 @@ TEST_F(RosBag2PlayTestFixture, burst_bursting_one_by_one_messages_with_the_same_ primitive_message->int32_value = 42; auto topic_types = std::vector{ - {"topic1", "test_msgs/BasicTypes", "", {}, ""}}; + {1u, "topic1", "test_msgs/BasicTypes", "", {}, ""}}; std::vector> messages = { @@ -210,7 +210,7 @@ TEST_F(RosBag2PlayTestFixture, play_respect_messages_timing_after_burst) { primitive_message->int32_value = 42; auto topic_types = std::vector{ - {"topic1", "test_msgs/BasicTypes", "", {}, ""}}; + {1u, "topic1", "test_msgs/BasicTypes", "", {}, ""}}; std::vector> messages = { @@ -265,7 +265,7 @@ TEST_F(RosBag2PlayTestFixture, player_can_resume_after_burst) { primitive_message->int32_value = 42; auto topic_types = std::vector{ - {"topic1", "test_msgs/BasicTypes", "", {}, ""}}; + {1u, "topic1", "test_msgs/BasicTypes", "", {}, ""}}; std::vector> messages = { @@ -313,8 +313,8 @@ TEST_F(RosBag2PlayTestFixture, burst_bursting_only_filtered_topics) { complex_message1->bool_values = {{true, false, true}}; auto topic_types = std::vector{ - {"topic1", "test_msgs/BasicTypes", "", {}, ""}, - {"topic2", "test_msgs/Arrays", "", {}, ""}, + {1u, "topic1", "test_msgs/BasicTypes", "", {}, ""}, + {2u, "topic2", "test_msgs/Arrays", "", {}, ""}, }; std::vector> messages = diff --git a/rosbag2_transport/test/rosbag2_transport/test_keyboard_controls.cpp b/rosbag2_transport/test/rosbag2_transport/test_keyboard_controls.cpp index 8d3f8fd605..d10b1a7d73 100644 --- a/rosbag2_transport/test/rosbag2_transport/test_keyboard_controls.cpp +++ b/rosbag2_transport/test/rosbag2_transport/test_keyboard_controls.cpp @@ -98,7 +98,7 @@ TEST_F(RosBag2PlayTestFixture, invalid_keybindings) auto message_time_difference = rclcpp::Duration(1, 0); auto topics_and_types = - std::vector{{"topic1", "test_msgs/Strings", "", {}, ""}}; + std::vector{{1u, "topic1", "test_msgs/Strings", "", {}, ""}}; std::vector> messages = {serialize_test_message("topic1", 0, primitive_message1), serialize_test_message("topic1", 0, primitive_message2)}; @@ -132,7 +132,7 @@ TEST_F(RosBag2PlayTestFixture, test_keyboard_controls) auto message_time_difference = rclcpp::Duration(1, 0); auto topics_and_types = - std::vector{{"topic1", "test_msgs/Strings", "", {}, ""}}; + std::vector{{1u, "topic1", "test_msgs/Strings", "", {}, ""}}; std::vector> messages = {serialize_test_message("topic1", 0, primitive_message1), serialize_test_message("topic1", 0, primitive_message2), diff --git a/rosbag2_transport/test/rosbag2_transport/test_play.cpp b/rosbag2_transport/test/rosbag2_transport/test_play.cpp index 5a867cff63..2cc2c20d17 100644 --- a/rosbag2_transport/test/rosbag2_transport/test_play.cpp +++ b/rosbag2_transport/test/rosbag2_transport/test_play.cpp @@ -53,8 +53,8 @@ TEST_F(RosBag2PlayTestFixture, recorded_messages_are_played_for_all_topics) complex_message1->bool_values = {{true, false, true}}; auto topic_types = std::vector{ - {"topic1", "test_msgs/BasicTypes", "", {}, ""}, - {"topic2", "test_msgs/Arrays", "", {}, ""}, + {1u, "topic1", "test_msgs/BasicTypes", "", {}, ""}, + {2u, "topic2", "test_msgs/Arrays", "", {}, ""}, }; std::vector> messages = @@ -121,9 +121,9 @@ TEST_F(RosBag2PlayTestFixture, recorded_messages_are_played_for_all_topics_with_ unknown_message1->int32_value = 42; auto topic_types = std::vector{ - {"topic1", "test_msgs/BasicTypes", "", {}, ""}, - {"topic2", "test_msgs/Arrays", "", {}, ""}, - {"topic3", "unknown_msgs/UnknownType", "", {}, ""}, + {1u, "topic1", "test_msgs/BasicTypes", "", {}, ""}, + {2u, "topic2", "test_msgs/Arrays", "", {}, ""}, + {3u, "topic3", "unknown_msgs/UnknownType", "", {}, ""}, }; std::vector> messages = @@ -188,8 +188,8 @@ TEST_F(RosBag2PlayTestFixture, recorded_messages_are_played_for_filtered_topics) complex_message1->bool_values = {{true, false, true}}; auto topic_types = std::vector{ - {"topic1", "test_msgs/BasicTypes", "", {}, ""}, - {"topic2", "test_msgs/Arrays", "", {}, ""}, + {1u, "topic1", "test_msgs/BasicTypes", "", {}, ""}, + {2u, "topic2", "test_msgs/Arrays", "", {}, ""}, }; std::vector> messages = @@ -310,9 +310,9 @@ TEST_F(RosBag2PlayTestFixture, recorded_messages_are_played_for_filtered_topics_ unknown_message1->int32_value = 42; auto topic_types = std::vector{ - {"topic1", "test_msgs/BasicTypes", "", {}, ""}, - {"topic2", "test_msgs/Arrays", "", {}, ""}, - {"topic3", "unknown_msgs/UnknownType", "", {}, ""}, + {1u, "topic1", "test_msgs/BasicTypes", "", {}, ""}, + {2u, "topic2", "test_msgs/Arrays", "", {}, ""}, + {3u, "topic3", "unknown_msgs/UnknownType", "", {}, ""}, }; std::vector> messages = @@ -416,7 +416,7 @@ TEST_F(RosBag2PlayTestFixture, player_gracefully_exit_by_rclcpp_shutdown_in_paus auto primitive_message1 = get_messages_basic_types()[0]; primitive_message1->int32_value = 42; auto topic_types = std::vector{ - {"topic1", "test_msgs/BasicTypes", "", {}, ""}, + {1u, "topic1", "test_msgs/BasicTypes", "", {}, ""}, }; std::vector> messages = @@ -461,13 +461,7 @@ class RosBag2PlayQosOverrideTestFixture : public RosBag2PlayTestFixture messages_.push_back(serialize_test_message(topic_name_, timestamp, basic_msg_)); } - topic_types_.push_back( - { - topic_name_, - msg_type_, - "", - offered_qos, - ""}); + topic_types_.push_back({0u, topic_name_, msg_type_, "", offered_qos, ""}); } template @@ -627,7 +621,7 @@ TEST_F(RosBag2PlayQosOverrideTestFixture, override_has_precedence_over_recorded) TEST_F(RosBag2PlayTestFixture, read_split_callback_is_called) { auto topic_types = std::vector{ - {"topic1", "test_msgs/BasicTypes", "", {}, ""}, + {1u, "topic1", "test_msgs/BasicTypes", "", {}, ""}, }; auto prepared_mock_reader = std::make_unique(); diff --git a/rosbag2_transport/test/rosbag2_transport/test_play_callbacks.cpp b/rosbag2_transport/test/rosbag2_transport/test_play_callbacks.cpp index 312bc50a67..c039b7ac24 100644 --- a/rosbag2_transport/test/rosbag2_transport/test_play_callbacks.cpp +++ b/rosbag2_transport/test/rosbag2_transport/test_play_callbacks.cpp @@ -39,7 +39,7 @@ class Rosbag2PlayCallbacksTestFixture : public Rosbag2TransportTestFixture rclcpp::init(0, nullptr); auto topics_and_types = - std::vector{{"topic1", "test_msgs/Strings", "", {}, ""}}; + std::vector{{0u, "topic1", "test_msgs/Strings", "", {}, ""}}; std::vector> messages; messages.reserve(num_test_messages_); diff --git a/rosbag2_transport/test/rosbag2_transport/test_play_duration.cpp b/rosbag2_transport/test/rosbag2_transport/test_play_duration.cpp index e5adaa7b29..feb6df153d 100644 --- a/rosbag2_transport/test/rosbag2_transport/test_play_duration.cpp +++ b/rosbag2_transport/test/rosbag2_transport/test_play_duration.cpp @@ -62,7 +62,7 @@ TEST_F(RosBag2PlayDurationTestFixture, play_for_none_are_played_due_to_duration) primitive_message2->int32_value = 2; auto topic_types = std::vector{ - {kTopic1Name_, "test_msgs/BasicTypes", "", {}, ""}}; + {1u, kTopic1Name_, "test_msgs/BasicTypes", "", {}, ""}}; std::vector> messages = { @@ -106,7 +106,7 @@ TEST_F(RosBag2PlayDurationTestFixture, play_for_less_than_the_total_duration) primitive_message2->int32_value = 2; auto topic_types = std::vector{ - {kTopic1Name_, "test_msgs/BasicTypes", "", {}, ""}}; + {1u, kTopic1Name_, "test_msgs/BasicTypes", "", {}, ""}}; std::vector> messages = { @@ -175,7 +175,7 @@ TEST_F( TEST_F(RosBag2PlayDurationTestFixture, play_should_return_false_when_interrupted) { auto topic_types = std::vector{ - {kTopic1Name_, "test_msgs/BasicTypes", "", {}, ""}}; + {1u, kTopic1Name_, "test_msgs/BasicTypes", "", {}, ""}}; auto primitive_message = get_messages_basic_types()[0]; primitive_message->int32_value = kIntValue; diff --git a/rosbag2_transport/test/rosbag2_transport/test_play_loop.cpp b/rosbag2_transport/test/rosbag2_transport/test_play_loop.cpp index f8d6e490ab..78c111f83a 100644 --- a/rosbag2_transport/test/rosbag2_transport/test_play_loop.cpp +++ b/rosbag2_transport/test/rosbag2_transport/test_play_loop.cpp @@ -52,7 +52,7 @@ TEST_F(RosBag2PlayTestFixture, play_bag_file_twice) { primitive_message1->int32_value = test_value; auto topic_types = std::vector{ - {"loop_test_topic", "test_msgs/BasicTypes", "", {}, ""} + {1u, "loop_test_topic", "test_msgs/BasicTypes", "", {}, ""} }; std::vector> messages(num_messages, @@ -116,7 +116,7 @@ TEST_F(RosBag2PlayTestFixture, messages_played_in_loop) { primitive_message1->int32_value = test_value; auto topic_types = std::vector{ - {"loop_test_topic", "test_msgs/BasicTypes", "", {}, ""} + {1u, "loop_test_topic", "test_msgs/BasicTypes", "", {}, ""} }; std::vector> messages(num_messages, diff --git a/rosbag2_transport/test/rosbag2_transport/test_play_next.cpp b/rosbag2_transport/test/rosbag2_transport/test_play_next.cpp index 12886e8fc0..8c6ec32897 100644 --- a/rosbag2_transport/test/rosbag2_transport/test_play_next.cpp +++ b/rosbag2_transport/test/rosbag2_transport/test_play_next.cpp @@ -35,7 +35,7 @@ TEST_F(RosBag2PlayTestFixture, play_next_with_false_preconditions) { primitive_message->int32_value = 42; auto topic_types = std::vector{ - {"topic1", "test_msgs/BasicTypes", "", {}, ""}}; + {1u, "topic1", "test_msgs/BasicTypes", "", {}, ""}}; std::vector> messages = {serialize_test_message("topic1", 2100, primitive_message)}; @@ -56,7 +56,7 @@ TEST_F(RosBag2PlayTestFixture, play_next_playing_all_messages_without_delays) { primitive_message->int32_value = 42; auto topic_types = std::vector{ - {"topic1", "test_msgs/BasicTypes", "", {}, ""}}; + {1u, "topic1", "test_msgs/BasicTypes", "", {}, ""}}; std::vector> messages = { @@ -110,7 +110,7 @@ TEST_F(RosBag2PlayTestFixture, play_next_playing_one_by_one_messages_with_the_sa primitive_message->int32_value = 42; auto topic_types = std::vector{ - {"topic1", "test_msgs/BasicTypes", "", {}, ""}}; + {1u, "topic1", "test_msgs/BasicTypes", "", {}, ""}}; std::vector> messages = { @@ -163,7 +163,7 @@ TEST_F(RosBag2PlayTestFixture, play_respect_messages_timing_after_play_next) { primitive_message->int32_value = 42; auto topic_types = std::vector{ - {"topic1", "test_msgs/BasicTypes", "", {}, ""}}; + {1u, "topic1", "test_msgs/BasicTypes", "", {}, ""}}; std::vector> messages = { @@ -218,7 +218,7 @@ TEST_F(RosBag2PlayTestFixture, player_can_resume_after_play_next) { primitive_message->int32_value = 42; auto topic_types = std::vector{ - {"topic1", "test_msgs/BasicTypes", "", {}, ""}}; + {1u, "topic1", "test_msgs/BasicTypes", "", {}, ""}}; std::vector> messages = { @@ -266,8 +266,8 @@ TEST_F(RosBag2PlayTestFixture, play_next_playing_only_filtered_topics) { complex_message1->bool_values = {{true, false, true}}; auto topic_types = std::vector{ - {"topic1", "test_msgs/BasicTypes", "", {}, ""}, - {"topic2", "test_msgs/Arrays", "", {}, ""}, + {1u, "topic1", "test_msgs/BasicTypes", "", {}, ""}, + {2u, "topic2", "test_msgs/Arrays", "", {}, ""}, }; std::vector> messages = diff --git a/rosbag2_transport/test/rosbag2_transport/test_play_publish_clock.cpp b/rosbag2_transport/test/rosbag2_transport/test_play_publish_clock.cpp index 785ec9f954..543d1f4bb5 100644 --- a/rosbag2_transport/test/rosbag2_transport/test_play_publish_clock.cpp +++ b/rosbag2_transport/test/rosbag2_transport/test_play_publish_clock.cpp @@ -43,7 +43,7 @@ class ClockPublishFixture : public RosBag2PlayTestFixture { // Fake bag setup auto topic_types = std::vector{ - {"topic1", "test_msgs/BasicTypes", "", {}, ""}, + {1u, "topic1", "test_msgs/BasicTypes", "", {}, ""}, }; std::vector> messages; diff --git a/rosbag2_transport/test/rosbag2_transport/test_play_seek.cpp b/rosbag2_transport/test/rosbag2_transport/test_play_seek.cpp index 100daa1a0a..f0d482b478 100644 --- a/rosbag2_transport/test/rosbag2_transport/test_play_seek.cpp +++ b/rosbag2_transport/test/rosbag2_transport/test_play_seek.cpp @@ -42,7 +42,7 @@ class RosBag2PlaySeekTestFixture : RosBag2PlayTestFixture() { topic_types_ = std::vector{ - {"topic1", "test_msgs/BasicTypes", rmw_get_serialization_format(), {}, ""}}; + {1u, "topic1", "test_msgs/BasicTypes", rmw_get_serialization_format(), {}, ""}}; const rcpputils::fs::path base{_SRC_RESOURCES_DIR_PATH}; const rcpputils::fs::path bag_path = base / GetParam() / "test_bag_for_seek"; diff --git a/rosbag2_transport/test/rosbag2_transport/test_play_services.cpp b/rosbag2_transport/test/rosbag2_transport/test_play_services.cpp index bdc40c7e70..c44764d9f3 100644 --- a/rosbag2_transport/test/rosbag2_transport/test_play_services.cpp +++ b/rosbag2_transport/test/rosbag2_transport/test_play_services.cpp @@ -202,7 +202,7 @@ class PlaySrvsTest : public RosBag2PlayTestFixture message->int32_value = 42; auto topic_types = std::vector{ - {test_topic_, "test_msgs/BasicTypes", "", {}, ""}, + {1u, test_topic_, "test_msgs/BasicTypes", "", {}, ""}, }; std::vector> messages; for (size_t i = 0; i < num_msgs_to_publish_; i++) { diff --git a/rosbag2_transport/test/rosbag2_transport/test_play_timing.cpp b/rosbag2_transport/test/rosbag2_transport/test_play_timing.cpp index befdc2defe..d3f58e4655 100644 --- a/rosbag2_transport/test/rosbag2_transport/test_play_timing.cpp +++ b/rosbag2_transport/test/rosbag2_transport/test_play_timing.cpp @@ -49,7 +49,7 @@ class PlayerTestFixture : public Rosbag2TransportTestFixture auto primitive_message2 = get_messages_strings()[0]; primitive_message2->string_value = "Hello World 2"; - topics_and_types = {{"topic1", "test_msgs/Strings", "", {}, ""}}; + topics_and_types = {{1u, "topic1", "test_msgs/Strings", "", {}, ""}}; messages = { serialize_test_message("topic1", 0, primitive_message1), serialize_test_message("topic1", 0, primitive_message2) diff --git a/rosbag2_transport/test/rosbag2_transport/test_play_topic_remap.cpp b/rosbag2_transport/test/rosbag2_transport/test_play_topic_remap.cpp index 37792e5463..96e71a0362 100644 --- a/rosbag2_transport/test/rosbag2_transport/test_play_topic_remap.cpp +++ b/rosbag2_transport/test/rosbag2_transport/test_play_topic_remap.cpp @@ -45,7 +45,7 @@ TEST_F(RosBag2PlayTestFixture, recorded_message_is_played_on_remapped_topic) { primitive_message1->int32_value = test_value; auto topic_types = std::vector{ - {original_topic, "test_msgs/BasicTypes", "", {}, ""} + {1u, original_topic, "test_msgs/BasicTypes", "", {}, ""} }; std::vector> messages; diff --git a/rosbag2_transport/test/rosbag2_transport/test_play_until.cpp b/rosbag2_transport/test/rosbag2_transport/test_play_until.cpp index e4523c460c..8e12da5ebf 100644 --- a/rosbag2_transport/test/rosbag2_transport/test_play_until.cpp +++ b/rosbag2_transport/test/rosbag2_transport/test_play_until.cpp @@ -69,7 +69,7 @@ TEST_F(RosBag2PlayUntilTestFixture, play_until_none_are_played_due_to_timestamp) primitive_message2->int32_value = 2; auto topic_types = std::vector{ - {kTopic1Name_, "test_msgs/BasicTypes", "", {}, ""}}; + {1u, kTopic1Name_, "test_msgs/BasicTypes", "", {}, ""}}; std::vector> messages = { @@ -113,7 +113,7 @@ TEST_F(RosBag2PlayUntilTestFixture, play_until_less_than_the_total_duration) primitive_message2->int32_value = 2; auto topic_types = std::vector{ - {kTopic1Name_, "test_msgs/BasicTypes", "", {}, ""}}; + {1u, kTopic1Name_, "test_msgs/BasicTypes", "", {}, ""}}; std::vector> messages = { @@ -182,7 +182,7 @@ TEST_F( TEST_F(RosBag2PlayUntilTestFixture, play_should_return_false_when_interrupted) { auto topic_types = std::vector{ - {kTopic1Name_, "test_msgs/BasicTypes", "", {}, ""}}; + {1u, kTopic1Name_, "test_msgs/BasicTypes", "", {}, ""}}; auto primitive_message = get_messages_basic_types()[0]; primitive_message->int32_value = kIntValue; @@ -270,7 +270,7 @@ TEST_F(RosBag2PlayUntilTestFixture, play_until_is_equal_to_the_total_duration) primitive_message2->int32_value = 2; auto topic_types = std::vector{ - {kTopic1Name_, "test_msgs/BasicTypes", "", {}, ""}}; + {1u, kTopic1Name_, "test_msgs/BasicTypes", "", {}, ""}}; std::vector> messages = { diff --git a/rosbag2_transport/test/rosbag2_transport/test_player_stop.cpp b/rosbag2_transport/test/rosbag2_transport/test_player_stop.cpp index 8532e47241..328c16fe84 100644 --- a/rosbag2_transport/test/rosbag2_transport/test_player_stop.cpp +++ b/rosbag2_transport/test/rosbag2_transport/test_player_stop.cpp @@ -41,7 +41,7 @@ class Rosbag2PlayerStopTestFixture : public Rosbag2TransportTestFixture { rclcpp::init(0, nullptr); auto topics_and_types = - std::vector{{"topic1", "test_msgs/Strings", "", {}, ""}}; + std::vector{{1u, "topic1", "test_msgs/Strings", "", {}, ""}}; std::vector> messages; messages.reserve(num_test_messages_);