Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Support image transport publishers in nodelet lazy #75

Open
wants to merge 2 commits into
base: indigo-devel
Choose a base branch
from
Open
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
66 changes: 44 additions & 22 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
};

/**
Copy link
Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

This is a helper function, that can also be used in the child class.

* @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)
Copy link
Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

This argument isn't used. It's not even in the doxygen documentation.

And I had to remove it because otherwise I can use it with an image_transport::Publisher callback.

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())
Copy link
Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

This is a very small and cosmetic change, but the diff is large because of one if block getting into the method. I recommend hiding whitespace changes.

Now this method can be overridden by the child class to also check for the image_transport::Publishers.

{
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)
Copy link
Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

The rest remains the same, but I changed the return; inside the if block to and if-else block, which is equivalent and easier to read in my opinion. If you don't like it, I can remove this from the PR.

{
if (verbose_connection_)
{
Expand Down Expand Up @@ -217,22 +232,29 @@ class NodeletLazy: public nodelet::Nodelet
*/
template<class T> ros::Publisher
advertise(ros::NodeHandle& nh,
std::string topic, int queue_size, bool latch=false)
const std::string& topic, int queue_size, bool latch=false)
Copy link
Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

The change to const & is in a separate commit, so if you don't like it I can remove it from this PR, but we shouldn't be passing a std::string by copy.

{
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);
Copy link
Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Note that I remove the _1 placeholder here, which is important after the change in connectionCallback.

The change to use connect_cb for both disconnection and connection is optional, but I think it's cleaner, since this was already declaring disconnect_cb the same way as connect_cb.

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 Checks 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