Skip to content

Commit d04d2c8

Browse files
mergify[bot]bjsowa
andauthored
Add lazy subscription to republisher (backport #325) (#327)
Signed-off-by: Alejandro Hernández Cordero <[email protected]> Co-authored-by: Błażej Sowa <[email protected]>
1 parent b17b272 commit d04d2c8

File tree

1 file changed

+41
-16
lines changed

1 file changed

+41
-16
lines changed

image_transport/src/republish.cpp

+41-16
Original file line numberDiff line numberDiff line change
@@ -43,6 +43,8 @@ using namespace std::chrono_literals;
4343
namespace image_transport
4444
{
4545

46+
std::mutex pub_matched_mutex;
47+
4648
Republisher::Republisher(const rclcpp::NodeOptions & options)
4749
: Node("image_republisher", options)
4850
{
@@ -111,18 +113,30 @@ void Republisher::initialize()
111113
if (out_transport.empty()) {
112114
// Use all available transports for output
113115

114-
this->pub = image_transport::create_publisher(
115-
this, out_topic,
116-
rmw_qos_profile_default, pub_options);
117-
118116
// Use Publisher::publish as the subscriber callback
119117
typedef void (image_transport::Publisher::* PublishMemFn)(
120118
const sensor_msgs::msg::Image::ConstSharedPtr &) const;
121119
PublishMemFn pub_mem_fn = &image_transport::Publisher::publish;
122120

123-
this->sub = image_transport::create_subscription(
124-
this, in_topic, std::bind(pub_mem_fn, &pub, std::placeholders::_1),
125-
in_transport, rmw_qos_profile_default, sub_options);
121+
pub_options.event_callbacks.matched_callback =
122+
[this, in_topic, in_transport, pub_mem_fn, sub_options](rclcpp::MatchedInfo &)
123+
{
124+
std::scoped_lock<std::mutex> lock(pub_matched_mutex);
125+
if (this->pub.getNumSubscribers() == 0) {
126+
this->sub.shutdown();
127+
} else if (!this->sub) {
128+
this->sub = image_transport::create_subscription(
129+
this, in_topic,
130+
std::bind(pub_mem_fn, &this->pub, std::placeholders::_1),
131+
in_transport,
132+
rmw_qos_profile_default,
133+
sub_options);
134+
}
135+
};
136+
137+
this->pub = image_transport::create_publisher(
138+
this, out_topic,
139+
rmw_qos_profile_default, pub_options);
126140
} else {
127141
// Use one specific transport for output
128142
// Load transport plugin
@@ -132,17 +146,28 @@ void Republisher::initialize()
132146
"image_transport::PublisherPlugin");
133147
std::string lookup_name = Plugin::getLookupName(out_transport);
134148

135-
instance = loader->createUniqueInstance(lookup_name);
136-
instance->advertise(this, out_topic, rmw_qos_profile_default, pub_options);
137-
138-
// Use PublisherPlugin::publish as the subscriber callback
149+
// Use PublisherPlugin::publishPtr as the subscriber callback
139150
typedef void (Plugin::* PublishMemFn)(const sensor_msgs::msg::Image::ConstSharedPtr &) const;
140151
PublishMemFn pub_mem_fn = &Plugin::publishPtr;
141-
this->sub = image_transport::create_subscription(
142-
this, in_topic,
143-
std::bind(
144-
pub_mem_fn,
145-
instance.get(), std::placeholders::_1), in_transport, rmw_qos_profile_default, sub_options);
152+
153+
this->instance = loader->createUniqueInstance(lookup_name);
154+
155+
pub_options.event_callbacks.matched_callback =
156+
[this, in_topic, in_transport, pub_mem_fn, sub_options](rclcpp::MatchedInfo & matched_info)
157+
{
158+
if (matched_info.current_count == 0) {
159+
this->sub.shutdown();
160+
} else if (!this->sub) {
161+
this->sub = image_transport::create_subscription(
162+
this, in_topic,
163+
std::bind(
164+
pub_mem_fn,
165+
this->instance.get(), std::placeholders::_1), in_transport, rmw_qos_profile_default,
166+
sub_options);
167+
}
168+
};
169+
170+
this->instance->advertise(this, out_topic, rmw_qos_profile_default, pub_options);
146171
}
147172
}
148173

0 commit comments

Comments
 (0)