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

Added method to introspect QoS in Python #1648

Merged
merged 12 commits into from
Aug 21, 2024
2 changes: 2 additions & 0 deletions rosbag2_py/rosbag2_py/__init__.py
Original file line number Diff line number Diff line change
Expand Up @@ -44,6 +44,7 @@
StorageOptions,
TopicMetadata,
TopicInformation,
convert_rclcpp_qos_to_rclpy_qos,
get_default_storage_id,
to_rclcpp_qos_vector,
)
Expand Down Expand Up @@ -71,6 +72,7 @@

__all__ = [
'bag_rewrite',
'convert_rclcpp_qos_to_rclpy_qos',
'CompressionMode',
'CompressionOptions',
'compression_mode_from_string',
Expand Down
4 changes: 2 additions & 2 deletions rosbag2_py/rosbag2_py/__init__.pyi
Original file line number Diff line number Diff line change
Expand Up @@ -3,8 +3,8 @@ from rosbag2_py._info import Info as Info
from rosbag2_py._message_definitions import LocalMessageDefinitionSource as LocalMessageDefinitionSource
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_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

__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']
1 change: 1 addition & 0 deletions rosbag2_py/rosbag2_py/_storage.pyi
Original file line number Diff line number Diff line change
Expand Up @@ -196,5 +196,6 @@ class rmw_qos_reliability_policy_t:
@property
def value(self) -> int: ...

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]: ...
30 changes: 30 additions & 0 deletions rosbag2_py/src/rosbag2_py/_storage.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -391,6 +391,36 @@ PYBIND11_MODULE(_storage, m) {
&rosbag2_storage::to_rclcpp_qos_vector,
"Convert QoS in YAML to std::vector<QoS>");

m.def(
"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");
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);

pybind11::object qos_profile = rclcpy_qos.attr("QoSProfile")(
"depth"_a = qos_input.depth(),
"history"_a = static_cast<int>(qos_input.history()),
"reliability"_a = static_cast<int>(qos_input.reliability()),
"durability"_a = static_cast<int>(qos_input.durability()),
"lifespan"_a = duration_lifespan,
"deadline"_a = duration_deadline,
"liveliness"_a = static_cast<int>(qos_input.liveliness()),
"liveliness_lease_duration"_a = duration_liveliness_lease_duration,
"avoid_ros_namespace_conventions"_a = qos_input.avoid_ros_namespace_conventions());

return qos_profile;
},
"Converts rclcpp::QoS to rclpy.qos");

pybind11::class_<rosbag2_storage::MetadataIo>(m, "MetadataIo")
.def(pybind11::init<>())
.def("write_metadata", &rosbag2_storage::MetadataIo::write_metadata)
Expand Down
1 change: 1 addition & 0 deletions rosbag2_py/src/rosbag2_py/pybind11.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -27,5 +27,6 @@
#endif
#include <pybind11/stl.h>
#include <pybind11/chrono.h>
#include <pybind11/embed.h>

#endif // ROSBAG2_PY__PYBIND11_HPP_
Loading