From 15e45f08d1e102ca757d97a667dabd00d18c1d7d Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Alejandro=20Hern=C3=A1ndez=20Cordero?= Date: Fri, 12 Jul 2024 17:26:47 +0200 Subject: [PATCH] fixes MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: Alejandro Hernández Cordero --- .../src/stereo_image_proc/disparity_node.cpp | 6 +++--- .../src/stereo_image_proc/point_cloud_node.cpp | 10 +++++----- 2 files changed, 8 insertions(+), 8 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 9316e14d5..5d09d10ff 100644 --- a/stereo_image_proc/src/stereo_image_proc/disparity_node.cpp +++ b/stereo_image_proc/src/stereo_image_proc/disparity_node.cpp @@ -315,7 +315,7 @@ DisparityNode::DisparityNode(const rclcpp::NodeOptions & options) image_transport::getCameraInfoTopic(right_topic), false); // REP-2003 specifies that subscriber should be SensorDataQoS - const auto sensor_data_qos = rclcpp::SensorDataQoS().get_rmw_qos_profile(); + const auto sensor_data_qos = rclcpp::SensorDataQoS(); // Support image transport for compression image_transport::TransportHints hints(this); @@ -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, - sensor_data_qos.get_rmw_qos_profile(), sub_opts); + sensor_data_qos, sub_opts); sub_r_image_.subscribe( this, right_topic, hints.getTransport(), sensor_data_qos, sub_opts); sub_r_info_.subscribe(this, right_info_topic, - sensor_data_qos.get_rmw_qos_profile(), sub_opts); + sensor_data_qos, 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 fa324d100..6dc0cd8a8 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 @@ -180,7 +180,7 @@ PointCloudNode::PointCloudNode(const rclcpp::NodeOptions & options) image_transport::getCameraInfoTopic(left_topic), false); // REP-2003 specifies that subscriber should be SensorDataQoS - const auto sensor_data_qos = rclcpp::SensorDataQoS().get_rmw_qos_profile(); + const auto sensor_data_qos = rclcpp::SensorDataQoS(); // Support image transport for compression image_transport::TransportHints hints(this); @@ -190,13 +190,13 @@ PointCloudNode::PointCloudNode(const rclcpp::NodeOptions & options) sub_opts.qos_overriding_options = rclcpp::QosOverridingOptions::with_default_policies(); sub_l_image_.subscribe( - this, left_topic, hints.getTransport(), sensor_data_qos, sub_opts); + this, left_topic, hints.getTransport(), sensor_data_qos.get_rmw_qos_profile(), sub_opts); sub_l_info_.subscribe(this, left_info_topic, - sensor_data_qos.get_rmw_qos_profile(), sub_opts); + sensor_data_qos, sub_opts); sub_r_info_.subscribe(this, right_topic, - sensor_data_qos.get_rmw_qos_profile(), sub_opts); + sensor_data_qos, sub_opts); sub_disparity_.subscribe(this, disparity_topic, - sensor_data_qos.get_rmw_qos_profile(), sub_opts); + sensor_data_qos, sub_opts); } }; pub_points2_ = create_publisher("points2", 1, pub_opts);