@@ -43,6 +43,8 @@ using namespace std::chrono_literals;
43
43
namespace image_transport
44
44
{
45
45
46
+ std::mutex pub_matched_mutex;
47
+
46
48
Republisher::Republisher (const rclcpp::NodeOptions & options)
47
49
: Node(" image_republisher" , options)
48
50
{
@@ -111,18 +113,30 @@ void Republisher::initialize()
111
113
if (out_transport.empty ()) {
112
114
// Use all available transports for output
113
115
114
- this ->pub = image_transport::create_publisher (
115
- this , out_topic,
116
- rmw_qos_profile_default, pub_options);
117
-
118
116
// Use Publisher::publish as the subscriber callback
119
117
typedef void (image_transport::Publisher::* PublishMemFn)(
120
118
const sensor_msgs::msg::Image::ConstSharedPtr &) const ;
121
119
PublishMemFn pub_mem_fn = &image_transport::Publisher::publish;
122
120
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);
126
140
} else {
127
141
// Use one specific transport for output
128
142
// Load transport plugin
@@ -132,17 +146,28 @@ void Republisher::initialize()
132
146
" image_transport::PublisherPlugin" );
133
147
std::string lookup_name = Plugin::getLookupName (out_transport);
134
148
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
139
150
typedef void (Plugin::* PublishMemFn)(const sensor_msgs::msg::Image::ConstSharedPtr &) const ;
140
151
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);
146
171
}
147
172
}
148
173
0 commit comments