Skip to content

Commit

Permalink
Add topic_id returned by storage to the TopicMetadata (#1538)
Browse files Browse the repository at this point in the history
* 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 <[email protected]>

* Map inner int64_t topic_id to the external uint16_t topic_id in sqlite3

Signed-off-by: Michael Orlov <[email protected]>

* Change TopicMetadata::id type to uint16_t

Signed-off-by: Michael Orlov <[email protected]>

* Use atomic for last_extern_topic_id_

Co-authored-by: Tomoya Fujita <[email protected]>
Signed-off-by: Michael Orlov <[email protected]>

---------

Signed-off-by: Michael Orlov <[email protected]>
Co-authored-by: Tomoya Fujita <[email protected]>
  • Loading branch information
MichaelOrlov and fujitatomoya authored Feb 6, 2024
1 parent 90d1da8 commit 1564687
Show file tree
Hide file tree
Showing 45 changed files with 271 additions and 219 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -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<rosbag2_storage::TopicMetadata>{topic_with_type_};
auto message = std::make_shared<rosbag2_storage::SerializedBagMessage>();
message->topic_name = topic_with_type_.name;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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<rosbag2_storage::SerializedBagMessage>();
message->topic_name = test_topic_name;
Expand Down Expand Up @@ -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<rosbag2_storage::SerializedBagMessage>();
message->topic_name = test_topic_name;
Expand Down Expand Up @@ -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<rosbag2_storage::SerializedBagMessage>();
message->topic_name = test_topic_name;
Expand Down Expand Up @@ -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<rosbag2_storage::SerializedBagMessage>();
message->topic_name = test_topic_name;
Expand Down Expand Up @@ -441,7 +441,7 @@ TEST_P(SequentialCompressionWriterTest, writer_sets_threads_priority)
std::make_unique<FakeCompressionFactory>(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<rosbag2_storage::SerializedBagMessage>();
message->topic_name = test_topic_name;
Expand Down
1 change: 1 addition & 0 deletions rosbag2_cpp/test/rosbag2_cpp/fake_data.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -34,6 +34,7 @@ void write_sample_split_bag(

writer.create_topic(
{
0u,
topic_name,
"test_msgs/msg/ByteMultiArray",
"cdr",
Expand Down
12 changes: 6 additions & 6 deletions rosbag2_cpp/test/rosbag2_cpp/test_info.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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);
Expand All @@ -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);
Expand Down Expand Up @@ -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);
Expand All @@ -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);
Expand Down Expand Up @@ -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));
Expand All @@ -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));
Expand Down
2 changes: 1 addition & 1 deletion rosbag2_cpp/test/rosbag2_cpp/test_multifile_reader.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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<rosbag2_storage::TopicMetadata>{topic_with_type};
metadata.topics_with_message_count.push_back({topic_with_type, 10});

Expand Down
24 changes: 12 additions & 12 deletions rosbag2_cpp/test/rosbag2_cpp/test_sequential_writer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -130,7 +130,7 @@ TEST_F(
auto message = std::make_shared<rosbag2_storage::SerializedBagMessage>();
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);
}

Expand All @@ -147,7 +147,7 @@ TEST_F(SequentialWriterTest, write_does_not_use_converters_if_input_and_output_f
auto message = std::make_shared<rosbag2_storage::SerializedBagMessage>();
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);
}

Expand Down Expand Up @@ -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<rosbag2_storage::SerializedBagMessage>();
message->topic_name = test_topic_name;
Expand Down Expand Up @@ -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<rosbag2_storage::SerializedBagMessage>();
message->topic_name = test_topic_name;
Expand Down Expand Up @@ -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);
Expand Down Expand Up @@ -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);
Expand Down Expand Up @@ -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) {
Expand Down Expand Up @@ -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);
Expand Down Expand Up @@ -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);
Expand Down Expand Up @@ -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);
Expand Down Expand Up @@ -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);
Expand Down Expand Up @@ -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);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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"};
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -34,6 +34,7 @@ int main(int, char **)

writer_->create_topic(
{
0u,
"synthetic",
"example_interfaces/msg/Int32",
rmw_get_serialization_format(),
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -35,6 +35,7 @@ class DataGenerator : public rclcpp::Node

writer_->create_topic(
{
0u,
"synthetic",
"example_interfaces/msg/Int32",
rmw_get_serialization_format(),
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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')
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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')
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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')
Expand Down
5 changes: 4 additions & 1 deletion rosbag2_py/src/rosbag2_py/_storage.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -209,12 +209,15 @@ PYBIND11_MODULE(_storage, m) {

pybind11::class_<rosbag2_storage::TopicMetadata>(m, "TopicMetadata")
.def(
pybind11::init<std::string, std::string, std::string, std::vector<rclcpp::QoS>, std::string>(),
pybind11::init<uint16_t, std::string, std::string, std::string, std::vector<rclcpp::QoS>,
std::string>(),
pybind11::arg("id"),
pybind11::arg("name"),
pybind11::arg("type"),
pybind11::arg("serialization_format"),
pybind11::arg("offered_qos_profiles") = std::vector<rclcpp::QoS>(),
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(
Expand Down
1 change: 1 addition & 0 deletions rosbag2_py/test/test_compression.py
Original file line number Diff line number Diff line change
Expand Up @@ -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')
Expand Down
2 changes: 1 addition & 1 deletion rosbag2_py/test/test_sequential_writer.py
Original file line number Diff line number Diff line change
Expand Up @@ -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)
Expand Down
3 changes: 3 additions & 0 deletions rosbag2_py/test/test_storage.py
Original file line number Diff line number Diff line change
Expand Up @@ -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'
Expand All @@ -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'),
Expand All @@ -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'),
Expand Down
4 changes: 3 additions & 1 deletion rosbag2_storage/include/rosbag2_storage/topic_metadata.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -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;
Expand All @@ -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;
Expand Down
Loading

0 comments on commit 1564687

Please sign in to comment.