Skip to content

Commit

Permalink
Add hasSubscribers helper method
Browse files Browse the repository at this point in the history
This simplifies the connectCallback code.
  • Loading branch information
efernandez committed Apr 27, 2018
1 parent 894ccfd commit d4e8ed7
Showing 1 changed file with 37 additions and 33 deletions.
70 changes: 37 additions & 33 deletions nodelet_topic_tools/include/nodelet_topic_tools/nodelet_lazy.h
Original file line number Diff line number Diff line change
Expand Up @@ -146,47 +146,23 @@ class NodeletLazy: public nodelet::Nodelet
if (lazy_)
{
boost::mutex::scoped_lock lock(connection_mutex_);
BOOST_FOREACH (const ros::Publisher& pub, publishers_)
if (hasSubscribers())
{
if (pub.getNumSubscribers() > 0)
if (connection_status_ != SUBSCRIBED)
{
if (connection_status_ != SUBSCRIBED)
if (verbose_connection_)
{
if (verbose_connection_)
{
NODELET_INFO("Subscribe input topics");
}
subscribe();
connection_status_ = SUBSCRIBED;
NODELET_INFO("Subscribe input topics");
}
if (!ever_subscribed_)
{
ever_subscribed_ = true;
}
return;
subscribe();
connection_status_ = SUBSCRIBED;
}
}
BOOST_FOREACH (const image_transport::Publisher& pub, image_transport_publishers_)
{
if (pub.getNumSubscribers() > 0)
if (!ever_subscribed_)
{
if (connection_status_ != SUBSCRIBED)
{
if (verbose_connection_)
{
NODELET_INFO("Subscribe input topics");
}
subscribe();
connection_status_ = SUBSCRIBED;
}
if (!ever_subscribed_)
{
ever_subscribed_ = true;
}
return;
ever_subscribed_ = true;
}
}
if (connection_status_ == SUBSCRIBED)
else if (connection_status_ == SUBSCRIBED)
{
if (verbose_connection_)
{
Expand Down Expand Up @@ -279,6 +255,34 @@ class NodeletLazy: public nodelet::Nodelet
return pub;
}

/**
* @brief Checks if at least one publisher has subscribers.
* @param publishers Vector of publishers.
* @return True if at least one publisher has subscribers; False otherwise.
*/
template <class T>
bool hasSubscribers(const std::vector<T>& publishers) const
{
BOOST_FOREACH (const T& publisher, publishers)
{
if (publisher.getNumSubscribers() > 0)
{
return true;
}
}

return false;
}

/**
* @brief Checkes if at least one ros::Publisher or image_transport::Publisher has subscribers.
* @return True if at least one publisher has subscribers; False otherwise.
*/
bool hasSubscribers() const
{
return hasSubscribers(publishers_) || hasSubscribers(image_transport_publishers_);
}

/** @brief
* mutex to call subscribe() and unsubscribe() in
* critical section.
Expand Down

0 comments on commit d4e8ed7

Please sign in to comment.