38 #include <boost/foreach.hpp> 39 #include <boost/algorithm/string/erase.hpp> 59 count += pub->getNumSubscribers();
110 impl_->loader_ = loader;
112 std::vector<std::string> blacklist_vec;
113 std::set<std::string> blacklist;
114 nh.
getParam(
impl_->base_topic_ +
"/disable_pub_plugins", blacklist_vec);
115 for (
size_t i = 0; i < blacklist_vec.size(); ++i)
117 blacklist.insert(blacklist_vec[i]);
120 BOOST_FOREACH(
const std::string& lookup_name, loader->getDeclaredClasses()) {
121 const std::string transport_name = boost::erase_last_copy(lookup_name,
"_pub");
122 if (blacklist.count(transport_name))
129 impl_->publishers_.push_back(pub);
130 pub->advertise(nh,
impl_->base_topic_, queue_size,
rebindCB(connect_cb),
131 rebindCB(disconnect_cb), tracked_object, latch);
133 catch (
const std::runtime_error& e) {
134 ROS_DEBUG(
"Failed to load plugin %s, error string: %s",
135 lookup_name.c_str(), e.what());
139 if (
impl_->publishers_.empty())
140 throw Exception(
"No plugins found! Does `rospack plugins --attrib=plugin " 141 "image_transport` find any packages?");
153 return std::string();
159 ROS_ASSERT_MSG(
false,
"Call to publish() on an invalid image_transport::Publisher");
164 if (pub->getNumSubscribers() > 0)
165 pub->publish(message);
172 ROS_ASSERT_MSG(
false,
"Call to publish() on an invalid image_transport::Publisher");
177 if (pub->getNumSubscribers() > 0)
178 pub->publish(message);
190 Publisher::operator
void*()
const 192 return (
impl_ &&
impl_->isValid()) ? (
void*)1 : (
void*)0;
199 if (
ImplPtr impl = impl_wptr.lock())
200 impl->subscriberCB(plugin_pub, user_cb);
static void weakSubscriberCb(const ImplWPtr &impl_wptr, const SingleSubscriberPublisher &plugin_pub, const SubscriberStatusCallback &user_cb)
uint32_t getNumSubscribers() const
Returns the number of subscribers that are currently connected to this Publisher. ...
SubscriberStatusCallback rebindCB(const SubscriberStatusCallback &user_cb)
boost::weak_ptr< Impl > ImplWPtr
boost::function< void(const SingleSubscriberPublisher &)> SubscriberStatusCallback
uint32_t getNumSubscribers() const
void shutdown()
Shutdown the advertisements associated with this Publisher.
bool getParam(const std::string &key, std::string &s) const
#define ROS_ASSERT_MSG(cond,...)
std::string resolveName(const std::string &name, bool remap=true) const
std::string getTopic() const
void publish(const sensor_msgs::Image &message) const
Publish an image on the topics associated with this Publisher.
Allows publication of an image to a single subscriber. Only available inside subscriber connection ca...
A base class for all image_transport exceptions inheriting from std::runtime_error.
void subscriberCB(const SingleSubscriberPublisher &plugin_pub, const SubscriberStatusCallback &user_cb)
std::vector< boost::shared_ptr< PublisherPlugin > > publishers_
std::string getSubscriberName() const
std::string getTopic() const
Returns the base topic of this Publisher.