Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035 #include "image_transport/publisher.h"
00036 #include "image_transport/publisher_plugin.h"
00037 #include <pluginlib/class_loader.h>
00038 #include <boost/ptr_container/ptr_vector.hpp>
00039 #include <boost/foreach.hpp>
00040 #include <boost/algorithm/string/erase.hpp>
00041
00042
00043
00044
00045
00046 namespace boost { namespace foreach {
00047 template <>
00048 struct is_noncopyable<ptr_vector<image_transport::PublisherPlugin> > : mpl::true_ {};
00049 }}
00050
00051 namespace image_transport {
00052
00053 struct Publisher::Impl
00054 {
00055 Impl()
00056 : unadvertised_(false)
00057 {
00058 }
00059
00060 ~Impl()
00061 {
00062 shutdown();
00063 }
00064
00065 uint32_t getNumSubscribers() const
00066 {
00067 uint32_t count = 0;
00068 BOOST_FOREACH(const PublisherPlugin& pub, publishers_)
00069 count += pub.getNumSubscribers();
00070 return count;
00071 }
00072
00073 std::string getTopic() const
00074 {
00075 return base_topic_;
00076 }
00077
00078 bool isValid() const
00079 {
00080 return !unadvertised_;
00081 }
00082
00083 void shutdown()
00084 {
00085 if (!unadvertised_) {
00086 unadvertised_ = true;
00087 BOOST_FOREACH(PublisherPlugin& pub, publishers_)
00088 pub.shutdown();
00089 publishers_.clear();
00090 }
00091 }
00092
00093 void subscriberCB(const SingleSubscriberPublisher& plugin_pub,
00094 const SubscriberStatusCallback& user_cb)
00095 {
00096 SingleSubscriberPublisher ssp(plugin_pub.getSubscriberName(), getTopic(),
00097 boost::bind(&Publisher::Impl::getNumSubscribers, this),
00098 plugin_pub.publish_fn_);
00099 user_cb(ssp);
00100 }
00101
00102 std::string base_topic_;
00103 PubLoaderPtr loader_;
00104 boost::ptr_vector<PublisherPlugin> publishers_;
00105 bool unadvertised_;
00106
00107 };
00108
00109
00110 Publisher::Publisher(ros::NodeHandle& nh, const std::string& base_topic, uint32_t queue_size,
00111 const SubscriberStatusCallback& connect_cb,
00112 const SubscriberStatusCallback& disconnect_cb,
00113 const ros::VoidPtr& tracked_object, bool latch,
00114 const PubLoaderPtr& loader)
00115 : impl_(new Impl)
00116 {
00117
00118
00119 impl_->base_topic_ = nh.resolveName(base_topic);
00120 impl_->loader_ = loader;
00121
00122 BOOST_FOREACH(const std::string& lookup_name, loader->getDeclaredClasses()) {
00123 try {
00124 PublisherPlugin* pub = loader->createClassInstance(lookup_name);
00125 impl_->publishers_.push_back(pub);
00126 pub->advertise(nh, impl_->base_topic_, queue_size, rebindCB(connect_cb),
00127 rebindCB(disconnect_cb), tracked_object, latch);
00128 }
00129 catch (const std::runtime_error& e) {
00130 ROS_DEBUG("Failed to load plugin %s, error string: %s",
00131 lookup_name.c_str(), e.what());
00132 }
00133 }
00134
00135 if (impl_->publishers_.empty())
00136 throw Exception("No plugins found! Does `rospack plugins --attrib=plugin "
00137 "image_transport` find any packages?");
00138 }
00139
00140 uint32_t Publisher::getNumSubscribers() const
00141 {
00142 if (impl_ && impl_->isValid()) return impl_->getNumSubscribers();
00143 return 0;
00144 }
00145
00146 std::string Publisher::getTopic() const
00147 {
00148 if (impl_) return impl_->getTopic();
00149 return std::string();
00150 }
00151
00152 void Publisher::publish(const sensor_msgs::Image& message) const
00153 {
00154 if (!impl_ || !impl_->isValid()) {
00155 ROS_ASSERT_MSG(false, "Call to publish() on an invalid image_transport::Publisher");
00156 return;
00157 }
00158
00159 BOOST_FOREACH(const PublisherPlugin& pub, impl_->publishers_) {
00160 if (pub.getNumSubscribers() > 0)
00161 pub.publish(message);
00162 }
00163 }
00164
00165 void Publisher::publish(const sensor_msgs::ImageConstPtr& message) const
00166 {
00167 if (!impl_ || !impl_->isValid()) {
00168 ROS_ASSERT_MSG(false, "Call to publish() on an invalid image_transport::Publisher");
00169 return;
00170 }
00171
00172 BOOST_FOREACH(const PublisherPlugin& pub, impl_->publishers_) {
00173 if (pub.getNumSubscribers() > 0)
00174 pub.publish(message);
00175 }
00176 }
00177
00178 void Publisher::shutdown()
00179 {
00180 if (impl_) {
00181 impl_->shutdown();
00182 impl_.reset();
00183 }
00184 }
00185
00186 Publisher::operator void*() const
00187 {
00188 return (impl_ && impl_->isValid()) ? (void*)1 : (void*)0;
00189 }
00190
00191 void Publisher::weakSubscriberCb(const ImplWPtr& impl_wptr,
00192 const SingleSubscriberPublisher& plugin_pub,
00193 const SubscriberStatusCallback& user_cb)
00194 {
00195 if (ImplPtr impl = impl_wptr.lock())
00196 impl->subscriberCB(plugin_pub, user_cb);
00197 }
00198
00199 SubscriberStatusCallback Publisher::rebindCB(const SubscriberStatusCallback& user_cb)
00200 {
00201
00202
00203
00204 if (user_cb)
00205 {
00206 ImplWPtr impl_wptr(impl_);
00207 return boost::bind(&Publisher::weakSubscriberCb, impl_wptr, _1, user_cb);
00208 }
00209 else
00210 return SubscriberStatusCallback();
00211 }
00212
00213 }