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

Use enum values for offered_qos_profiles in code and string names in serialized metadata #1476

Merged
merged 51 commits into from
Nov 10, 2023
Merged
Show file tree
Hide file tree
Changes from 49 commits
Commits
Show all changes
51 commits
Select commit Hold shift + click to select a range
f34e165
Make C++ QoS YAML (de)serialization compliant with QoS override file …
roncapat Oct 3, 2023
30832e8
UGLY DRAFT - handle different versions of TopicMetadata
roncapat Oct 7, 2023
8d704fe
Handle unknown cases
roncapat Oct 7, 2023
d0434e3
Uncrustify
roncapat Oct 7, 2023
545ec1c
Fix test
roncapat Oct 7, 2023
ec87bcd
Refactor to avoid templates
roncapat Oct 7, 2023
4208cd3
Reduce diff
roncapat Oct 7, 2023
31d98a9
Fix for rosbag2_py
roncapat Oct 7, 2023
a6fb35c
Fix missing include (cpplint)
roncapat Oct 7, 2023
17281e3
WIP: decode everything
roncapat Oct 24, 2023
823dfba
WIP: decode everything
roncapat Oct 24, 2023
afeee44
WIP: decode everything
roncapat Oct 24, 2023
0b7fc66
WIP: decode everything
roncapat Oct 24, 2023
e4164d6
WIP: decode everything
roncapat Oct 25, 2023
b3c1040
WIP: decode everything
roncapat Oct 25, 2023
9a9f9a2
Uncrustify (warning: still draft code)
roncapat Oct 25, 2023
57cc668
Uncrustify
roncapat Oct 25, 2023
827df9d
Try to export dependency
roncapat Oct 25, 2023
e0483dc
Cpplint
roncapat Oct 25, 2023
1359a47
Fix encode bug
roncapat Oct 25, 2023
acf1fc2
Fix transform bug
roncapat Oct 25, 2023
95521bb
Try to fix runtime error with py constructor
roncapat Oct 25, 2023
5083ebb
Fix "test_record"
roncapat Oct 26, 2023
f20226b
Various fixes
roncapat Oct 26, 2023
b080d4f
Various fixes
roncapat Oct 26, 2023
00520e8
Various fixes
roncapat Oct 26, 2023
e22afad
Various fixes
roncapat Oct 26, 2023
fbd5846
Format
roncapat Oct 26, 2023
a7a7356
Format
roncapat Oct 26, 2023
258fb56
Tentative fixes
roncapat Oct 27, 2023
3c24d68
Fixes
roncapat Oct 27, 2023
e1dda74
MCAP Fixes
roncapat Oct 27, 2023
189e25b
History QOS Fixes
roncapat Oct 27, 2023
526f28e
uncrust
roncapat Oct 27, 2023
ded8bf3
Remove VScode files
roncapat Oct 30, 2023
7f9885e
PR Diff analysis & reduction
roncapat Oct 30, 2023
7b970a3
Refactor conversion snippets
roncapat Oct 30, 2023
fe67da8
Uncrustify
roncapat Oct 30, 2023
6cd68a2
Address some comments
roncapat Nov 2, 2023
d8243dd
Address some comments
roncapat Nov 2, 2023
a3ffbc4
Address some comments
roncapat Nov 2, 2023
01f25dd
More fixes
roncapat Nov 2, 2023
6b4c2bd
Fixes for failing tests in the test_qos.cpp
MichaelOrlov Nov 3, 2023
377d1e6
Add qos serialization format auto-detection
MichaelOrlov Nov 3, 2023
cae07aa
Workaround to properly convert offered_qos_profiles in mcap storage
MichaelOrlov Nov 3, 2023
753e3e3
Fix clang format
roncapat Nov 4, 2023
dff7cdf
Last fixes
roncapat Nov 6, 2023
de95fbb
Fix visibility
roncapat Nov 7, 2023
3bcc025
Uncrust
roncapat Nov 7, 2023
fc19114
Fix DLL troubles with yaml-cpp
roncapat Nov 8, 2023
39c453c
Metadata V9 offered_qos_profiles as pure YAML
roncapat Nov 9, 2023
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
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_, "", ""};
"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 @@ -243,7 +243,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({test_topic_name, test_topic_type, "", {}, ""});

auto message = std::make_shared<rosbag2_storage::SerializedBagMessage>();
message->topic_name = test_topic_name;
Expand Down Expand Up @@ -285,7 +285,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({test_topic_name, test_topic_type, "", {}, ""});

auto message = std::make_shared<rosbag2_storage::SerializedBagMessage>();
message->topic_name = test_topic_name;
Expand Down Expand Up @@ -323,7 +323,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({test_topic_name, test_topic_type, "", {}, ""});

auto message = std::make_shared<rosbag2_storage::SerializedBagMessage>();
message->topic_name = test_topic_name;
Expand Down Expand Up @@ -370,7 +370,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({test_topic_name, test_topic_type, "", {}, ""});

auto message = std::make_shared<rosbag2_storage::SerializedBagMessage>();
message->topic_name = test_topic_name;
Expand Down
2 changes: 1 addition & 1 deletion rosbag2_cpp/src/rosbag2_cpp/reindexer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -208,7 +208,7 @@ void Reindexer::aggregate_metadata(
ROSBAG2_CPP_LOG_DEBUG_STREAM("Found topic!");
// Merge in the new information
found_topic->second.message_count += topic.message_count;
if (topic.topic_metadata.offered_qos_profiles != "") {
if (!topic.topic_metadata.offered_qos_profiles.empty()) {
found_topic->second.topic_metadata.offered_qos_profiles =
topic.topic_metadata.offered_qos_profiles;
}
Expand Down
2 changes: 1 addition & 1 deletion rosbag2_cpp/test/rosbag2_cpp/fake_data.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -37,7 +37,7 @@ void write_sample_split_bag(
topic_name,
"test_msgs/msg/ByteMultiArray",
"cdr",
"",
{},
""
},
{
Expand Down
22 changes: 14 additions & 8 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{{"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{{"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 All @@ -121,13 +121,19 @@ TEST_P(ParametrizedTemporaryDirectoryFixture, read_metadata_supports_version_6)
" name: topic1\n"
" type: type1\n"
" serialization_format: rmw1\n"
" offered_qos_profiles: default\n"
" offered_qos_profiles: \"- history: 1\\n depth: 1\\n reliability: 1\\n durability: "
"2\\n deadline:\\n sec: 0\\n nsec: 0\\n lifespan:\\n sec: 0\\n nsec: 0\\n "
"liveliness: 0\\n liveliness_lease_duration:\\n sec: 0\\n nsec: 0\\n "
"avoid_ros_namespace_conventions: false\"\n"
" message_count: 100\n"
" - topic_metadata:\n"
" name: topic2\n"
" type: type2\n"
" serialization_format: rmw2\n"
" offered_qos_profiles: default\n"
" offered_qos_profiles: \"- history: 1\\n depth: 1\\n reliability: 1\\n durability: "
"2\\n deadline:\\n sec: 0\\n nsec: 0\\n lifespan:\\n sec: 0\\n nsec: 0\\n "
"liveliness: 0\\n liveliness_lease_duration:\\n sec: 0\\n nsec: 0\\n "
"avoid_ros_namespace_conventions: false\"\n"
" message_count: 200\n"
" compression_format: \"zstd\"\n"
" compression_mode: \"FILE\"\n"
Expand Down Expand Up @@ -186,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{{"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 @@ -195,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{{"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 @@ -256,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};
{{"topic1", "type1", "rmw1", {}, ""}, 100};
EXPECT_THAT(
actual_first_topic.topic_metadata.name,
Eq(expected_first_topic.topic_metadata.name));
Expand All @@ -269,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};
{{"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_, "", ""};
"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({"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({"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({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({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({"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({"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({"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({"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({"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({"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({"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({"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 @@ -56,7 +56,7 @@ TEST_F(StorageWithoutMetadataFileTest, open_uses_storage_id_from_storage_options
"topic",
"test_msgs/BasicTypes",
kRmwFormat,
"",
{},
""
};

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -37,7 +37,7 @@ int main(int, char **)
"synthetic",
"example_interfaces/msg/Int32",
rmw_get_serialization_format(),
"",
{},
""
});

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -38,7 +38,7 @@ class DataGenerator : public rclcpp::Node
"synthetic",
"example_interfaces/msg/Int32",
rmw_get_serialization_format(),
"",
{},
"",
});

Expand Down
61 changes: 59 additions & 2 deletions rosbag2_py/src/rosbag2_py/_storage.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -23,6 +23,7 @@
#include "rosbag2_storage/storage_interfaces/base_read_interface.hpp"
#include "rosbag2_storage/storage_options.hpp"
#include "rosbag2_storage/topic_metadata.hpp"
#include "rosbag2_storage/qos.hpp"

#include "./format_bag_metadata.hpp"

Expand Down Expand Up @@ -152,13 +153,69 @@ PYBIND11_MODULE(_storage, m) {
&rosbag2_storage::MessageDefinition::encoded_message_definition)
.def_readwrite("type_hash", &rosbag2_storage::MessageDefinition::type_hash);

pybind11::enum_<rmw_qos_history_policy_t>(m, "rmw_qos_history_policy_t")
.value("RMW_QOS_POLICY_HISTORY_SYSTEM_DEFAULT", RMW_QOS_POLICY_HISTORY_SYSTEM_DEFAULT)
.value("RMW_QOS_POLICY_HISTORY_KEEP_LAST", RMW_QOS_POLICY_HISTORY_KEEP_LAST)
.value("RMW_QOS_POLICY_HISTORY_KEEP_ALL", RMW_QOS_POLICY_HISTORY_KEEP_ALL)
.value("RMW_QOS_POLICY_HISTORY_UNKNOWN", RMW_QOS_POLICY_HISTORY_UNKNOWN);

pybind11::enum_<rmw_qos_reliability_policy_t>(m, "rmw_qos_reliability_policy_t")
.value("RMW_QOS_POLICY_RELIABILITY_SYSTEM_DEFAULT", RMW_QOS_POLICY_RELIABILITY_SYSTEM_DEFAULT)
.value("RMW_QOS_POLICY_RELIABILITY_RELIABLE", RMW_QOS_POLICY_RELIABILITY_RELIABLE)
.value("RMW_QOS_POLICY_RELIABILITY_BEST_EFFORT", RMW_QOS_POLICY_RELIABILITY_BEST_EFFORT)
.value("RMW_QOS_POLICY_RELIABILITY_UNKNOWN", RMW_QOS_POLICY_RELIABILITY_UNKNOWN);

pybind11::enum_<rmw_qos_durability_policy_t>(m, "rmw_qos_durability_policy_t")
.value("RMW_QOS_POLICY_DURABILITY_SYSTEM_DEFAULT", RMW_QOS_POLICY_DURABILITY_SYSTEM_DEFAULT)
.value("RMW_QOS_POLICY_DURABILITY_TRANSIENT_LOCAL", RMW_QOS_POLICY_DURABILITY_TRANSIENT_LOCAL)
.value("RMW_QOS_POLICY_DURABILITY_VOLATILE", RMW_QOS_POLICY_DURABILITY_VOLATILE)
.value("RMW_QOS_POLICY_DURABILITY_UNKNOWN", RMW_QOS_POLICY_DURABILITY_UNKNOWN);


pybind11::enum_<rmw_qos_liveliness_policy_t>(m, "rmw_qos_liveliness_policy_t")
.value("RMW_QOS_POLICY_LIVELINESS_SYSTEM_DEFAULT", RMW_QOS_POLICY_LIVELINESS_SYSTEM_DEFAULT)
.value("RMW_QOS_POLICY_LIVELINESS_AUTOMATIC", RMW_QOS_POLICY_LIVELINESS_AUTOMATIC)
.value("RMW_QOS_POLICY_LIVELINESS_MANUAL_BY_TOPIC", RMW_QOS_POLICY_LIVELINESS_MANUAL_BY_TOPIC)
.value("RMW_QOS_POLICY_LIVELINESS_UNKNOWN", RMW_QOS_POLICY_LIVELINESS_UNKNOWN);

pybind11::class_<rclcpp::Duration>(m, "Duration")
.def(
pybind11::init<int32_t, uint32_t>(),
pybind11::arg("seconds"),
pybind11::arg("nanoseconds"));

pybind11::class_<rclcpp::QoS>(m, "QoS")
.def(
pybind11::init<size_t>(),
pybind11::arg("history_depth"))
.def("keep_last", &rclcpp::QoS::keep_last)
.def("keep_all", &rclcpp::QoS::keep_all)
.def("reliable", &rclcpp::QoS::reliable)
.def("best_effort", &rclcpp::QoS::best_effort)
.def("durability_volatile", &rclcpp::QoS::durability_volatile)
.def("transient_local", &rclcpp::QoS::transient_local)
.def("history", pybind11::overload_cast<rmw_qos_history_policy_t>(&rclcpp::QoS::history))
.def(
"reliability",
pybind11::overload_cast<rmw_qos_reliability_policy_t>(&rclcpp::QoS::reliability))
.def("durability", pybind11::overload_cast<rmw_qos_durability_policy_t>(&rclcpp::QoS::durability))
.def("liveliness", pybind11::overload_cast<rmw_qos_liveliness_policy_t>(&rclcpp::QoS::liveliness))
.def("deadline", pybind11::overload_cast<const rclcpp::Duration &>(&rclcpp::QoS::deadline))
.def("lifespan", pybind11::overload_cast<const rclcpp::Duration &>(&rclcpp::QoS::lifespan))
.def(
"liveliness_lease_duration",
pybind11::overload_cast<const rclcpp::Duration &>(&rclcpp::QoS::liveliness_lease_duration))
.def(
"avoid_ros_namespace_conventions",
pybind11::overload_cast<bool>(&rclcpp::QoS::avoid_ros_namespace_conventions));

pybind11::class_<rosbag2_storage::TopicMetadata>(m, "TopicMetadata")
.def(
pybind11::init<std::string, std::string, std::string, std::string, std::string>(),
pybind11::init<std::string, std::string, std::string, std::vector<rclcpp::QoS>, std::string>(),
pybind11::arg("name"),
pybind11::arg("type"),
pybind11::arg("serialization_format"),
pybind11::arg("offered_qos_profiles") = "",
pybind11::arg("offered_qos_profiles") = std::vector<rclcpp::QoS>(),
pybind11::arg("type_description_hash") = "")
.def_readwrite("name", &rosbag2_storage::TopicMetadata::name)
.def_readwrite("type", &rosbag2_storage::TopicMetadata::type)
Expand Down
2 changes: 1 addition & 1 deletion rosbag2_py/src/rosbag2_py/_transport.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -295,7 +295,7 @@ void bag_rewrite(
rosbag2_storage::StorageOptions storage_options{};
YAML::convert<rosbag2_storage::StorageOptions>::decode(bag_node, storage_options);
rosbag2_transport::RecordOptions record_options = bag_rewrite_default_record_options();
YAML::convert<rosbag2_transport::RecordOptions>::decode(bag_node, record_options);
record_options = bag_node.as<rosbag2_transport::RecordOptions>();
output_options.push_back(std::make_pair(storage_options, record_options));
}
rosbag2_transport::bag_rewrite(input_options, output_options);
Expand Down
Loading
Loading