publisher.h
Go to the documentation of this file.
00001 /*********************************************************************
00002  * Software License Agreement (BSD License)
00003  * 
00004  *  Copyright (c) 2009, Willow Garage, Inc.
00005  *  All rights reserved.
00006  * 
00007  *  Redistribution and use in source and binary forms, with or without
00008  *  modification, are permitted provided that the following conditions
00009  *  are met:
00010  * 
00011  *   * Redistributions of source code must retain the above copyright
00012  *     notice, this list of conditions and the following disclaimer.
00013  *   * Redistributions in binary form must reproduce the above
00014  *     copyright notice, this list of conditions and the following
00015  *     disclaimer in the documentation and/or other materials provided
00016  *     with the distribution.
00017  *   * Neither the name of the Willow Garage nor the names of its
00018  *     contributors may be used to endorse or promote products derived
00019  *     from this software without specific prior written permission.
00020  * 
00021  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032  *  POSSIBILITY OF SUCH DAMAGE.
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                                         // Note: the subscriber callback must be bound to the internal Impl object, not
00157                                         // 'this'. Due to copying behavior the Impl object may outlive this.
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 } //namespace message_transport
00171 
00172 #endif


message_transport_common
Author(s): Cedric Pradalier
autogenerated on Sun Oct 5 2014 23:48:49