$search
00001 #ifndef MESSAGE_TRANSPORT_SIMPLE_PUBLISHER_PLUGIN_H 00002 #define MESSAGE_TRANSPORT_SIMPLE_PUBLISHER_PLUGIN_H 00003 00004 #include "message_transport/publisher_plugin.h" 00005 #include <boost/scoped_ptr.hpp> 00006 00007 namespace message_transport { 00008 00026 template <class Base,class M> 00027 class SimplePublisherPlugin : public PublisherPlugin<Base> 00028 { 00029 public: 00030 SimplePublisherPlugin(bool forceLatch = false) : forcelatch_(forceLatch) {} 00031 virtual ~SimplePublisherPlugin() {} 00032 00033 virtual uint32_t getNumSubscribers() const 00034 { 00035 if (simple_impl_) return simple_impl_->pub_.getNumSubscribers(); 00036 return 0; 00037 } 00038 00039 virtual std::string getTopic() const 00040 { 00041 if (simple_impl_) return simple_impl_->pub_.getTopic(); 00042 return std::string(); 00043 } 00044 00045 virtual void publish(const Base& message) const 00046 { 00047 if (!simple_impl_ || !simple_impl_->pub_) { 00048 ROS_ASSERT_MSG(false, "Call to publish() on an invalid message_transport::SimplePublisherPlugin"); 00049 return; 00050 } 00051 00052 publish(message, bindInternalPublisher(simple_impl_->pub_)); 00053 } 00054 00055 virtual void shutdown() 00056 { 00057 if (simple_impl_) simple_impl_->pub_.shutdown(); 00058 } 00059 00060 protected: 00061 virtual void advertiseImpl(ros::NodeHandle & nh, const std::string& base_topic, uint32_t queue_size, 00062 const typename SingleSubscriberPublisher<Base>::StatusCB& user_connect_cb, 00063 const typename SingleSubscriberPublisher<Base>::StatusCB& user_disconnect_cb, 00064 const ros::VoidPtr& tracked_object, bool latch) 00065 { 00067 ros::NodeHandle param_nh(nh, getTopicToAdvertise(base_topic)); 00068 simple_impl_.reset(new SimplePublisherPluginImpl(nh,param_nh)); 00069 simple_impl_->pub_ = nh.advertise<M>(getTopicToAdvertise(base_topic), queue_size, 00070 bindCB(user_connect_cb, &SimplePublisherPlugin::connectCallbackHandle), 00071 bindCB(user_disconnect_cb, &SimplePublisherPlugin::disconnectCallbackHandle), 00072 tracked_object, latch | forcelatch_); 00073 this->postAdvertiseInit(); 00074 } 00075 00077 //initialisation function once the node has been initialised 00078 virtual void postAdvertiseInit() { 00079 // ROS_WARN("Calling default postAdvertiseInit"); 00080 } 00081 00083 typedef boost::function<void(const M&)> PublishFn; 00084 00093 virtual void publish(const Base& message, const PublishFn& publish_fn) const = 0; 00094 00095 void publishInternal(const M& message) const { 00096 if (simple_impl_) simple_impl_->pub_.publish(message); 00097 } 00098 00104 virtual std::string getTopicToAdvertise(const std::string& base_topic) const 00105 { 00106 return base_topic + "/" + this->getTransportName(); 00107 } 00108 00114 virtual void connectCallback(const ros::SingleSubscriberPublisher& pub) {} 00115 void connectCallbackHandle(const ros::SingleSubscriberPublisher& pub) { 00116 this->connectCallback(pub); 00117 } 00118 00124 virtual void disconnectCallback(const ros::SingleSubscriberPublisher& pub) {} 00125 void disconnectCallbackHandle(const ros::SingleSubscriberPublisher& pub) { 00126 this->disconnectCallback(pub); 00127 } 00128 00132 const ros::NodeHandle& getParamNode() const 00133 { 00134 return simple_impl_->param_nh_; 00135 } 00136 00137 ros::NodeHandle& getNodeHandle() 00138 { 00139 return simple_impl_->nh_; 00140 } 00141 00142 private: 00143 struct SimplePublisherPluginImpl 00144 { 00145 SimplePublisherPluginImpl(ros::NodeHandle& nh, const ros::NodeHandle& param_nh) 00146 : nh_(nh), param_nh_(param_nh) 00147 { 00148 } 00149 00150 ros::NodeHandle nh_; 00151 const ros::NodeHandle param_nh_; 00152 ros::Publisher pub_; 00153 }; 00154 00155 boost::scoped_ptr<SimplePublisherPluginImpl> simple_impl_; 00156 bool forcelatch_; 00157 00158 typedef void (SimplePublisherPlugin::*SubscriberStatusMemFn)(const ros::SingleSubscriberPublisher& pub); 00159 00164 ros::SubscriberStatusCallback bindCB(const typename SingleSubscriberPublisher<Base>::StatusCB& user_cb, 00165 SubscriberStatusMemFn internal_cb_fn) 00166 { 00167 ros::SubscriberStatusCallback internal_cb = boost::bind(internal_cb_fn, this, _1); 00168 if (user_cb) 00169 return boost::bind(&SimplePublisherPlugin::subscriberCB, this, _1, user_cb, internal_cb); 00170 else 00171 return internal_cb; 00172 } 00173 00179 void subscriberCB(const ros::SingleSubscriberPublisher& ros_ssp, 00180 const typename SingleSubscriberPublisher<Base>::StatusCB& user_cb, 00181 const ros::SubscriberStatusCallback& internal_cb) 00182 { 00183 // First call the internal callback (for sending setup headers, etc.) 00184 internal_cb(ros_ssp); 00185 00186 // Construct a function object for publishing Base through the 00187 // subclass-implemented publish() using the ros::SingleSubscriberPublisher to send 00188 // messages of the transport-specific type. 00189 typedef void (SimplePublisherPlugin::*PublishMemFn)(const Base&, const PublishFn&) const; 00190 PublishMemFn pub_mem_fn = &SimplePublisherPlugin::publish; 00191 MessagePublishFn message_publish_fn = boost::bind(pub_mem_fn, this, _1, bindInternalPublisher(ros_ssp)); 00192 00193 SingleSubscriberPublisher<Base> ssp(ros_ssp.getSubscriberName(), getTopic(), 00194 boost::bind(&SimplePublisherPlugin::getNumSubscribers, this), 00195 message_publish_fn); 00196 user_cb(ssp); 00197 } 00198 00199 typedef boost::function<void(const Base&)> MessagePublishFn; 00200 00207 template <class PubT> 00208 PublishFn bindInternalPublisher(const PubT& pub) const 00209 { 00210 // Bind PubT::publish(const Message&) as PublishFn 00211 typedef void (PubT::*InternalPublishMemFn)(const M&) const; 00212 InternalPublishMemFn internal_pub_mem_fn = &PubT::publish; 00213 return boost::bind(internal_pub_mem_fn, &pub, _1); 00214 } 00215 }; 00216 00217 } //namespace message_transport 00218 00219 #endif