@@ -146,47 +146,23 @@ class NodeletLazy: public nodelet::Nodelet
146
146
if (lazy_)
147
147
{
148
148
boost::mutex::scoped_lock lock (connection_mutex_);
149
- BOOST_FOREACH ( const ros::Publisher& pub, publishers_ )
149
+ if ( hasSubscribers () )
150
150
{
151
- if (pub. getNumSubscribers () > 0 )
151
+ if (connection_status_ != SUBSCRIBED )
152
152
{
153
- if (connection_status_ != SUBSCRIBED )
153
+ if (verbose_connection_ )
154
154
{
155
- if (verbose_connection_)
156
- {
157
- NODELET_INFO (" Subscribe input topics" );
158
- }
159
- subscribe ();
160
- connection_status_ = SUBSCRIBED;
155
+ NODELET_INFO (" Subscribe input topics" );
161
156
}
162
- if (!ever_subscribed_)
163
- {
164
- ever_subscribed_ = true ;
165
- }
166
- return ;
157
+ subscribe ();
158
+ connection_status_ = SUBSCRIBED;
167
159
}
168
- }
169
- BOOST_FOREACH (const image_transport::Publisher& pub, image_transport_publishers_)
170
- {
171
- if (pub.getNumSubscribers () > 0 )
160
+ if (!ever_subscribed_)
172
161
{
173
- if (connection_status_ != SUBSCRIBED)
174
- {
175
- if (verbose_connection_)
176
- {
177
- NODELET_INFO (" Subscribe input topics" );
178
- }
179
- subscribe ();
180
- connection_status_ = SUBSCRIBED;
181
- }
182
- if (!ever_subscribed_)
183
- {
184
- ever_subscribed_ = true ;
185
- }
186
- return ;
162
+ ever_subscribed_ = true ;
187
163
}
188
164
}
189
- if (connection_status_ == SUBSCRIBED)
165
+ else if (connection_status_ == SUBSCRIBED)
190
166
{
191
167
if (verbose_connection_)
192
168
{
@@ -279,6 +255,34 @@ class NodeletLazy: public nodelet::Nodelet
279
255
return pub;
280
256
}
281
257
258
+ /* *
259
+ * @brief Checks if at least one publisher has subscribers.
260
+ * @param publishers Vector of publishers.
261
+ * @return True if at least one publisher has subscribers; False otherwise.
262
+ */
263
+ template <class T >
264
+ bool hasSubscribers (const std::vector<T>& publishers) const
265
+ {
266
+ BOOST_FOREACH (const T& publisher, publishers)
267
+ {
268
+ if (publisher.getNumSubscribers () > 0 )
269
+ {
270
+ return true ;
271
+ }
272
+ }
273
+
274
+ return false ;
275
+ }
276
+
277
+ /* *
278
+ * @brief Checkes if at least one ros::Publisher or image_transport::Publisher has subscribers.
279
+ * @return True if at least one publisher has subscribers; False otherwise.
280
+ */
281
+ bool hasSubscribers () const
282
+ {
283
+ return hasSubscribers (publishers_) || hasSubscribers (image_transport_publishers_);
284
+ }
285
+
282
286
/* * @brief
283
287
* mutex to call subscribe() and unsubscribe() in
284
288
* critical section.
0 commit comments