$search
00001 #ifndef MESSAGE_TRANSPORT_PUBLISHER_IMPL_H 00002 #define MESSAGE_TRANSPORT_PUBLISHER_IMPL_H 00003 00004 /********************************************************************* 00005 * Software License Agreement (BSD License) 00006 * 00007 * Copyright (c) 2009, Willow Garage, Inc. 00008 * All rights reserved. 00009 * 00010 * Redistribution and use in source and binary forms, with or without 00011 * modification, are permitted provided that the following conditions 00012 * are met: 00013 * 00014 * * Redistributions of source code must retain the above copyright 00015 * notice, this list of conditions and the following disclaimer. 00016 * * Redistributions in binary form must reproduce the above 00017 * copyright notice, this list of conditions and the following 00018 * disclaimer in the documentation and/or other materials provided 00019 * with the distribution. 00020 * * Neither the name of the Willow Garage nor the names of its 00021 * contributors may be used to endorse or promote products derived 00022 * from this software without specific prior written permission. 00023 * 00024 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 00025 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 00026 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 00027 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 00028 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 00029 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 00030 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 00031 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 00032 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 00033 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 00034 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00035 * POSSIBILITY OF SUCH DAMAGE. 00036 *********************************************************************/ 00037 00038 #include "message_transport/publisher.h" 00039 #include "message_transport/publisher_plugin.h" 00040 #include <pluginlib/class_loader.h> 00041 #include <boost/ptr_container/ptr_vector.hpp> 00042 #include <boost/foreach.hpp> 00043 #include <boost/algorithm/string/erase.hpp> 00044 00045 namespace message_transport { 00046 00047 class PublisherImplGen 00048 { 00049 public: 00050 PublisherImplGen(const std::string & topic) : 00051 base_topic_(topic), unadvertised_(false) { } 00052 00053 virtual ~PublisherImplGen() 00054 { 00055 } 00056 00057 virtual uint32_t getNumSubscribers() const = 0; 00058 uint32_t getNumSubscribersBindable() const { 00059 return this->getNumSubscribers(); 00060 } 00061 00062 std::string getTopic() const 00063 { 00064 return base_topic_; 00065 } 00066 00067 bool isValid() const 00068 { 00069 return !unadvertised_; 00070 } 00071 00072 void shutdown() { 00073 this->shutdownImpl(); 00074 } 00075 00076 virtual void shutdownImpl() = 0; 00077 00078 template <class M> 00079 void subscriberCB(const SingleSubscriberPublisher<M>& plugin_pub, 00080 const typename SingleSubscriberPublisher<M>::StatusCB& user_cb) 00081 { 00082 SingleSubscriberPublisher<M> ssp(plugin_pub.getSubscriberName(), this->getTopic(), 00083 boost::bind(&PublisherImplGen::getNumSubscribersBindable, this), 00084 plugin_pub.publish_fn_); 00085 user_cb(ssp); 00086 } 00087 00088 virtual std::vector<std::string> getDeclaredClasses() = 0; 00089 00090 00091 template <class M> 00092 void publish(const M& message) const; 00093 00094 template <class M> 00095 void publish(const typename M::ConstPtr& message) const; 00096 00097 protected : 00098 std::string base_topic_; 00099 bool unadvertised_; 00100 //double constructed_; 00101 }; 00102 00103 template <class M> 00104 class PublisherImpl : public PublisherImplGen 00105 { 00106 public : 00107 PublisherImpl(const std::string & topic, 00108 const std::string & packageName, 00109 const std::string & className) : PublisherImplGen(topic), 00110 loader_(packageName, 00111 std::string("message_transport::PublisherPlugin<")+className+">") 00112 { 00113 } 00114 00115 virtual ~PublisherImpl() { 00116 shutdownImpl(); 00117 } 00118 00119 virtual uint32_t getNumSubscribers() const 00120 { 00121 uint32_t count = 0; 00122 for (unsigned int i=0;i<publishers_.size();i++) { 00123 count += publishers_[i]->getNumSubscribers(); 00124 } 00125 return count; 00126 } 00127 00128 virtual void shutdownImpl() 00129 { 00130 if (!unadvertised_) { 00131 unadvertised_ = true; 00132 for (unsigned int i=0;i<publishers_.size();i++) { 00133 publishers_[i]->shutdown(); 00134 } 00135 publishers_.clear(); 00136 } 00137 } 00138 00139 virtual std::vector<std::string> getDeclaredClasses() { 00140 return loader_.getDeclaredClasses(); 00141 } 00142 00143 boost::shared_ptr< PublisherPlugin<M> > addInstance(const std::string & name) { 00144 #if ROS_VERSION_MINIMUM(1, 7, 0) // if current ros version is >= 1.7.0 00145 boost::shared_ptr< PublisherPlugin<M> > pub = loader_.createInstance(name); 00146 #else 00147 boost::shared_ptr< PublisherPlugin<M> > pub(loader_.createClassInstance(name)); 00148 #endif 00149 publishers_.push_back(pub); 00150 return pub; 00151 } 00152 00153 uint32_t getNumPublishers() const { 00154 return publishers_.size(); 00155 } 00156 00157 void publish(const M& message) const { 00158 for (unsigned int i=0;i<publishers_.size();i++) { 00159 if (publishers_[i]->getNumSubscribers() > 0) { 00160 publishers_[i]->publish(message); 00161 } 00162 } 00163 } 00164 00165 void publish(const typename M::ConstPtr& message) const { 00166 for (unsigned int i=0;i<publishers_.size();i++) { 00167 if (publishers_[i]->getNumSubscribers() > 0) { 00168 publishers_[i]->publish(message); 00169 } 00170 } 00171 } 00172 protected: 00173 pluginlib::ClassLoader< PublisherPlugin<M> > loader_; 00174 std::vector<boost::shared_ptr< PublisherPlugin<M> > > publishers_; 00175 }; 00176 00177 template <class M> 00178 void PublisherImplGen::publish(const M& message) const 00179 { 00180 (dynamic_cast<const PublisherImpl<M>* const>(this))->publish(message); 00181 } 00182 00183 template <class M> 00184 void PublisherImplGen::publish(const typename M::ConstPtr& message) const 00185 { 00186 (dynamic_cast<const PublisherImpl<M>* const>(this))->publish(message); 00187 } 00188 }; 00189 #endif // MESSAGE_TRANSPORT_PUBLISHER_IMPL_H