diff --git a/rosbag2_py/src/rosbag2_py/_transport.cpp b/rosbag2_py/src/rosbag2_py/_transport.cpp index e6c98f262b..0aec7e7713 100644 --- a/rosbag2_py/src/rosbag2_py/_transport.cpp +++ b/rosbag2_py/src/rosbag2_py/_transport.cpp @@ -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( - 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 * obj = PyObject_CallMethod(source.ptr(), "get_c_qos_profile", ""); + auto o = py::cast(obj); + auto rmw_qos_profile = o.cast(); + 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)