Skip to content

Commit

Permalink
add support for lazy subscribers (#272)
Browse files Browse the repository at this point in the history
  • Loading branch information
mikeferguson authored Jul 13, 2023
1 parent 843443f commit 4965283
Show file tree
Hide file tree
Showing 4 changed files with 10 additions and 9 deletions.
5 changes: 2 additions & 3 deletions image_transport/include/image_transport/camera_publisher.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
3 changes: 2 additions & 1 deletion image_transport/include/image_transport/image_transport.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -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.
Expand Down
6 changes: 3 additions & 3 deletions image_transport/src/camera_publisher.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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<Impl>(node))
{
// Explicitly resolve name here so we compute the correct CameraInfo topic when the
Expand All @@ -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<sensor_msgs::msg::CameraInfo>(info_topic, qos);
}

Expand Down
5 changes: 3 additions & 2 deletions image_transport/src/image_transport.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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(
Expand Down

0 comments on commit 4965283

Please sign in to comment.