From ebca8d12395eb831339f89ffadd69f04e4b8de2f Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Alejandro=20Hern=C3=A1ndez=20Cordero?= Date: Thu, 16 May 2024 16:10:21 +0200 Subject: [PATCH 01/11] Added convert_rosbag_qos_to_rlcpy_qos function MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: Alejandro Hernández Cordero --- rosbag2_py/rosbag2_py/__init__.py | 2 ++ rosbag2_py/rosbag2_py/_storage.pyi | 2 ++ rosbag2_py/src/rosbag2_py/_storage.cpp | 36 ++++++++++++++++++++++++++ rosbag2_py/src/rosbag2_py/pybind11.hpp | 1 + 4 files changed, 41 insertions(+) diff --git a/rosbag2_py/rosbag2_py/__init__.py b/rosbag2_py/rosbag2_py/__init__.py index 6f084da507..adced46705 100644 --- a/rosbag2_py/rosbag2_py/__init__.py +++ b/rosbag2_py/rosbag2_py/__init__.py @@ -41,6 +41,7 @@ StorageOptions, TopicMetadata, TopicInformation, + convert_rosbag_qos_to_rlcpy_qos, get_default_storage_id, to_rclcpp_qos_vector, ) @@ -68,6 +69,7 @@ __all__ = [ 'bag_rewrite', + 'convert_rosbag_qos_to_rlcpy_qos', 'CompressionMode', 'CompressionOptions', 'compression_mode_from_string', diff --git a/rosbag2_py/rosbag2_py/_storage.pyi b/rosbag2_py/rosbag2_py/_storage.pyi index abf846c7ce..e839c12308 100644 --- a/rosbag2_py/rosbag2_py/_storage.pyi +++ b/rosbag2_py/rosbag2_py/_storage.pyi @@ -1,6 +1,7 @@ from typing import ClassVar, Dict, List import datetime +from rclpy import QoSProfile class BagMetadata: bag_size: int @@ -214,3 +215,4 @@ class rmw_qos_reliability_policy_t: def get_default_storage_id() -> str: ... def to_rclcpp_qos_vector(arg0: str, arg1: int) -> List[QoS]: ... +def convert_rosbag_qos_to_rlcpy_qos(arg0: QoS) -> List[QoSProfile]: ... diff --git a/rosbag2_py/src/rosbag2_py/_storage.cpp b/rosbag2_py/src/rosbag2_py/_storage.cpp index 4fc0999308..07eacc7952 100644 --- a/rosbag2_py/src/rosbag2_py/_storage.cpp +++ b/rosbag2_py/src/rosbag2_py/_storage.cpp @@ -391,6 +391,42 @@ PYBIND11_MODULE(_storage, m) { &rosbag2_storage::to_rclcpp_qos_vector, "Convert QoS in YAML to std::vector"); + m.def( + "convert_rosbag_qos_to_rlcpy_qos", + [](rclcpp::QoS qos_input) { + pybind11::object rclcpy_qos = pybind11::module_::import("rclpy.qos"); + pybind11::object rclcpy_duration = pybind11::module_::import("rclpy.duration"); + pybind11::object duration_lifespan = rclcpy_qos.attr("Duration")( + "seconds"_a=qos_input.lifespan().to_rmw_time().sec, + "nanoseconds"_a=qos_input.lifespan().to_rmw_time().nsec); + pybind11::object duration_deadline = rclcpy_qos.attr("Duration")( + "seconds"_a=qos_input.deadline().to_rmw_time().sec, + "nanoseconds"_a=qos_input.deadline().to_rmw_time().nsec); + pybind11::object duration_liveliness_lease_duration = rclcpy_qos.attr("Duration")( + "seconds"_a=qos_input.liveliness_lease_duration().to_rmw_time().sec, + "nanoseconds"_a=qos_input.liveliness_lease_duration().to_rmw_time().nsec); + + auto history = rclcpp::HistoryPolicy::KeepLast; + if (qos_input.history() != rclcpp::HistoryPolicy::Unknown) { + history = qos_input.history(); + } + + using namespace pybind11::literals; + pybind11::object qos_profile = rclcpy_qos.attr("QoSProfile")( + "depth"_a=qos_input.depth(), + "history"_a=static_cast(history), + "reliability"_a=static_cast(qos_input.reliability()), + "durability"_a=static_cast(qos_input.durability()), + "lifespan"_a=duration_lifespan, + "deadline"_a=duration_deadline, + "liveliness"_a=static_cast(qos_input.liveliness()), + "liveliness_lease_duration"_a=duration_liveliness_lease_duration, + "avoid_ros_namespace_conventions"_a=static_cast(qos_input.avoid_ros_namespace_conventions())); + + return qos_profile; + }, + "Convert QoS in YAML to std::vector"); + pybind11::class_(m, "MetadataIo") .def(pybind11::init<>()) .def("write_metadata", &rosbag2_storage::MetadataIo::write_metadata) diff --git a/rosbag2_py/src/rosbag2_py/pybind11.hpp b/rosbag2_py/src/rosbag2_py/pybind11.hpp index fd6fa9af16..fd25c34ce9 100644 --- a/rosbag2_py/src/rosbag2_py/pybind11.hpp +++ b/rosbag2_py/src/rosbag2_py/pybind11.hpp @@ -27,5 +27,6 @@ #endif #include #include +#include #endif // ROSBAG2_PY__PYBIND11_HPP_ From 910fc2ed8d600d500ab05dc5dece821e63f74162 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Alejandro=20Hern=C3=A1ndez=20Cordero?= Date: Thu, 16 May 2024 16:14:23 +0200 Subject: [PATCH 02/11] make linters happy MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: Alejandro Hernández Cordero --- rosbag2_py/src/rosbag2_py/_storage.cpp | 33 +++++++++++++------------- 1 file changed, 17 insertions(+), 16 deletions(-) diff --git a/rosbag2_py/src/rosbag2_py/_storage.cpp b/rosbag2_py/src/rosbag2_py/_storage.cpp index 07eacc7952..122a72574e 100644 --- a/rosbag2_py/src/rosbag2_py/_storage.cpp +++ b/rosbag2_py/src/rosbag2_py/_storage.cpp @@ -397,31 +397,32 @@ PYBIND11_MODULE(_storage, m) { pybind11::object rclcpy_qos = pybind11::module_::import("rclpy.qos"); pybind11::object rclcpy_duration = pybind11::module_::import("rclpy.duration"); pybind11::object duration_lifespan = rclcpy_qos.attr("Duration")( - "seconds"_a=qos_input.lifespan().to_rmw_time().sec, - "nanoseconds"_a=qos_input.lifespan().to_rmw_time().nsec); + "seconds"_a = qos_input.lifespan().to_rmw_time().sec, + "nanoseconds"_a = qos_input.lifespan().to_rmw_time().nsec); pybind11::object duration_deadline = rclcpy_qos.attr("Duration")( - "seconds"_a=qos_input.deadline().to_rmw_time().sec, - "nanoseconds"_a=qos_input.deadline().to_rmw_time().nsec); + "seconds"_a = qos_input.deadline().to_rmw_time().sec, + "nanoseconds"_a = qos_input.deadline().to_rmw_time().nsec); pybind11::object duration_liveliness_lease_duration = rclcpy_qos.attr("Duration")( - "seconds"_a=qos_input.liveliness_lease_duration().to_rmw_time().sec, - "nanoseconds"_a=qos_input.liveliness_lease_duration().to_rmw_time().nsec); + "seconds"_a = qos_input.liveliness_lease_duration().to_rmw_time().sec, + "nanoseconds"_a = qos_input.liveliness_lease_duration().to_rmw_time().nsec); auto history = rclcpp::HistoryPolicy::KeepLast; if (qos_input.history() != rclcpp::HistoryPolicy::Unknown) { - history = qos_input.history(); + history = qos_input.history(); } using namespace pybind11::literals; pybind11::object qos_profile = rclcpy_qos.attr("QoSProfile")( - "depth"_a=qos_input.depth(), - "history"_a=static_cast(history), - "reliability"_a=static_cast(qos_input.reliability()), - "durability"_a=static_cast(qos_input.durability()), - "lifespan"_a=duration_lifespan, - "deadline"_a=duration_deadline, - "liveliness"_a=static_cast(qos_input.liveliness()), - "liveliness_lease_duration"_a=duration_liveliness_lease_duration, - "avoid_ros_namespace_conventions"_a=static_cast(qos_input.avoid_ros_namespace_conventions())); + "depth"_a = qos_input.depth(), + "history"_a = static_cast(history), + "reliability"_a = static_cast(qos_input.reliability()), + "durability"_a = static_cast(qos_input.durability()), + "lifespan"_a = duration_lifespan, + "deadline"_a = duration_deadline, + "liveliness"_a = static_cast(qos_input.liveliness()), + "liveliness_lease_duration"_a = duration_liveliness_lease_duration, + "avoid_ros_namespace_conventions"_a = + static_cast(qos_input.avoid_ros_namespace_conventions())); return qos_profile; }, From df8407b053abe43802952ccd0f3b3f991ce33e59 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Alejandro=20Hern=C3=A1ndez=20Cordero?= Date: Thu, 16 May 2024 16:26:27 +0200 Subject: [PATCH 03/11] make linters happy MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: Alejandro Hernández Cordero --- rosbag2_py/src/rosbag2_py/_storage.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/rosbag2_py/src/rosbag2_py/_storage.cpp b/rosbag2_py/src/rosbag2_py/_storage.cpp index 122a72574e..80cc5cc5a3 100644 --- a/rosbag2_py/src/rosbag2_py/_storage.cpp +++ b/rosbag2_py/src/rosbag2_py/_storage.cpp @@ -411,7 +411,6 @@ PYBIND11_MODULE(_storage, m) { history = qos_input.history(); } - using namespace pybind11::literals; pybind11::object qos_profile = rclcpy_qos.attr("QoSProfile")( "depth"_a = qos_input.depth(), "history"_a = static_cast(history), @@ -422,7 +421,8 @@ PYBIND11_MODULE(_storage, m) { "liveliness"_a = static_cast(qos_input.liveliness()), "liveliness_lease_duration"_a = duration_liveliness_lease_duration, "avoid_ros_namespace_conventions"_a = - static_cast(qos_input.avoid_ros_namespace_conventions())); + static_cast( + qos_input.avoid_ros_namespace_conventions())); // cppcheck-suppress assignBoolToPointer return qos_profile; }, From 98596c75939bc084ddbc7cd1df3677d3c56d3308 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Alejandro=20Hern=C3=A1ndez=20Cordero?= Date: Thu, 16 May 2024 16:38:37 +0200 Subject: [PATCH 04/11] make linters happy MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: Alejandro Hernández Cordero --- rosbag2_py/src/rosbag2_py/_storage.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/rosbag2_py/src/rosbag2_py/_storage.cpp b/rosbag2_py/src/rosbag2_py/_storage.cpp index 80cc5cc5a3..f08c55b21a 100644 --- a/rosbag2_py/src/rosbag2_py/_storage.cpp +++ b/rosbag2_py/src/rosbag2_py/_storage.cpp @@ -420,9 +420,9 @@ PYBIND11_MODULE(_storage, m) { "deadline"_a = duration_deadline, "liveliness"_a = static_cast(qos_input.liveliness()), "liveliness_lease_duration"_a = duration_liveliness_lease_duration, - "avoid_ros_namespace_conventions"_a = + "avoid_ros_namespace_conventions"_a = // cppcheck-suppress assignBoolToPointer static_cast( - qos_input.avoid_ros_namespace_conventions())); // cppcheck-suppress assignBoolToPointer + qos_input.avoid_ros_namespace_conventions())); return qos_profile; }, From 2d8372a10a1c6de8a0fb9564cc1f1f6186eec168 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Alejandro=20Hern=C3=A1ndez=20Cordero?= Date: Thu, 16 May 2024 17:07:42 +0200 Subject: [PATCH 05/11] make linters happy MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: Alejandro Hernández Cordero --- rosbag2_py/src/rosbag2_py/_storage.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/rosbag2_py/src/rosbag2_py/_storage.cpp b/rosbag2_py/src/rosbag2_py/_storage.cpp index f08c55b21a..c5034ebe37 100644 --- a/rosbag2_py/src/rosbag2_py/_storage.cpp +++ b/rosbag2_py/src/rosbag2_py/_storage.cpp @@ -420,8 +420,8 @@ PYBIND11_MODULE(_storage, m) { "deadline"_a = duration_deadline, "liveliness"_a = static_cast(qos_input.liveliness()), "liveliness_lease_duration"_a = duration_liveliness_lease_duration, - "avoid_ros_namespace_conventions"_a = // cppcheck-suppress assignBoolToPointer - static_cast( + "avoid_ros_namespace_conventions"_a = + static_cast( qos_input.avoid_ros_namespace_conventions())); return qos_profile; From 6ede3d911ce6347408aa55b9405333fde2934c16 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Alejandro=20Hern=C3=A1ndez=20Cordero?= Date: Thu, 16 May 2024 17:11:17 +0200 Subject: [PATCH 06/11] make linters happy MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: Alejandro Hernández Cordero --- rosbag2_py/src/rosbag2_py/_storage.cpp | 4 +--- 1 file changed, 1 insertion(+), 3 deletions(-) diff --git a/rosbag2_py/src/rosbag2_py/_storage.cpp b/rosbag2_py/src/rosbag2_py/_storage.cpp index c5034ebe37..55f32110ed 100644 --- a/rosbag2_py/src/rosbag2_py/_storage.cpp +++ b/rosbag2_py/src/rosbag2_py/_storage.cpp @@ -420,9 +420,7 @@ PYBIND11_MODULE(_storage, m) { "deadline"_a = duration_deadline, "liveliness"_a = static_cast(qos_input.liveliness()), "liveliness_lease_duration"_a = duration_liveliness_lease_duration, - "avoid_ros_namespace_conventions"_a = - static_cast( - qos_input.avoid_ros_namespace_conventions())); + "avoid_ros_namespace_conventions"_a = qos_input.avoid_ros_namespace_conventions()); return qos_profile; }, From 61d04ef66d891d036d62ff51c068a0ce2657c783 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Alejandro=20Hern=C3=A1ndez=20Cordero?= Date: Thu, 16 May 2024 18:26:49 +0200 Subject: [PATCH 07/11] make linters happy MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: Alejandro Hernández Cordero --- rosbag2_py/rosbag2_py/_storage.pyi | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/rosbag2_py/rosbag2_py/_storage.pyi b/rosbag2_py/rosbag2_py/_storage.pyi index e839c12308..e5f56e0602 100644 --- a/rosbag2_py/rosbag2_py/_storage.pyi +++ b/rosbag2_py/rosbag2_py/_storage.pyi @@ -1,7 +1,6 @@ from typing import ClassVar, Dict, List import datetime -from rclpy import QoSProfile class BagMetadata: bag_size: int @@ -213,6 +212,6 @@ class rmw_qos_reliability_policy_t: @property def value(self) -> int: ... +def convert_rosbag_qos_to_rlcpy_qos(arg0: QoS) -> object: ... def get_default_storage_id() -> str: ... def to_rclcpp_qos_vector(arg0: str, arg1: int) -> List[QoS]: ... -def convert_rosbag_qos_to_rlcpy_qos(arg0: QoS) -> List[QoSProfile]: ... From e7b66bf411eec1c6ac48c6ed7b5f3ca3f655dc47 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Alejandro=20Hern=C3=A1ndez=20Cordero?= Date: Thu, 16 May 2024 19:30:50 +0200 Subject: [PATCH 08/11] make linters happy MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: Alejandro Hernández Cordero --- rosbag2_py/rosbag2_py/__init__.pyi | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/rosbag2_py/rosbag2_py/__init__.pyi b/rosbag2_py/rosbag2_py/__init__.pyi index a6ed335a19..7e84de91e9 100644 --- a/rosbag2_py/rosbag2_py/__init__.pyi +++ b/rosbag2_py/rosbag2_py/__init__.pyi @@ -2,6 +2,6 @@ from rosbag2_py._compression_options import CompressionMode as CompressionMode, from rosbag2_py._info import Info as Info from rosbag2_py._reader import SequentialCompressionReader as SequentialCompressionReader, SequentialReader as SequentialReader, get_registered_readers as get_registered_readers from rosbag2_py._reindexer import Reindexer as Reindexer -from rosbag2_py._storage import BagMetadata as BagMetadata, ConverterOptions as ConverterOptions, FileInformation as FileInformation, MessageDefinition as MessageDefinition, MetadataIo as MetadataIo, ReadOrder as ReadOrder, ReadOrderSortBy as ReadOrderSortBy, StorageFilter as StorageFilter, StorageOptions as StorageOptions, TopicInformation as TopicInformation, TopicMetadata as TopicMetadata, get_default_storage_id as get_default_storage_id, to_rclcpp_qos_vector as to_rclcpp_qos_vector +from rosbag2_py._storage import BagMetadata as BagMetadata, ConverterOptions as ConverterOptions, FileInformation as FileInformation, MessageDefinition as MessageDefinition, MetadataIo as MetadataIo, ReadOrder as ReadOrder, ReadOrderSortBy as ReadOrderSortBy, StorageFilter as StorageFilter, StorageOptions as StorageOptions, TopicInformation as TopicInformation, TopicMetadata as TopicMetadata, convert_rosbag_qos_to_rlcpy_qos as convert_rosbag_qos_to_rlcpy_qos, get_default_storage_id as get_default_storage_id, to_rclcpp_qos_vector as to_rclcpp_qos_vector from rosbag2_py._transport import PlayOptions as PlayOptions, Player as Player, RecordOptions as RecordOptions, Recorder as Recorder, ServiceRequestsSource as ServiceRequestsSource, bag_rewrite as bag_rewrite from rosbag2_py._writer import SequentialCompressionWriter as SequentialCompressionWriter, SequentialWriter as SequentialWriter, get_registered_compressors as get_registered_compressors, get_registered_serializers as get_registered_serializers, get_registered_writers as get_registered_writers From 9b7cca911ba2d6b258ed639ce48418013ad343c6 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Alejandro=20Hern=C3=A1ndez=20Cordero?= Date: Wed, 22 May 2024 15:17:25 +0200 Subject: [PATCH 09/11] Added feedback MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: Alejandro Hernández Cordero --- rosbag2_py/rosbag2_py/__init__.py | 4 ++-- rosbag2_py/rosbag2_py/__init__.pyi | 2 +- rosbag2_py/rosbag2_py/_storage.pyi | 2 +- rosbag2_py/src/rosbag2_py/_storage.cpp | 4 ++-- 4 files changed, 6 insertions(+), 6 deletions(-) diff --git a/rosbag2_py/rosbag2_py/__init__.py b/rosbag2_py/rosbag2_py/__init__.py index adced46705..cb105753a9 100644 --- a/rosbag2_py/rosbag2_py/__init__.py +++ b/rosbag2_py/rosbag2_py/__init__.py @@ -41,7 +41,7 @@ StorageOptions, TopicMetadata, TopicInformation, - convert_rosbag_qos_to_rlcpy_qos, + convert_rclcpp_qos_to_rclpy_qos, get_default_storage_id, to_rclcpp_qos_vector, ) @@ -69,7 +69,7 @@ __all__ = [ 'bag_rewrite', - 'convert_rosbag_qos_to_rlcpy_qos', + 'convert_rclcpp_qos_to_rclpy_qos', 'CompressionMode', 'CompressionOptions', 'compression_mode_from_string', diff --git a/rosbag2_py/rosbag2_py/__init__.pyi b/rosbag2_py/rosbag2_py/__init__.pyi index 7e84de91e9..1b554a21ad 100644 --- a/rosbag2_py/rosbag2_py/__init__.pyi +++ b/rosbag2_py/rosbag2_py/__init__.pyi @@ -2,6 +2,6 @@ from rosbag2_py._compression_options import CompressionMode as CompressionMode, from rosbag2_py._info import Info as Info from rosbag2_py._reader import SequentialCompressionReader as SequentialCompressionReader, SequentialReader as SequentialReader, get_registered_readers as get_registered_readers from rosbag2_py._reindexer import Reindexer as Reindexer -from rosbag2_py._storage import BagMetadata as BagMetadata, ConverterOptions as ConverterOptions, FileInformation as FileInformation, MessageDefinition as MessageDefinition, MetadataIo as MetadataIo, ReadOrder as ReadOrder, ReadOrderSortBy as ReadOrderSortBy, StorageFilter as StorageFilter, StorageOptions as StorageOptions, TopicInformation as TopicInformation, TopicMetadata as TopicMetadata, convert_rosbag_qos_to_rlcpy_qos as convert_rosbag_qos_to_rlcpy_qos, get_default_storage_id as get_default_storage_id, to_rclcpp_qos_vector as to_rclcpp_qos_vector +from rosbag2_py._storage import BagMetadata as BagMetadata, ConverterOptions as ConverterOptions, FileInformation as FileInformation, MessageDefinition as MessageDefinition, MetadataIo as MetadataIo, ReadOrder as ReadOrder, ReadOrderSortBy as ReadOrderSortBy, StorageFilter as StorageFilter, StorageOptions as StorageOptions, TopicInformation as TopicInformation, TopicMetadata as TopicMetadata, convert_rclcpp_qos_to_rclpy_qos as convert_rclcpp_qos_to_rclpy_qos, get_default_storage_id as get_default_storage_id, to_rclcpp_qos_vector as to_rclcpp_qos_vector from rosbag2_py._transport import PlayOptions as PlayOptions, Player as Player, RecordOptions as RecordOptions, Recorder as Recorder, ServiceRequestsSource as ServiceRequestsSource, bag_rewrite as bag_rewrite from rosbag2_py._writer import SequentialCompressionWriter as SequentialCompressionWriter, SequentialWriter as SequentialWriter, get_registered_compressors as get_registered_compressors, get_registered_serializers as get_registered_serializers, get_registered_writers as get_registered_writers diff --git a/rosbag2_py/rosbag2_py/_storage.pyi b/rosbag2_py/rosbag2_py/_storage.pyi index e5f56e0602..f99b0c2f60 100644 --- a/rosbag2_py/rosbag2_py/_storage.pyi +++ b/rosbag2_py/rosbag2_py/_storage.pyi @@ -212,6 +212,6 @@ class rmw_qos_reliability_policy_t: @property def value(self) -> int: ... -def convert_rosbag_qos_to_rlcpy_qos(arg0: QoS) -> object: ... +def convert_rclcpp_qos_to_rclpy_qos(arg0: QoS) -> object: ... def get_default_storage_id() -> str: ... def to_rclcpp_qos_vector(arg0: str, arg1: int) -> List[QoS]: ... diff --git a/rosbag2_py/src/rosbag2_py/_storage.cpp b/rosbag2_py/src/rosbag2_py/_storage.cpp index 55f32110ed..4c2f5ebab5 100644 --- a/rosbag2_py/src/rosbag2_py/_storage.cpp +++ b/rosbag2_py/src/rosbag2_py/_storage.cpp @@ -392,7 +392,7 @@ PYBIND11_MODULE(_storage, m) { "Convert QoS in YAML to std::vector"); m.def( - "convert_rosbag_qos_to_rlcpy_qos", + "convert_rclcpp_qos_to_rclpy_qos", [](rclcpp::QoS qos_input) { pybind11::object rclcpy_qos = pybind11::module_::import("rclpy.qos"); pybind11::object rclcpy_duration = pybind11::module_::import("rclpy.duration"); @@ -424,7 +424,7 @@ PYBIND11_MODULE(_storage, m) { return qos_profile; }, - "Convert QoS in YAML to std::vector"); + "Converts rclcpp::QoS to rclpy.qos"); pybind11::class_(m, "MetadataIo") .def(pybind11::init<>()) From 77a6e34a27074605d502a08dee67e37ada647c9e Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Alejandro=20Hern=C3=A1ndez=20Cordero?= Date: Tue, 20 Aug 2024 13:31:22 +0200 Subject: [PATCH 10/11] updated code MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: Alejandro Hernández Cordero --- rosbag2_py/src/rosbag2_py/_storage.cpp | 7 +------ 1 file changed, 1 insertion(+), 6 deletions(-) diff --git a/rosbag2_py/src/rosbag2_py/_storage.cpp b/rosbag2_py/src/rosbag2_py/_storage.cpp index 4c2f5ebab5..e12898053d 100644 --- a/rosbag2_py/src/rosbag2_py/_storage.cpp +++ b/rosbag2_py/src/rosbag2_py/_storage.cpp @@ -406,14 +406,9 @@ PYBIND11_MODULE(_storage, m) { "seconds"_a = qos_input.liveliness_lease_duration().to_rmw_time().sec, "nanoseconds"_a = qos_input.liveliness_lease_duration().to_rmw_time().nsec); - auto history = rclcpp::HistoryPolicy::KeepLast; - if (qos_input.history() != rclcpp::HistoryPolicy::Unknown) { - history = qos_input.history(); - } - pybind11::object qos_profile = rclcpy_qos.attr("QoSProfile")( "depth"_a = qos_input.depth(), - "history"_a = static_cast(history), + "history"_a = static_cast(qos_input.history()), "reliability"_a = static_cast(qos_input.reliability()), "durability"_a = static_cast(qos_input.durability()), "lifespan"_a = duration_lifespan, From f1237a7ed29c16109458b27a479f67e04fc23533 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Alejandro=20Hern=C3=A1ndez=20Cordero?= Date: Tue, 20 Aug 2024 15:13:28 +0200 Subject: [PATCH 11/11] Fix MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: Alejandro Hernández Cordero --- rosbag2_py/rosbag2_py/__init__.pyi | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/rosbag2_py/rosbag2_py/__init__.pyi b/rosbag2_py/rosbag2_py/__init__.pyi index 47b25ed80e..c38eaa3383 100644 --- a/rosbag2_py/rosbag2_py/__init__.pyi +++ b/rosbag2_py/rosbag2_py/__init__.pyi @@ -7,4 +7,4 @@ from rosbag2_py._storage import BagMetadata as BagMetadata, ConverterOptions as from rosbag2_py._transport import PlayOptions as PlayOptions, Player as Player, RecordOptions as RecordOptions, Recorder as Recorder, ServiceRequestsSource as ServiceRequestsSource, bag_rewrite as bag_rewrite from rosbag2_py._writer import SequentialCompressionWriter as SequentialCompressionWriter, SequentialWriter as SequentialWriter, get_registered_compressors as get_registered_compressors, get_registered_serializers as get_registered_serializers, get_registered_writers as get_registered_writers -__all__ = ['bag_rewrite', 'CompressionMode', 'CompressionOptions', 'compression_mode_from_string', 'compression_mode_to_string', 'ConverterOptions', 'FileInformation', 'get_default_storage_id', 'get_registered_readers', 'get_registered_writers', 'get_registered_compressors', 'get_registered_serializers', 'to_rclcpp_qos_vector', 'ReadOrder', 'ReadOrderSortBy', 'Reindexer', 'SequentialCompressionReader', 'SequentialCompressionWriter', 'SequentialReader', 'SequentialWriter', 'StorageFilter', 'StorageOptions', 'TopicMetadata', 'TopicInformation', 'BagMetadata', 'MessageDefinition', 'MetadataIo', 'Info', 'Player', 'PlayOptions', 'ServiceRequestsSource', 'Recorder', 'RecordOptions', 'LocalMessageDefinitionSource'] +__all__ = ['bag_rewrite', 'convert_rclcpp_qos_to_rclpy_qos', 'CompressionMode', 'CompressionOptions', 'compression_mode_from_string', 'compression_mode_to_string', 'ConverterOptions', 'FileInformation', 'get_default_storage_id', 'get_registered_readers', 'get_registered_writers', 'get_registered_compressors', 'get_registered_serializers', 'to_rclcpp_qos_vector', 'ReadOrder', 'ReadOrderSortBy', 'Reindexer', 'SequentialCompressionReader', 'SequentialCompressionWriter', 'SequentialReader', 'SequentialWriter', 'StorageFilter', 'StorageOptions', 'TopicMetadata', 'TopicInformation', 'BagMetadata', 'MessageDefinition', 'MetadataIo', 'Info', 'Player', 'PlayOptions', 'ServiceRequestsSource', 'Recorder', 'RecordOptions', 'LocalMessageDefinitionSource']