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 #ifndef MESSAGE_TRANSPORT_PUBLISHER_H
00036 #define MESSAGE_TRANSPORT_PUBLISHER_H
00037
00038 #include <ros/ros.h>
00039 #include "message_transport/publisher_impl.h"
00040 #include "message_transport/single_subscriber_publisher.h"
00041
00042 namespace message_transport {
00043
00061 class Publisher
00062 {
00063 public:
00064 Publisher() {}
00065 Publisher(ros::NodeHandle& nh);
00066
00073 uint32_t getNumSubscribers() const;
00074
00078 std::string getTopic() const;
00079
00083 template <class M>
00084 void publish(const M& message) const
00085 {
00086 if (!impl_ || !impl_->isValid()) {
00087 ROS_ASSERT_MSG(false, "Call to publish() on an invalid message_transport::Publisher");
00088 return;
00089 }
00090
00091 impl_->publish<M>(message);
00092 }
00093
00097 template <class M>
00098 void publish(const typename M::ConstPtr& message) const
00099 {
00100 if (!impl_ || !impl_->isValid()) {
00101 ROS_ASSERT_MSG(false, "Call to publish() on an invalid message_transport::Publisher");
00102 return;
00103 }
00104
00105 impl_->publish<M>(message);
00106 }
00107
00111 void shutdown();
00112
00113 operator void*() const;
00114 bool operator< (const Publisher& rhs) const { return impl_ < rhs.impl_; }
00115 bool operator!=(const Publisher& rhs) const { return impl_ != rhs.impl_; }
00116 bool operator==(const Publisher& rhs) const { return impl_ == rhs.impl_; }
00117
00118
00119 template <class M>
00120 void do_initialise(ros::NodeHandle& nh,
00121 const std::string & package_name, const std::string & class_name,
00122 const std::string& base_topic, uint32_t queue_size,
00123 const typename SingleSubscriberPublisher<M>::StatusCB& connect_cb,
00124 const typename SingleSubscriberPublisher<M>::StatusCB& disconnect_cb,
00125 const ros::VoidPtr& tracked_object, bool latch)
00126 {
00127 assert(impl_ == NULL);
00128 PublisherImpl<M>* impl = new PublisherImpl<M>(base_topic,package_name, class_name);
00129 impl_.reset(impl);
00130
00131 BOOST_FOREACH(const std::string& lookup_name, impl->getDeclaredClasses()) {
00132 try {
00133 boost::shared_ptr< PublisherPlugin<M> > pub = impl->addInstance(lookup_name);
00134 pub->advertise(nh, impl->getTopic(), queue_size,
00135 rebindCB<M>(connect_cb),
00136 rebindCB<M>(disconnect_cb),
00137 tracked_object, latch);
00138 }
00139 catch (const std::runtime_error& e) {
00140 ROS_DEBUG("Failed to load plugin %s, error string: %s",
00141 lookup_name.c_str(), e.what());
00142 }
00143 }
00144
00145 if (impl->getNumPublishers() == 0) {
00146 throw std::runtime_error("No plugins found! Does `rospack plugins --attrib=plugin "
00147 "message_transport` find any packages?");
00148 }
00149 }
00150
00151 private:
00152
00153 template <class M>
00154 typename SingleSubscriberPublisher<M>::StatusCB rebindCB(const typename SingleSubscriberPublisher<M>::StatusCB& user_cb)
00155 {
00156
00157
00158 if (user_cb)
00159 return boost::bind(&PublisherImplGen::subscriberCB<M>, impl_, _1, user_cb);
00160 else
00161 return typename SingleSubscriberPublisher<M>::StatusCB();
00162 }
00163
00164 typedef boost::shared_ptr<PublisherImplGen> ImplPtr;
00165
00166 ImplPtr impl_;
00167
00168 };
00169
00170 }
00171
00172 #endif