Skip to content
New issue

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

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

Already on GitHub? Sign in to your account

Add QoS profiles field to metadata struct and provide serialization utilities #330

Merged
merged 15 commits into from
Mar 26, 2020
Original file line number Diff line number Diff line change
Expand Up @@ -44,7 +44,7 @@ class SequentialCompressionReaderTest : public Test
storage_serialization_format_{"rmw1_format"}
{
topic_with_type_ = rosbag2_storage::TopicMetadata{
"topic", "test_msgs/BasicTypes", storage_serialization_format_};
"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
8 changes: 4 additions & 4 deletions rosbag2_cpp/test/rosbag2_cpp/test_info.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -82,7 +82,7 @@ TEST_F(TemporaryDirectoryFixture, 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{{"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 @@ -91,7 +91,7 @@ TEST_F(TemporaryDirectoryFixture, 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{{"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 @@ -148,7 +148,7 @@ TEST_F(TemporaryDirectoryFixture, read_metadata_makes_appropriate_call_to_metada
EXPECT_THAT(read_metadata.message_count, Eq(50u));
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};
rosbag2_storage::TopicInformation expected_first_topic = {{"topic1", "type1", "rmw1", ""}, 100};
EXPECT_THAT(
actual_first_topic.topic_metadata.name,
Eq(expected_first_topic.topic_metadata.name));
Expand All @@ -160,7 +160,7 @@ TEST_F(TemporaryDirectoryFixture, read_metadata_makes_appropriate_call_to_metada
Eq(expected_first_topic.topic_metadata.serialization_format));
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};
rosbag2_storage::TopicInformation expected_second_topic = {{"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 @@ -43,7 +43,7 @@ class MultifileReaderTest : public Test
relative_path_2_("some_relative_path_2")
{
auto topic_with_type = rosbag2_storage::TopicMetadata{
"topic", "test_msgs/BasicTypes", storage_serialization_format_};
"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>();
Expand Down
8 changes: 4 additions & 4 deletions rosbag2_cpp/test/rosbag2_cpp/test_sequential_writer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -93,7 +93,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({"test_topic", "test_msgs/BasicTypes", "", ""});
writer_->write(message);
}

Expand All @@ -110,7 +110,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({"test_topic", "test_msgs/BasicTypes", "", ""});
writer_->write(message);
}

Expand Down Expand Up @@ -179,7 +179,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({"test_topic", "test_msgs/BasicTypes", "", ""});

for (auto i = 0; i < counter; ++i) {
writer_->write(message);
Expand Down Expand Up @@ -227,7 +227,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({"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 @@ -55,7 +55,8 @@ TEST_F(StorageWithoutMetadataFileTest, open_uses_storage_id_from_storage_options
auto topic_with_type = rosbag2_storage::TopicMetadata{
"topic",
"test_msgs/BasicTypes",
kRmwFormat
kRmwFormat,
""
};

auto topic_information = rosbag2_storage::TopicInformation{
Expand Down
2 changes: 1 addition & 1 deletion rosbag2_storage/include/rosbag2_storage/bag_metadata.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -33,7 +33,7 @@ struct TopicInformation

struct BagMetadata
{
int version = 3; // upgrade this number when changing the content of the struct
int version = 4; // upgrade this number when changing the content of the struct
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

is it the right time to update the bag metadata? Could we delay that until the feature is built completely? What's the impact if we were to release rosbag2 just after this PR gets merged?

Copy link
Collaborator Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Yeah I was considering this, but I think that now is the time because now is when the data model actually changes. Moving forward that model will just start to hold more useful values. If we were to release this now, nothing bad would happen, it's fully backward compatible with previous metadata versions.

uint64_t bag_size = 0; // Will not be serialized
std::string storage_identifier;
std::vector<std::string> relative_file_paths;
Expand Down
2 changes: 2 additions & 0 deletions rosbag2_storage/include/rosbag2_storage/topic_metadata.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -25,6 +25,8 @@ struct TopicMetadata
std::string name;
std::string type;
std::string serialization_format;
// Serialized std::vector<rclcpp::QoS> as a YAML string
std::string offered_qos_profiles;

bool operator==(const rosbag2_storage::TopicMetadata & rhs) const
{
Expand Down
1 change: 1 addition & 0 deletions rosbag2_storage/src/rosbag2_storage/metadata_io.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -48,6 +48,7 @@ struct convert<rosbag2_storage::TopicMetadata>
node["name"] = topic.name;
node["type"] = topic.type;
node["serialization_format"] = topic.serialization_format;
node["offered_qos_profiles"] = topic.offered_qos_profiles;
return node;
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -53,8 +53,8 @@ TEST_F(MetadataFixture, test_writing_and_reading_yaml)
metadata.starting_time =
std::chrono::time_point<std::chrono::high_resolution_clock>(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({{"topic1", "type1", "rmw1", "qos1"}, 100});
metadata.topics_with_message_count.push_back({{"topic2", "type2", "rmw2", "qos2"}, 200});

metadata_io_->write_metadata(temporary_dir_path_, metadata);
auto read_metadata = metadata_io_->read_metadata(temporary_dir_path_);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -167,7 +167,8 @@ void SqliteStorage::initialize()
"id INTEGER PRIMARY KEY," \
"name TEXT NOT NULL," \
"type TEXT NOT NULL," \
"serialization_format TEXT NOT NULL);";
"serialization_format TEXT NOT NULL," \
"offered_qos_profiles TEXT NOT NULL);";
database_->prepare_statement(create_stmt)->execute_and_reset();
create_stmt = "CREATE TABLE messages(" \
"id INTEGER PRIMARY KEY," \
Expand All @@ -184,8 +185,10 @@ void SqliteStorage::create_topic(const rosbag2_storage::TopicMetadata & topic)
if (topics_.find(topic.name) == std::end(topics_)) {
auto insert_topic =
database_->prepare_statement(
"INSERT INTO topics (name, type, serialization_format) VALUES (?, ?, ?)");
insert_topic->bind(topic.name, topic.type, topic.serialization_format);
"INSERT INTO topics (name, type, serialization_format, offered_qos_profiles) "
"VALUES (?, ?, ?, ?)");
insert_topic->bind(
topic.name, topic.type, topic.serialization_format, topic.offered_qos_profiles);
insert_topic->execute_and_reset();
topics_.emplace(topic.name, static_cast<int>(database_->get_last_insert_id()));
}
Expand Down Expand Up @@ -228,7 +231,7 @@ void SqliteStorage::fill_topics_and_types()

for (auto result : query_results) {
all_topics_and_types_.push_back(
{std::get<0>(result), std::get<1>(result), std::get<2>(result)});
{std::get<0>(result), std::get<1>(result), std::get<2>(result), ""});
}
}

Expand Down Expand Up @@ -270,7 +273,7 @@ rosbag2_storage::BagMetadata SqliteStorage::get_metadata()
for (auto result : query_results) {
metadata.topics_with_message_count.push_back(
{
{std::get<0>(result), std::get<1>(result), std::get<2>(result)},
{std::get<0>(result), std::get<1>(result), std::get<2>(result), ""},
static_cast<size_t>(std::get<3>(result))
});

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -105,7 +105,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);
writable_storage->create_topic({topic_name, type_name, rmw_format});
writable_storage->create_topic({topic_name, type_name, rmw_format, ""});
auto bag_message = std::make_shared<rosbag2_storage::SerializedBagMessage>();
bag_message->serialized_data = make_serialized_message(std::get<0>(msg));
bag_message->time_stamp = std::get<1>(msg);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -119,8 +119,8 @@ TEST_F(StorageTestFixture, get_all_topics_and_types_returns_the_correct_vector)
const auto read_write_filename = (rcpputils::fs::path(temporary_dir_path_) / "rosbag").string();

writable_storage->open(read_write_filename);
writable_storage->create_topic({"topic1", "type1", "rmw1"});
writable_storage->create_topic({"topic2", "type2", "rmw2"});
writable_storage->create_topic({"topic1", "type1", "rmw1", ""});
writable_storage->create_topic({"topic2", "type2", "rmw2", ""});

const auto read_only_filename = writable_storage->get_relative_file_path();

Expand All @@ -134,8 +134,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"},
rosbag2_storage::TopicMetadata{"topic2", "type2", "rmw2"}
rosbag2_storage::TopicMetadata{"topic1", "type1", "rmw1", ""},
rosbag2_storage::TopicMetadata{"topic2", "type2", "rmw2", ""}
}));
}

Expand Down Expand Up @@ -164,9 +164,9 @@ TEST_F(StorageTestFixture, get_metadata_returns_correct_struct) {
metadata.topics_with_message_count, ElementsAreArray(
{
rosbag2_storage::TopicInformation{rosbag2_storage::TopicMetadata{
"topic1", "type1", "rmw_format"}, 2u},
"topic1", "type1", "rmw_format", ""}, 2u},
rosbag2_storage::TopicInformation{rosbag2_storage::TopicMetadata{
"topic2", "type2", "rmw_format"}, 1u}
"topic2", "type2", "rmw_format", ""}, 1u}
}));
EXPECT_THAT(metadata.message_count, Eq(3u));
EXPECT_THAT(
Expand Down Expand Up @@ -204,8 +204,8 @@ TEST_F(StorageTestFixture, remove_topics_and_types_returns_the_empty_vector) {
const auto read_write_filename = (rcpputils::fs::path(temporary_dir_path_) / "rosbag").string();

writable_storage->open(read_write_filename);
writable_storage->create_topic({"topic1", "type1", "rmw1"});
writable_storage->remove_topic({"topic1", "type1", "rmw1"});
writable_storage->create_topic({"topic1", "type1", "rmw1", ""});
writable_storage->remove_topic({"topic1", "type1", "rmw1", ""});

const auto read_only_filename = writable_storage->get_relative_file_path();

Expand Down
13 changes: 13 additions & 0 deletions rosbag2_transport/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -35,6 +35,7 @@ add_library(${PROJECT_NAME} SHARED
src/rosbag2_transport/formatter.cpp
src/rosbag2_transport/generic_publisher.cpp
src/rosbag2_transport/generic_subscription.cpp
src/rosbag2_transport/qos.cpp
src/rosbag2_transport/recorder.cpp
src/rosbag2_transport/rosbag2_node.cpp
src/rosbag2_transport/rosbag2_transport.cpp)
Expand Down Expand Up @@ -176,6 +177,18 @@ if(BUILD_TESTING)
ament_target_dependencies(test_play test_msgs rosbag2_test_common)
endif()

ament_add_gmock(test_qos
test/rosbag2_transport/test_qos.cpp
WORKING_DIRECTORY ${CMAKE_CURRENT_BINARY_DIR}
${SKIP_TEST})
if(TARGET test_qos)
target_link_libraries(test_qos rosbag2_transport)
target_include_directories(test_qos
PUBLIC
$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/src/rosbag2_transport>)
ament_target_dependencies(test_qos rosbag2_test_common)
endif()

endif()

ament_package()
70 changes: 70 additions & 0 deletions rosbag2_transport/src/rosbag2_transport/qos.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,70 @@
// Copyright 2020 Amazon.com, Inc. or its affiliates. All Rights Reserved.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.

#include "qos.hpp"

namespace YAML
{
Node convert<rmw_time_t>::encode(const rmw_time_t & time)
{
Node node;
node["sec"] = time.sec;
node["nsec"] = time.nsec;
return node;
}

bool convert<rmw_time_t>::decode(const Node & node, rmw_time_t & time)
{
time.sec = node["sec"].as<uint>();
time.nsec = node["nsec"].as<uint>();
Comment on lines +29 to +30
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Suggested change
time.sec = node["sec"].as<uint>();
time.nsec = node["nsec"].as<uint>();
time.sec = node["sec"].as<uint64_t>();
time.nsec = node["nsec"].as<uint64_t>();

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I think this would fix it,

return true;
}

Node convert<rosbag2_transport::Rosbag2QoS>::encode(const rosbag2_transport::Rosbag2QoS & qos)
{
const auto & p = qos.get_rmw_qos_profile();
Node node;
node["history"] = static_cast<int>(p.history);
node["depth"] = p.depth;
node["reliability"] = static_cast<int>(p.reliability);
node["durability"] = static_cast<int>(p.durability);
node["deadline"] = p.deadline;
node["lifespan"] = p.lifespan;
node["liveliness"] = static_cast<int>(p.liveliness);
node["liveliness_lease_duration"] = p.liveliness_lease_duration;
node["avoid_ros_namespace_conventions"] = p.avoid_ros_namespace_conventions;
return node;
}

bool convert<rosbag2_transport::Rosbag2QoS>::decode(
const Node & node, rosbag2_transport::Rosbag2QoS & qos)
{
auto history = static_cast<rmw_qos_history_policy_t>(node["history"].as<int>());
auto reliability = static_cast<rmw_qos_reliability_policy_t>(node["reliability"].as<int>());
auto durability = static_cast<rmw_qos_durability_policy_t>(node["durability"].as<int>());
auto liveliness = static_cast<rmw_qos_liveliness_policy_t>(node["liveliness"].as<int>());

qos
.keep_last(node["depth"].as<int>())
.history(history)
.reliability(reliability)
.durability(durability)
.deadline(node["deadline"].as<rmw_time_t>())
.lifespan(node["lifespan"].as<rmw_time_t>())
.liveliness(liveliness)
.liveliness_lease_duration(node["liveliness_lease_duration"].as<rmw_time_t>())
.avoid_ros_namespace_conventions(node["avoid_ros_namespace_conventions"].as<bool>());
Comment on lines +58 to +67
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I know it's a hard problem to solve, but any idea about how we could try to keep this in sync as qos gets new fields?

Copy link
Collaborator Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I don't have a good answer to this. My thought as of right now is just that rosbag2 needs to have a pass to support new fields if they are added, and until that time it will only support the default values for any given policy.

I'm not aware of a way to introspect fields of a struct in C++, but that doesn't mean there isn't a way

Copy link
Collaborator Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Ah - I thought of something we can do. It is a "change detector" like we try to avoid, but in this case of serialization method, it seems like the right thing to do. I'm adding a test that explicitly builds a rmw_qos_profile_t using {} initializer, so if new fields are added, the build will fail.

Copy link
Contributor

@thomas-moulard thomas-moulard Mar 26, 2020

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Thinking about it, deserialize(serialize(x)) == x should do the trick?

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

If you're sure the qos struct will always be a POD, memcmp is an option otherwise (tread carefully as it can blow up easily)

Copy link
Collaborator Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I don't think it will. If new fields are added - when I construct the object it will use the default values for those new fields. Now when I serialize, it will write out all the fields we specified here. Then, on deserializing, it will read the fields that it knows, with the unknown fields having default values. The equality will pass and new fields will have slipped through undetected

Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

we could maybe apply something like a builder pattern which only allows to build the object if all parts are present. But I don't see a real way around updating the code base if the QoS struct gets more fields.

return true;
}
} // namespace YAML
66 changes: 66 additions & 0 deletions rosbag2_transport/src/rosbag2_transport/qos.hpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,66 @@
// Copyright 2020 Amazon.com, Inc. or its affiliates. All Rights Reserved.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef ROSBAG2_TRANSPORT__QOS_HPP_
#define ROSBAG2_TRANSPORT__QOS_HPP_

#include "rclcpp/qos.hpp"

#ifdef _WIN32
// This is necessary because of a bug in yaml-cpp's cmake
#define YAML_CPP_DLL
// This is necessary because yaml-cpp does not always use dllimport/dllexport consistently
# pragma warning(push)
# pragma warning(disable:4251)
# pragma warning(disable:4275)
#endif
#include "yaml-cpp/yaml.h"
#ifdef _WIN32
# pragma warning(pop)
#endif


Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Suggested change

namespace rosbag2_transport
{
/// Simple wrapper around rclcpp::QoS to provide a default constructor for YAML deserialization.
class Rosbag2QoS : public rclcpp::QoS
{
public:
Rosbag2QoS()
: rclcpp::QoS(0) {} // 0 history depth is always overwritten on deserializing
Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I guess we could also default to rclcpp::SystemsDefaultQos() or something. But I think this doesn't really matter as far as I can understand your comment.

Copy link
Collaborator Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Note that rmw_qos_profile_system_default is different than rmw_qos_profile_default - system_default is dependent on the rmw implementation, and because of that I don't think it's something anybody should ever use.

But, I will instantiate this with the default profile (not system_default)

explicit Rosbag2QoS(const rclcpp::QoS & value)
: rclcpp::QoS(value) {}
};
} // namespace rosbag2_transport

Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Suggested change


namespace YAML
{
template<>
struct convert<rmw_time_t>
{
static Node encode(const rmw_time_t & time);
static bool decode(const Node & node, rmw_time_t & time);
};

template<>
struct convert<rosbag2_transport::Rosbag2QoS>
{
static Node encode(const rosbag2_transport::Rosbag2QoS & qos);
static bool decode(const Node & node, rosbag2_transport::Rosbag2QoS & qos);
};
} // namespace YAML

Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Suggested change


#endif // ROSBAG2_TRANSPORT__QOS_HPP_
Loading