Skip to content
Merged
Changes from all commits
Commits
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
10 changes: 5 additions & 5 deletions rosbag2_py/src/rosbag2_py/_transport.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -40,11 +40,11 @@ namespace

rclcpp::QoS qos_from_handle(const py::handle source)
{
auto py_capsule = PyObject_CallMethod(source.ptr(), "get_c_qos_profile", "");
const auto rmw_qos_profile = reinterpret_cast<rmw_qos_profile_t *>(
PyCapsule_GetPointer(py_capsule, "rmw_qos_profile_t"));
const auto qos_init = rclcpp::QoSInitialization::from_rmw(*rmw_qos_profile);
return rclcpp::QoS{qos_init, *rmw_qos_profile};
PyObject * raw_obj = PyObject_CallMethod(source.ptr(), "get_c_qos_profile", "");
const auto py_obj = py::cast<py::object>(raw_obj);
const auto rmw_qos_profile = py_obj.cast<rmw_qos_profile_t>();
Copy link
Copy Markdown
Contributor

Choose a reason for hiding this comment

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

This looks like it will work, though I wouldn't rely on rclpy's C/C++ interface being API/ABI stable. It's possible (but very unlikely) that this will break in the same ROS distro in the future.

get_c_qos_profile() itself should really be documented as internal-use-only.

Copy link
Copy Markdown
Collaborator Author

Choose a reason for hiding this comment

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

Do you have a suggestion on how rosbag2's pybind could take rclpy.QoS as an argument in a more stable way?

Copy link
Copy Markdown
Collaborator Author

Choose a reason for hiding this comment

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

Alternatively - we could pass the YAML file directly and have the C++ layer do the parsing, which it does already have utilities for. Maybe that's a better way, though I had preferred that the CLI layer do input validation

const auto qos_init = rclcpp::QoSInitialization::from_rmw(rmw_qos_profile);
return rclcpp::QoS{qos_init, rmw_qos_profile};
}

QoSMap qos_map_from_py_dict(const py::dict & dict)
Expand Down