From 3bb201e4b9b939262584790bdacec974723f1d89 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Alejandro=20Hern=C3=A1ndez=20Cordero?= Date: Fri, 12 Jul 2024 17:16:20 +0200 Subject: [PATCH] Add feedback MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: Alejandro Hernández Cordero --- stereo_image_proc/src/stereo_image_proc/disparity_node.cpp | 4 ++-- .../src/stereo_image_proc/point_cloud_node.cpp | 6 +++--- 2 files changed, 5 insertions(+), 5 deletions(-) diff --git a/stereo_image_proc/src/stereo_image_proc/disparity_node.cpp b/stereo_image_proc/src/stereo_image_proc/disparity_node.cpp index dbebb5e3f..9316e14d5 100644 --- a/stereo_image_proc/src/stereo_image_proc/disparity_node.cpp +++ b/stereo_image_proc/src/stereo_image_proc/disparity_node.cpp @@ -327,11 +327,11 @@ DisparityNode::DisparityNode(const rclcpp::NodeOptions & options) sub_l_image_.subscribe( this, left_topic, hints.getTransport(), sensor_data_qos, sub_opts); sub_l_info_.subscribe(this, left_info_topic, - rclcpp::QoS(rclcpp::QoSInitialization::from_rmw(sensor_data_qos)), sub_opts); + sensor_data_qos.get_rmw_qos_profile(), sub_opts); sub_r_image_.subscribe( this, right_topic, hints.getTransport(), sensor_data_qos, sub_opts); sub_r_info_.subscribe(this, right_info_topic, - rclcpp::QoS(rclcpp::QoSInitialization::from_rmw(sensor_data_qos)), sub_opts); + sensor_data_qos.get_rmw_qos_profile(), sub_opts); } }; diff --git a/stereo_image_proc/src/stereo_image_proc/point_cloud_node.cpp b/stereo_image_proc/src/stereo_image_proc/point_cloud_node.cpp index 90a1e3e62..fa324d100 100644 --- a/stereo_image_proc/src/stereo_image_proc/point_cloud_node.cpp +++ b/stereo_image_proc/src/stereo_image_proc/point_cloud_node.cpp @@ -192,11 +192,11 @@ PointCloudNode::PointCloudNode(const rclcpp::NodeOptions & options) sub_l_image_.subscribe( this, left_topic, hints.getTransport(), sensor_data_qos, sub_opts); sub_l_info_.subscribe(this, left_info_topic, - rclcpp::QoS(rclcpp::QoSInitialization::from_rmw(sensor_data_qos)), sub_opts); + sensor_data_qos.get_rmw_qos_profile(), sub_opts); sub_r_info_.subscribe(this, right_topic, - rclcpp::QoS(rclcpp::QoSInitialization::from_rmw(sensor_data_qos)), sub_opts); + sensor_data_qos.get_rmw_qos_profile(), sub_opts); sub_disparity_.subscribe(this, disparity_topic, - rclcpp::QoS(rclcpp::QoSInitialization::from_rmw(sensor_data_qos)), sub_opts); + sensor_data_qos.get_rmw_qos_profile(), sub_opts); } }; pub_points2_ = create_publisher("points2", 1, pub_opts);