subscriber_impl.h
Go to the documentation of this file.
00001 #ifndef MESSAGE_TRANSPORT_SUBSCRIBER_IMPL_H
00002 #define MESSAGE_TRANSPORT_SUBSCRIBER_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/subscriber_plugin.h"
00039 #include <pluginlib/class_loader.h>
00040 #include <boost/scoped_ptr.hpp>
00041 
00042 namespace message_transport {
00043 
00044         class  SubscriberImplGen
00045         {
00046                 public :
00047                         SubscriberImplGen() : unsubscribed_(false) { }
00048 
00049                         ~SubscriberImplGen()
00050                         {
00051                         }
00052 
00053                         bool isValid() const
00054                         {
00055                                 return !unsubscribed_;
00056                         }
00057 
00058                         virtual void reset(const TransportHints& transport_hints) = 0;
00059                         void shutdown() {
00060                                 this->shutdownImpl();
00061                         }
00062                         virtual void shutdownImpl() = 0;
00063                         virtual boost::shared_ptr< SubscriberPluginGen > getSubscriber() = 0;
00064 
00065                         template <class M> 
00066                                 boost::shared_ptr< SubscriberPlugin<M> > getTemplateSubscriber() {
00067                     return boost::dynamic_pointer_cast< SubscriberPlugin<M> >(getSubscriber());
00068                                 }
00069 
00070 
00071                         virtual std::vector<std::string> getDeclaredClasses() = 0;
00072                 protected :
00073 
00074                         bool unsubscribed_;
00075         };
00076 
00077         template <class M>
00078                 class  SubscriberImpl : public SubscriberImplGen
00079         {
00080                 public:
00081                         SubscriberImpl(const std::string & packageName,const std::string & className)
00082                                 : loader_(packageName, 
00083                                                 std::string("message_transport::SubscriberPlugin<")+className+">") { }
00084 
00085                         ~SubscriberImpl() {
00086                                 shutdownImpl();
00087                         }
00088 
00089                         virtual void shutdownImpl()
00090                         {
00091                                 if (!unsubscribed_) {
00092                                         unsubscribed_ = true;
00093                                         subscriber_->shutdown();
00094                                 }
00095                         }
00096 
00097                         virtual void reset(const TransportHints& transport_hints) {
00098                                 std::string lookup_name = SubscriberPluginGen::getLookupName(transport_hints.getTransport());
00099 #if ROS_VERSION_MINIMUM(1, 7, 0) // if current ros version is >= 1.7.0
00100                                 subscriber_ = loader_.createInstance(lookup_name);
00101 #else
00102                                 subscriber_.reset(loader_.createClassInstance(lookup_name));
00103 #endif
00104                         }
00105 
00106                         virtual boost::shared_ptr< SubscriberPluginGen > getSubscriber() {
00107                                 return subscriber_;
00108                         }
00109 
00110                         virtual std::vector<std::string> getDeclaredClasses() {
00111                                 return loader_.getDeclaredClasses();
00112                         }
00113 
00114                 protected:
00115 
00116                         pluginlib::ClassLoader< SubscriberPlugin<M> > loader_;
00117             boost::shared_ptr< SubscriberPlugin<M> > subscriber_;
00118         };
00119 };
00120 
00121 #endif // MESSAGE_TRANSPORT_SUBSCRIBER_IMPL_H


message_transport_common
Author(s): Cedric Pradalier
autogenerated on Sat Dec 28 2013 16:56:55