From 14a21c595e9de5e8359203caa3a6b68d396a70be Mon Sep 17 00:00:00 2001 From: "mergify[bot]" <37929162+mergify[bot]@users.noreply.github.com> Date: Mon, 19 Aug 2024 13:20:00 -0400 Subject: [PATCH] Finish QoS updates (backport #1019) (#1024) This implements the remainder of #847: - Make sure publishers default to system defaults (reliable) - Add QoS overriding where possible (some of the image_transport / message_filters stuff doesn't really support that) - Use the matching heuristic for subscribers consistently --- depth_image_proc/doc/tutorials.rst | 4 + depth_image_proc/package.xml | 1 + depth_image_proc/src/convert_metric.cpp | 15 +++- depth_image_proc/src/crop_foremost.cpp | 16 +++- depth_image_proc/src/disparity.cpp | 4 +- depth_image_proc/src/point_cloud_xyz.cpp | 17 ++-- .../src/point_cloud_xyz_radial.cpp | 17 ++-- depth_image_proc/src/point_cloud_xyzi.cpp | 5 +- .../src/point_cloud_xyzi_radial.cpp | 16 +++- depth_image_proc/src/point_cloud_xyzrgb.cpp | 5 +- .../src/point_cloud_xyzrgb_radial.cpp | 5 +- depth_image_proc/src/register.cpp | 2 + image_pipeline/doc/tutorials.rst | 80 +++++++++++++++++++ image_proc/doc/tutorials.rst | 4 + image_proc/include/image_proc/utils.hpp | 1 + image_proc/src/crop_decimate.cpp | 8 +- image_proc/src/crop_non_zero.cpp | 7 +- image_proc/src/debayer.cpp | 11 ++- image_proc/src/rectify.cpp | 8 +- image_proc/src/resize.cpp | 7 +- image_proc/src/track_marker.cpp | 4 +- image_publisher/src/image_publisher.cpp | 5 +- image_rotate/src/image_rotate_node.cpp | 2 + image_view/src/extract_images_node.cpp | 2 +- image_view/src/image_saver_node.cpp | 2 +- image_view/src/image_view_node.cpp | 4 +- 26 files changed, 191 insertions(+), 61 deletions(-) diff --git a/depth_image_proc/doc/tutorials.rst b/depth_image_proc/doc/tutorials.rst index 74713f5e6..a37dc373b 100644 --- a/depth_image_proc/doc/tutorials.rst +++ b/depth_image_proc/doc/tutorials.rst @@ -57,3 +57,7 @@ parameter is used: Remapping camera_info Topics ---------------------------- See `tutorial in image_pipline `_. + +Using QoS Overrides +------------------- +See `tutorial in image_pipline `_. diff --git a/depth_image_proc/package.xml b/depth_image_proc/package.xml index 1cffcaa09..c8e3779cd 100644 --- a/depth_image_proc/package.xml +++ b/depth_image_proc/package.xml @@ -32,6 +32,7 @@ image_geometry image_transport libopencv-dev + image_proc message_filters rclcpp rclcpp_components diff --git a/depth_image_proc/src/convert_metric.cpp b/depth_image_proc/src/convert_metric.cpp index 60e18a217..849e197d0 100644 --- a/depth_image_proc/src/convert_metric.cpp +++ b/depth_image_proc/src/convert_metric.cpp @@ -41,6 +41,7 @@ #include #include +#include #include namespace depth_image_proc @@ -68,7 +69,7 @@ ConvertMetricNode::ConvertMetricNode(const rclcpp::NodeOptions & options) // TransportHints does not actually declare the parameter this->declare_parameter("image_transport", "raw"); - // Create publisher with connect callback + // Setup lazy subscriber using publisher connection callback rclcpp::PublisherOptions pub_options; pub_options.event_callbacks.matched_callback = [this](rclcpp::MatchedInfo &) @@ -83,18 +84,24 @@ ConvertMetricNode::ConvertMetricNode(const rclcpp::NodeOptions & options) std::string topic = node_base->resolve_topic_or_service_name("image_raw", false); // Get transport hints image_transport::TransportHints hints(this); + // Create subscriber with QoS matched to subscribed topic publisher + auto qos_profile = image_proc::getTopicQosProfile(this, topic); sub_raw_ = image_transport::create_subscription( this, topic, std::bind(&ConvertMetricNode::depthCb, this, std::placeholders::_1), - hints.getTransport()); + hints.getTransport(), + qos_profile); } }; // For compressed topics to remap appropriately, we need to pass a // fully expanded and remapped topic name to image_transport auto node_base = this->get_node_base_interface(); std::string topic = node_base->resolve_topic_or_service_name("image", false); - pub_depth_ = - image_transport::create_publisher(this, topic, rmw_qos_profile_default, pub_options); + + // Create publisher - allow overriding QoS settings (history, depth, reliability) + pub_options.qos_overriding_options = rclcpp::QosOverridingOptions::with_default_policies(); + pub_depth_ = image_transport::create_publisher(this, topic, rmw_qos_profile_default, + pub_options); } void ConvertMetricNode::depthCb(const sensor_msgs::msg::Image::ConstSharedPtr & raw_msg) diff --git a/depth_image_proc/src/crop_foremost.cpp b/depth_image_proc/src/crop_foremost.cpp index 3807cd939..ddfd845ee 100644 --- a/depth_image_proc/src/crop_foremost.cpp +++ b/depth_image_proc/src/crop_foremost.cpp @@ -38,6 +38,7 @@ #include "depth_image_proc/visibility.h" #include +#include #include #include @@ -74,7 +75,8 @@ CropForemostNode::CropForemostNode(const rclcpp::NodeOptions & options) distance_ = this->declare_parameter("distance", 0.0); - // Create publisher with connect callback + + // Setup lazy subscriber using publisher connection callback rclcpp::PublisherOptions pub_options; pub_options.event_callbacks.matched_callback = [this](rclcpp::MatchedInfo &) @@ -89,18 +91,24 @@ CropForemostNode::CropForemostNode(const rclcpp::NodeOptions & options) std::string topic = node_base->resolve_topic_or_service_name("image_raw", false); // Get transport hints image_transport::TransportHints hints(this); + // Create publisher with same QoS as subscribed topic publisher + auto qos_profile = image_proc::getTopicQosProfile(this, topic); sub_raw_ = image_transport::create_subscription( this, topic, std::bind(&CropForemostNode::depthCb, this, std::placeholders::_1), - hints.getTransport()); + hints.getTransport(), + qos_profile); } }; // For compressed topics to remap appropriately, we need to pass a // fully expanded and remapped topic name to image_transport auto node_base = this->get_node_base_interface(); std::string topic = node_base->resolve_topic_or_service_name("image", false); - pub_depth_ = - image_transport::create_publisher(this, topic, rmw_qos_profile_default, pub_options); + + // Create publisher - allow overriding QoS settings (history, depth, reliability) + pub_options.qos_overriding_options = rclcpp::QosOverridingOptions::with_default_policies(); + pub_depth_ = image_transport::create_publisher(this, topic, rmw_qos_profile_default, + pub_options); } void CropForemostNode::depthCb(const sensor_msgs::msg::Image::ConstSharedPtr & raw_msg) diff --git a/depth_image_proc/src/disparity.cpp b/depth_image_proc/src/disparity.cpp index 4cad8eb5d..acacca568 100644 --- a/depth_image_proc/src/disparity.cpp +++ b/depth_image_proc/src/disparity.cpp @@ -119,8 +119,10 @@ DisparityNode::DisparityNode(const rclcpp::NodeOptions & options) sub_info_.subscribe(this, "right/camera_info"); } }; + // Allow overriding QoS settings (history, depth, reliability) + pub_options.qos_overriding_options = rclcpp::QosOverridingOptions::with_default_policies(); pub_disparity_ = create_publisher( - "left/disparity", rclcpp::SensorDataQoS(), pub_options); + "left/disparity", rclcpp::SystemDefaultsQoS(), pub_options); } void DisparityNode::depthCb( diff --git a/depth_image_proc/src/point_cloud_xyz.cpp b/depth_image_proc/src/point_cloud_xyz.cpp index 227a4100b..d85a56748 100644 --- a/depth_image_proc/src/point_cloud_xyz.cpp +++ b/depth_image_proc/src/point_cloud_xyz.cpp @@ -40,6 +40,7 @@ #include #include +#include #include #include #include @@ -75,10 +76,12 @@ PointCloudXyzNode::PointCloudXyzNode(const rclcpp::NodeOptions & options) auto node_base = this->get_node_base_interface(); std::string topic = node_base->resolve_topic_or_service_name("image_rect", false); - // Get transport and QoS + // Get transport hints image_transport::TransportHints depth_hints(this, "raw", "depth_image_transport"); - auto custom_qos = rmw_qos_profile_system_default; - custom_qos.depth = queue_size_; + + // Create subscriber with QoS matched to subscribed topic publisher + auto qos_profile = image_proc::getTopicQosProfile(this, topic); + qos_profile.depth = queue_size_; sub_depth_ = image_transport::create_camera_subscription( this, @@ -87,10 +90,14 @@ PointCloudXyzNode::PointCloudXyzNode(const rclcpp::NodeOptions & options) &PointCloudXyzNode::depthCb, this, std::placeholders::_1, std::placeholders::_2), depth_hints.getTransport(), - custom_qos); + qos_profile); } }; - pub_point_cloud_ = create_publisher("points", rclcpp::SensorDataQoS(), pub_options); + + // Allow overriding QoS settings (history, depth, reliability) + pub_options.qos_overriding_options = rclcpp::QosOverridingOptions::with_default_policies(); + pub_point_cloud_ = + create_publisher("points", rclcpp::SystemDefaultsQoS(), pub_options); } void PointCloudXyzNode::depthCb( diff --git a/depth_image_proc/src/point_cloud_xyz_radial.cpp b/depth_image_proc/src/point_cloud_xyz_radial.cpp index 660ea99df..4407de7c5 100644 --- a/depth_image_proc/src/point_cloud_xyz_radial.cpp +++ b/depth_image_proc/src/point_cloud_xyz_radial.cpp @@ -39,6 +39,7 @@ #include #include +#include #include #include #include @@ -56,7 +57,7 @@ PointCloudXyzRadialNode::PointCloudXyzRadialNode(const rclcpp::NodeOptions & opt // Read parameters queue_size_ = this->declare_parameter("queue_size", 5); - // Create publisher with connect callback + // Setup lazy subscriber using publisher connection callback rclcpp::PublisherOptions pub_options; pub_options.event_callbacks.matched_callback = [this](rclcpp::MatchedInfo & s) @@ -69,10 +70,11 @@ PointCloudXyzRadialNode::PointCloudXyzRadialNode(const rclcpp::NodeOptions & opt // fully expanded and remapped topic name to image_transport auto node_base = this->get_node_base_interface(); std::string topic = node_base->resolve_topic_or_service_name("depth/image_raw", false); - // Get transport and QoS + // Get transport hints image_transport::TransportHints depth_hints(this, "raw", "depth_image_transport"); - auto custom_qos = rmw_qos_profile_system_default; - custom_qos.depth = queue_size_; + // Create subscriber with QoS matched to subscribed topic publisher + auto qos_profile = image_proc::getTopicQosProfile(this, topic); + qos_profile.depth = queue_size_; // Create subscriber sub_depth_ = image_transport::create_camera_subscription( this, @@ -81,11 +83,14 @@ PointCloudXyzRadialNode::PointCloudXyzRadialNode(const rclcpp::NodeOptions & opt &PointCloudXyzRadialNode::depthCb, this, std::placeholders::_1, std::placeholders::_2), depth_hints.getTransport(), - custom_qos); + qos_profile); } }; + + // Allow overriding QoS settings (history, depth, reliability) + pub_options.qos_overriding_options = rclcpp::QosOverridingOptions::with_default_policies(); pub_point_cloud_ = create_publisher( - "points", rclcpp::SensorDataQoS(), pub_options); + "points", rclcpp::SystemDefaultsQoS(), pub_options); } void PointCloudXyzRadialNode::depthCb( diff --git a/depth_image_proc/src/point_cloud_xyzi.cpp b/depth_image_proc/src/point_cloud_xyzi.cpp index 0abc0ff8c..1ac6d5a5d 100644 --- a/depth_image_proc/src/point_cloud_xyzi.cpp +++ b/depth_image_proc/src/point_cloud_xyzi.cpp @@ -111,7 +111,10 @@ PointCloudXyziNode::PointCloudXyziNode(const rclcpp::NodeOptions & options) sub_info_.subscribe(this, intensity_info_topic); } }; - pub_point_cloud_ = create_publisher("points", rclcpp::SensorDataQoS(), pub_options); + // Allow overriding QoS settings (history, depth, reliability) + pub_options.qos_overriding_options = rclcpp::QosOverridingOptions::with_default_policies(); + pub_point_cloud_ = create_publisher("points", rclcpp::SystemDefaultsQoS(), + pub_options); } void PointCloudXyziNode::imageCb( diff --git a/depth_image_proc/src/point_cloud_xyzi_radial.cpp b/depth_image_proc/src/point_cloud_xyzi_radial.cpp index c592851e0..da8c8decb 100644 --- a/depth_image_proc/src/point_cloud_xyzi_radial.cpp +++ b/depth_image_proc/src/point_cloud_xyzi_radial.cpp @@ -37,6 +37,7 @@ #include "depth_image_proc/visibility.h" +#include #include #include #include @@ -73,7 +74,7 @@ PointCloudXyziRadialNode::PointCloudXyziRadialNode(const rclcpp::NodeOptions & o std::placeholders::_2, std::placeholders::_3)); - // Create publisher with connect callback + // Setup lazy subscriber using publisher connection callback rclcpp::PublisherOptions pub_options; pub_options.event_callbacks.matched_callback = [this](rclcpp::MatchedInfo & s) @@ -98,16 +99,23 @@ PointCloudXyziRadialNode::PointCloudXyziRadialNode(const rclcpp::NodeOptions & o // depth image can use different transport.(e.g. compressedDepth) image_transport::TransportHints depth_hints(this, "raw", "depth_image_transport"); - sub_depth_.subscribe(this, depth_topic, depth_hints.getTransport()); + // Create subscriber with QoS matched to subscribed topic publisher + auto depth_qos_profile = image_proc::getTopicQosProfile(this, depth_topic); + sub_depth_.subscribe(this, depth_topic, depth_hints.getTransport(), depth_qos_profile); // intensity uses normal ros transport hints. image_transport::TransportHints hints(this); - sub_intensity_.subscribe(this, intensity_topic, hints.getTransport()); + // Create subscriber with QoS matched to subscribed topic publisher + auto qos_profile = image_proc::getTopicQosProfile(this, intensity_topic); + sub_intensity_.subscribe(this, intensity_topic, hints.getTransport(), qos_profile); sub_info_.subscribe(this, intensity_info_topic); } }; + + // Allow overriding QoS settings (history, depth, reliability) + pub_options.qos_overriding_options = rclcpp::QosOverridingOptions::with_default_policies(); pub_point_cloud_ = create_publisher( - "points", rclcpp::SensorDataQoS(), pub_options); + "points", rclcpp::SystemDefaultsQoS(), pub_options); } void PointCloudXyziRadialNode::imageCb( diff --git a/depth_image_proc/src/point_cloud_xyzrgb.cpp b/depth_image_proc/src/point_cloud_xyzrgb.cpp index 5ef736d96..4e315b4a3 100644 --- a/depth_image_proc/src/point_cloud_xyzrgb.cpp +++ b/depth_image_proc/src/point_cloud_xyzrgb.cpp @@ -137,7 +137,10 @@ PointCloudXyzrgbNode::PointCloudXyzrgbNode(const rclcpp::NodeOptions & options) sub_info_.subscribe(this, rgb_info_topic); } }; - pub_point_cloud_ = create_publisher("points", rclcpp::SensorDataQoS(), pub_options); + // Allow overriding QoS settings (history, depth, reliability) + pub_options.qos_overriding_options = rclcpp::QosOverridingOptions::with_default_policies(); + pub_point_cloud_ = create_publisher("points", rclcpp::SystemDefaultsQoS(), + pub_options); } void PointCloudXyzrgbNode::imageCb( diff --git a/depth_image_proc/src/point_cloud_xyzrgb_radial.cpp b/depth_image_proc/src/point_cloud_xyzrgb_radial.cpp index 7d2c92477..a1620c9f0 100644 --- a/depth_image_proc/src/point_cloud_xyzrgb_radial.cpp +++ b/depth_image_proc/src/point_cloud_xyzrgb_radial.cpp @@ -121,7 +121,10 @@ PointCloudXyzrgbRadialNode::PointCloudXyzrgbRadialNode(const rclcpp::NodeOptions sub_info_.subscribe(this, rgb_info_topic); } }; - pub_point_cloud_ = create_publisher("points", rclcpp::SensorDataQoS(), pub_options); + // Allow overriding QoS settings (history, depth, reliability) + pub_options.qos_overriding_options = rclcpp::QosOverridingOptions::with_default_policies(); + pub_point_cloud_ = create_publisher("points", rclcpp::SystemDefaultsQoS(), + pub_options); } void PointCloudXyzrgbRadialNode::imageCb( diff --git a/depth_image_proc/src/register.cpp b/depth_image_proc/src/register.cpp index 6269f4cf4..e078beedd 100644 --- a/depth_image_proc/src/register.cpp +++ b/depth_image_proc/src/register.cpp @@ -149,6 +149,8 @@ RegisterNode::RegisterNode(const rclcpp::NodeOptions & options) std::string topic = node_base->resolve_topic_or_service_name("depth_registered/image_rect", false); + // Allow overriding QoS settings (history, depth, reliability) + pub_options.qos_overriding_options = rclcpp::QosOverridingOptions::with_default_policies(); pub_registered_ = image_transport::create_camera_publisher( this, topic, diff --git a/image_pipeline/doc/tutorials.rst b/image_pipeline/doc/tutorials.rst index b5e83a32e..1dffb7a50 100644 --- a/image_pipeline/doc/tutorials.rst +++ b/image_pipeline/doc/tutorials.rst @@ -24,3 +24,83 @@ camera info topic. An example: * The fully resolved name for the camera info is now ``my_camera/camera_info``. * If your camera driver actually publishes ``another_ns/camera_info``, then you would have to remap ``my_camera/camera_info`` to ``another_ns/camera_info``. + +.. _`Using QoS Overrides`: + +Using QoS Overrides +------------------- +Most components in image_pipeline follow the Quality of Service (QoS) recommendations +of `REP-2003 `_ by default. This means that +subscribers are configured with the "Sensor Data" QoS (which uses "best effort"), +and publishers are configured with "System Default" QoS (which uses "reliable" transport). + +These QoS settings work well for many applications, but can be overridden using the +standard features of recent ROS 2 releases. This involves adding additional parameters +to your YAML or launch file. For example, we could update the +`image_publisher_file.launch.py` launch file to change the QoS settings: + +.. code-block:: python + + import os + + from ament_index_python.packages import get_package_share_directory + from launch import LaunchDescription + import launch_ros.actions + + def generate_launch_description(): + filename = os.path.join(get_package_share_directory('image_publisher'), 'launch', + 'splash.png') + return LaunchDescription([ + + launch_ros.actions.Node( + package='image_publisher', executable='image_publisher_node', output='screen', + arguments=[filename], + parameters=[{ + 'qos_overrides': { + '/camera/image_raw': { + 'publisher': { + 'reliability': 'best_effort', + 'history': 'keep_last', + 'depth': 100, + } + } + }, + }], + remappings=[('image_raw', '/camera/image_raw'), + ('camera_info', '/camera/camera_info')]), + ]) + +If we then run the launch file, we can see our settings are applied: + +.. code-block:: bash + + $ ros2 topic info /camera/image_raw -v + Type: sensor_msgs/msg/Image + + Publisher count: 1 + + Node name: ImagePublisher + Node namespace: / + Topic type: sensor_msgs/msg/Image + Topic type hash: RIHS01_d31d41a9a4c4bc8eae9be757b0beed306564f7526c88ea6a4588fb9582527d47 + Endpoint type: PUBLISHER + GID: 01.10.bf.bd.b7.85.a8.33.58.34.5c.ae.00.00.17.03 + QoS profile: + Reliability: BEST_EFFORT + History (Depth): KEEP_LAST (100) + Durability: VOLATILE + Lifespan: Infinite + Deadline: Infinite + Liveliness: AUTOMATIC + Liveliness lease duration: Infinite + + Subscription count: 0 + +A few things to note: + + * The topic name (``/camera/image_raw``) must be the fully resolved topic name, + and therefore we use the remapped topic name rather than the name in the code + for the component. + * Only ``reliability``, ``history``, and ``depth`` can be overwritten. + +For more information on QoS overrides, see the `design doc `_. diff --git a/image_proc/doc/tutorials.rst b/image_proc/doc/tutorials.rst index b13fbc2a0..f86ef123c 100644 --- a/image_proc/doc/tutorials.rst +++ b/image_proc/doc/tutorials.rst @@ -75,6 +75,10 @@ Remapping camera_info Topics ---------------------------- See `tutorial in image_pipline `_. +Using QoS Overrides +------------------- +See `tutorial in image_pipline `_. + .. _Using image_proc Launch File: Using image_proc Launch File diff --git a/image_proc/include/image_proc/utils.hpp b/image_proc/include/image_proc/utils.hpp index 6be4b88f7..ee32ef21d 100644 --- a/image_proc/include/image_proc/utils.hpp +++ b/image_proc/include/image_proc/utils.hpp @@ -40,6 +40,7 @@ namespace image_proc { +inline rmw_qos_profile_t getTopicQosProfile(rclcpp::Node * node, const std::string & topic) { /** diff --git a/image_proc/src/crop_decimate.cpp b/image_proc/src/crop_decimate.cpp index a53ab9ac2..91169afbd 100644 --- a/image_proc/src/crop_decimate.cpp +++ b/image_proc/src/crop_decimate.cpp @@ -152,12 +152,10 @@ CropDecimateNode::CropDecimateNode(const rclcpp::NodeOptions & options) } }; - // Allow overriding QoS settings (history, depth, reliability) + // Create publisher - allow overriding QoS settings (history, depth, reliability) pub_options.qos_overriding_options = rclcpp::QosOverridingOptions::with_default_policies(); - - // Create publisher with QoS matched to subscribed topic publisher - auto qos_profile = getTopicQosProfile(this, image_topic_); - pub_ = image_transport::create_camera_publisher(this, pub_topic, qos_profile, pub_options); + pub_ = image_transport::create_camera_publisher(this, pub_topic, rmw_qos_profile_default, + pub_options); } void CropDecimateNode::imageCb( diff --git a/image_proc/src/crop_non_zero.cpp b/image_proc/src/crop_non_zero.cpp index 100a23ed7..1fa8ebf61 100644 --- a/image_proc/src/crop_non_zero.cpp +++ b/image_proc/src/crop_non_zero.cpp @@ -80,12 +80,9 @@ CropNonZeroNode::CropNonZeroNode(const rclcpp::NodeOptions & options) } }; - // Allow overriding QoS settings (history, depth, reliability) + // Create publisher - allow overriding QoS settings (history, depth, reliability) pub_options.qos_overriding_options = rclcpp::QosOverridingOptions::with_default_policies(); - - // Create publisher with QoS matched to subscribed topic publisher - auto qos_profile = getTopicQosProfile(this, image_topic_); - pub_ = image_transport::create_publisher(this, pub_topic, qos_profile, pub_options); + pub_ = image_transport::create_publisher(this, pub_topic, rmw_qos_profile_default, pub_options); } void CropNonZeroNode::imageCb(const sensor_msgs::msg::Image::ConstSharedPtr & raw_msg) diff --git a/image_proc/src/debayer.cpp b/image_proc/src/debayer.cpp index fe4faf9ec..ad870a4e8 100644 --- a/image_proc/src/debayer.cpp +++ b/image_proc/src/debayer.cpp @@ -84,13 +84,12 @@ DebayerNode::DebayerNode(const rclcpp::NodeOptions & options) } }; - // Allow overriding QoS settings (history, depth, reliability) + // Create publisher - allow overriding QoS settings (history, depth, reliability) pub_options.qos_overriding_options = rclcpp::QosOverridingOptions::with_default_policies(); - - // Create publisher with QoS matched to subscribed topic publisher - auto qos_profile = getTopicQosProfile(this, image_topic_); - pub_mono_ = image_transport::create_publisher(this, mono_topic, qos_profile, pub_options); - pub_color_ = image_transport::create_publisher(this, color_topic, qos_profile, pub_options); + pub_mono_ = image_transport::create_publisher(this, mono_topic, rmw_qos_profile_default, + pub_options); + pub_color_ = image_transport::create_publisher(this, color_topic, rmw_qos_profile_default, + pub_options); } void DebayerNode::imageCb(const sensor_msgs::msg::Image::ConstSharedPtr & raw_msg) diff --git a/image_proc/src/rectify.cpp b/image_proc/src/rectify.cpp index 24d37768c..7b0e32fb0 100644 --- a/image_proc/src/rectify.cpp +++ b/image_proc/src/rectify.cpp @@ -81,12 +81,10 @@ RectifyNode::RectifyNode(const rclcpp::NodeOptions & options) } }; - // Allow overriding QoS settings (history, depth, reliability) + // Create publisher - allow overriding QoS settings (history, depth, reliability) pub_options.qos_overriding_options = rclcpp::QosOverridingOptions::with_default_policies(); - - // Create publisher with QoS matched to subscribed topic publisher - auto qos_profile = getTopicQosProfile(this, image_topic_); - pub_rect_ = image_transport::create_publisher(this, "image_rect", qos_profile, pub_options); + pub_rect_ = image_transport::create_publisher(this, "image_rect", rmw_qos_profile_default, + pub_options); } void RectifyNode::imageCb( diff --git a/image_proc/src/resize.cpp b/image_proc/src/resize.cpp index fdd908df1..b342096ae 100644 --- a/image_proc/src/resize.cpp +++ b/image_proc/src/resize.cpp @@ -89,13 +89,10 @@ ResizeNode::ResizeNode(const rclcpp::NodeOptions & options) } }; - // Allow overriding QoS settings (history, depth, reliability) + // Create publisher - allow overriding QoS settings (history, depth, reliability) pub_options.qos_overriding_options = rclcpp::QosOverridingOptions::with_default_policies(); - - // Create publisher with QoS matched to subscribed topic publisher - auto qos_profile = getTopicQosProfile(this, image_topic_); pub_image_ = - image_transport::create_camera_publisher(this, pub_topic, qos_profile, pub_options); + image_transport::create_camera_publisher(this, pub_topic, rmw_qos_profile_default, pub_options); } void ResizeNode::imageCb( diff --git a/image_proc/src/track_marker.cpp b/image_proc/src/track_marker.cpp index c0586e475..e103de067 100644 --- a/image_proc/src/track_marker.cpp +++ b/image_proc/src/track_marker.cpp @@ -86,10 +86,8 @@ TrackMarkerNode::TrackMarkerNode(const rclcpp::NodeOptions & options) } }; - // Allow overriding QoS settings (history, depth, reliability) + // Create publisher - allow overriding QoS settings (history, depth, reliability) pub_options.qos_overriding_options = rclcpp::QosOverridingOptions::with_default_policies(); - - // Create publisher pub_ = this->create_publisher( "tracked_pose", 10, pub_options); } diff --git a/image_publisher/src/image_publisher.cpp b/image_publisher/src/image_publisher.cpp index 52ac724ec..325c28523 100644 --- a/image_publisher/src/image_publisher.cpp +++ b/image_publisher/src/image_publisher.cpp @@ -60,7 +60,10 @@ ImagePublisher::ImagePublisher( // fully expanded and remapped topic name to image_transport auto node_base = this->get_node_base_interface(); std::string topic_name = node_base->resolve_topic_or_service_name("image_raw", false); - pub_ = image_transport::create_camera_publisher(this, topic_name); + rclcpp::PublisherOptions pub_options; + pub_options.qos_overriding_options = rclcpp::QosOverridingOptions::with_default_policies(); + pub_ = image_transport::create_camera_publisher(this, topic_name, rmw_qos_profile_default, + pub_options); field_of_view_ = this->declare_parameter("field_of_view", static_cast(0)); flip_horizontal_ = this->declare_parameter("flip_horizontal", false); diff --git a/image_rotate/src/image_rotate_node.cpp b/image_rotate/src/image_rotate_node.cpp index 280954489..fd70e8476 100644 --- a/image_rotate/src/image_rotate_node.cpp +++ b/image_rotate/src/image_rotate_node.cpp @@ -344,6 +344,8 @@ void ImageRotateNode::onInit() auto node_base = this->get_node_base_interface(); std::string topic = node_base->resolve_topic_or_service_name("rotated/image", false); + // Allow overriding QoS settings (history, depth, reliability) + pub_options.qos_overriding_options = rclcpp::QosOverridingOptions::with_default_policies(); img_pub_ = image_transport::create_publisher(this, topic, rmw_qos_profile_default, pub_options); } } // namespace image_rotate diff --git a/image_view/src/extract_images_node.cpp b/image_view/src/extract_images_node.cpp index 271ced3a9..e073616ca 100644 --- a/image_view/src/extract_images_node.cpp +++ b/image_view/src/extract_images_node.cpp @@ -82,7 +82,7 @@ ExtractImagesNode::ExtractImagesNode(const rclcpp::NodeOptions & options) sub_ = image_transport::create_subscription( this, topic, std::bind( &ExtractImagesNode::image_cb, this, std::placeholders::_1), - hints.getTransport()); + hints.getTransport(), rmw_qos_profile_sensor_data); auto topics = this->get_topic_names_and_types(); diff --git a/image_view/src/image_saver_node.cpp b/image_view/src/image_saver_node.cpp index 075d84853..abd8d2576 100644 --- a/image_view/src/image_saver_node.cpp +++ b/image_view/src/image_saver_node.cpp @@ -85,7 +85,7 @@ ImageSaverNode::ImageSaverNode(const rclcpp::NodeOptions & options) cam_sub_ = image_transport::create_camera_subscription( this, topic, std::bind( &ImageSaverNode::callbackWithCameraInfo, this, std::placeholders::_1, std::placeholders::_2), - hints.getTransport()); + hints.getTransport(), rmw_qos_profile_sensor_data); // Useful when CameraInfo is not being published image_sub_ = image_transport::create_subscription( diff --git a/image_view/src/image_view_node.cpp b/image_view/src/image_view_node.cpp index fe607d9d2..951eedd9c 100644 --- a/image_view/src/image_view_node.cpp +++ b/image_view/src/image_view_node.cpp @@ -117,8 +117,8 @@ ImageViewNode::ImageViewNode(const rclcpp::NodeOptions & options) pub_ = this->create_publisher("output", 1); sub_ = image_transport::create_subscription( - this, topic, std::bind( - &ImageViewNode::imageCb, this, std::placeholders::_1), hints.getTransport()); + this, topic, std::bind(&ImageViewNode::imageCb, this, std::placeholders::_1), + hints.getTransport(), rmw_qos_profile_sensor_data); auto topics = this->get_topic_names_and_types();