diff --git a/image_transport/include/image_transport/camera_publisher.hpp b/image_transport/include/image_transport/camera_publisher.hpp index 9945ea54..9ed81b07 100644 --- a/image_transport/include/image_transport/camera_publisher.hpp +++ b/image_transport/include/image_transport/camera_publisher.hpp @@ -71,9 +71,8 @@ class CameraPublisher CameraPublisher( rclcpp::Node * node, const std::string & base_topic, - rmw_qos_profile_t custom_qos = rmw_qos_profile_default); - - // TODO(ros2) Restore support for SubscriberStatusCallbacks when available. + rmw_qos_profile_t custom_qos = rmw_qos_profile_default, + rclcpp::PublisherOptions = rclcpp::PublisherOptions()); /*! * \brief Returns the number of subscribers that are currently connected to diff --git a/image_transport/include/image_transport/image_transport.hpp b/image_transport/include/image_transport/image_transport.hpp index 53f38bad..9de2de29 100644 --- a/image_transport/include/image_transport/image_transport.hpp +++ b/image_transport/include/image_transport/image_transport.hpp @@ -75,7 +75,8 @@ IMAGE_TRANSPORT_PUBLIC CameraPublisher create_camera_publisher( rclcpp::Node * node, const std::string & base_topic, - rmw_qos_profile_t custom_qos = rmw_qos_profile_default); + rmw_qos_profile_t custom_qos = rmw_qos_profile_default, + rclcpp::PublisherOptions pub_options = rclcpp::PublisherOptions()); /*! * \brief Subscribe to a camera, free function version. diff --git a/image_transport/src/camera_publisher.cpp b/image_transport/src/camera_publisher.cpp index 0b6542a7..178a8005 100644 --- a/image_transport/src/camera_publisher.cpp +++ b/image_transport/src/camera_publisher.cpp @@ -74,11 +74,11 @@ struct CameraPublisher::Impl bool unadvertised_; }; -// TODO(ros2) Add support for SubscriberStatusCallbacks when rcl/rmw support it. CameraPublisher::CameraPublisher( rclcpp::Node * node, const std::string & base_topic, - rmw_qos_profile_t custom_qos) + rmw_qos_profile_t custom_qos, + rclcpp::PublisherOptions pub_options) : impl_(std::make_shared(node)) { // Explicitly resolve name here so we compute the correct CameraInfo topic when the @@ -89,7 +89,7 @@ CameraPublisher::CameraPublisher( std::string info_topic = getCameraInfoTopic(image_topic); auto qos = rclcpp::QoS(rclcpp::QoSInitialization::from_rmw(custom_qos), custom_qos); - impl_->image_pub_ = image_transport::create_publisher(node, image_topic, custom_qos); + impl_->image_pub_ = image_transport::create_publisher(node, image_topic, custom_qos, pub_options); impl_->info_pub_ = node->create_publisher(info_topic, qos); } diff --git a/image_transport/src/image_transport.cpp b/image_transport/src/image_transport.cpp index 71c91d18..85b7b9ba 100644 --- a/image_transport/src/image_transport.cpp +++ b/image_transport/src/image_transport.cpp @@ -79,9 +79,10 @@ Subscriber create_subscription( CameraPublisher create_camera_publisher( rclcpp::Node * node, const std::string & base_topic, - rmw_qos_profile_t custom_qos) + rmw_qos_profile_t custom_qos, + rclcpp::PublisherOptions pub_options) { - return CameraPublisher(node, base_topic, custom_qos); + return CameraPublisher(node, base_topic, custom_qos, pub_options); } CameraSubscriber create_camera_subscription(