Skip to content

Commit

Permalink
Allow to extend w/ support for image_transport
Browse files Browse the repository at this point in the history
Add hasSubscribers and remove not-needed argument from
connectionCallback, so we can overload the hasSubscriber
check and support image_transport::Publisher.

Also share connect and disconnect cb.
  • Loading branch information
efernandez committed May 3, 2018
1 parent 2f25b77 commit 5daa0db
Showing 1 changed file with 43 additions and 21 deletions.
64 changes: 43 additions & 21 deletions nodelet_topic_tools/include/nodelet_topic_tools/nodelet_lazy.h
Original file line number Diff line number Diff line change
Expand Up @@ -40,6 +40,7 @@

#include <ros/ros.h>
#include <nodelet/nodelet.h>
#include <boost/foreach.hpp>
#include <boost/thread.hpp>
#include <string>
#include <vector>
Expand All @@ -57,6 +58,25 @@ enum ConnectionStatus
SUBSCRIBED
};

/**
* @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 has_subscribers(const std::vector<T>& publishers)
{
BOOST_FOREACH (const T& publisher, publishers)
{
if (publisher.getNumSubscribers() > 0)
{
return true;
}
}

return false;
}

/** @brief
* Nodelet to automatically subscribe/unsubscribe
* topics according to subscription of advertised topics.
Expand Down Expand Up @@ -135,7 +155,7 @@ class NodeletLazy: public nodelet::Nodelet
/** @brief
* callback function which is called when new subscriber come
*/
virtual void connectionCallback(const ros::SingleSubscriberPublisher& pub)
virtual void connectionCallback()
{
if (verbose_connection_)
{
Expand All @@ -144,28 +164,23 @@ class NodeletLazy: public nodelet::Nodelet
if (lazy_)
{
boost::mutex::scoped_lock lock(connection_mutex_);
for (size_t i = 0; i < publishers_.size(); i++)
if (hasSubscribers())
{
ros::Publisher pub = publishers_[i];
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;
}
if (!ever_subscribed_)
{
ever_subscribed_ = true;
}
}
if (connection_status_ == SUBSCRIBED)
else if (connection_status_ == SUBSCRIBED)
{
if (verbose_connection_)
{
Expand Down Expand Up @@ -221,18 +236,25 @@ class NodeletLazy: public nodelet::Nodelet
{
boost::mutex::scoped_lock lock(connection_mutex_);
ros::SubscriberStatusCallback connect_cb
= boost::bind(&NodeletLazy::connectionCallback, this, _1);
ros::SubscriberStatusCallback disconnect_cb
= boost::bind(&NodeletLazy::connectionCallback, this, _1);
= boost::bind(&NodeletLazy::connectionCallback, this);
ros::Publisher pub = nh.advertise<T>(topic, queue_size,
connect_cb,
disconnect_cb,
connect_cb,
ros::VoidConstPtr(),
latch);
publishers_.push_back(pub);
return pub;
}

/**
* @brief Checkes if at least one publisher has subscribers.
* @return True if at least one publisher has subscribers; False otherwise.
*/
virtual bool hasSubscribers() const
{
return has_subscribers(publishers_);
}

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

0 comments on commit 5daa0db

Please sign in to comment.