From 29b148a6f96ba0b30e5e3738c554ae960d90e640 Mon Sep 17 00:00:00 2001 From: Michael Ferguson Date: Thu, 18 Jan 2024 22:07:58 -0500 Subject: [PATCH] add parameter for subscriber transport --- image_rotate/include/image_rotate/image_rotate_node.hpp | 1 + image_rotate/src/image_rotate_node.cpp | 7 +++++-- 2 files changed, 6 insertions(+), 2 deletions(-) diff --git a/image_rotate/include/image_rotate/image_rotate_node.hpp b/image_rotate/include/image_rotate/image_rotate_node.hpp index 67e08eae3..5bad8cf91 100644 --- a/image_rotate/include/image_rotate/image_rotate_node.hpp +++ b/image_rotate/include/image_rotate/image_rotate_node.hpp @@ -66,6 +66,7 @@ struct ImageRotateConfig bool use_camera_info; double max_angular_rate; double output_image_size; + std::string transport; }; class ImageRotateNode : public rclcpp::Node diff --git a/image_rotate/src/image_rotate_node.cpp b/image_rotate/src/image_rotate_node.cpp index 68ffe35b1..aa310f9b8 100644 --- a/image_rotate/src/image_rotate_node.cpp +++ b/image_rotate/src/image_rotate_node.cpp @@ -128,6 +128,9 @@ ImageRotateNode::ImageRotateNode(const rclcpp::NodeOptions & options) config_.max_angular_rate = this->declare_parameter("max_angular_rate", 10.0); config_.output_image_size = this->declare_parameter("output_image_size", 2.0); + // Allow overriding the SUBSCRIBER transport + config_.transport = this->declare_parameter("image_transport", "raw"); + onInit(); } @@ -319,7 +322,7 @@ void ImageRotateNode::onInit() std::bind( &ImageRotateNode::imageCallbackWithInfo, this, std::placeholders::_1, std::placeholders::_2), - "raw", + config_.transport, custom_qos); } else { auto custom_qos = rmw_qos_profile_system_default; @@ -328,7 +331,7 @@ void ImageRotateNode::onInit() this, topic_name, std::bind(&ImageRotateNode::imageCallback, this, std::placeholders::_1), - "raw", + config_.transport, custom_qos); } }