signal9.h
Go to the documentation of this file.
00001 /*********************************************************************
00002 * Software License Agreement (BSD License)
00003 *
00004 *  Copyright (c) 2010, 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_FILTERS_SIGNAL9_H
00036 #define MESSAGE_FILTERS_SIGNAL9_H
00037 
00038 #include <boost/noncopyable.hpp>
00039 
00040 #include "connection.h"
00041 #include "null_types.h"
00042 #include <ros/message_event.h>
00043 #include <ros/parameter_adapter.h>
00044 
00045 #include <boost/bind.hpp>
00046 #include <boost/thread/mutex.hpp>
00047 
00048 namespace message_filters
00049 {
00050 using ros::ParameterAdapter;
00051 
00052 template<typename M0, typename M1, typename M2, typename M3, typename M4, typename M5, typename M6, typename M7, typename M8>
00053 class CallbackHelper9
00054 {
00055 public:
00056   typedef ros::MessageEvent<M0 const> M0Event;
00057   typedef ros::MessageEvent<M1 const> M1Event;
00058   typedef ros::MessageEvent<M2 const> M2Event;
00059   typedef ros::MessageEvent<M3 const> M3Event;
00060   typedef ros::MessageEvent<M4 const> M4Event;
00061   typedef ros::MessageEvent<M5 const> M5Event;
00062   typedef ros::MessageEvent<M6 const> M6Event;
00063   typedef ros::MessageEvent<M7 const> M7Event;
00064   typedef ros::MessageEvent<M8 const> M8Event;
00065 
00066   virtual ~CallbackHelper9() {}
00067 
00068   virtual void call(bool nonconst_force_copy, const M0Event& e0, const M1Event& e1, const M2Event& e2, const M3Event& e3,
00069                     const M4Event& e4, const M5Event& e5, const M6Event& e6, const M7Event& e7, const M8Event& e8) = 0;
00070 
00071   typedef boost::shared_ptr<CallbackHelper9> Ptr;
00072 };
00073 
00074 template<typename P0, typename P1, typename P2, typename P3, typename P4, typename P5, typename P6, typename P7, typename P8>
00075 class CallbackHelper9T :
00076   public CallbackHelper9<typename ParameterAdapter<P0>::Message,
00077                          typename ParameterAdapter<P1>::Message,
00078                          typename ParameterAdapter<P2>::Message,
00079                          typename ParameterAdapter<P3>::Message,
00080                          typename ParameterAdapter<P4>::Message,
00081                          typename ParameterAdapter<P5>::Message,
00082                          typename ParameterAdapter<P6>::Message,
00083                          typename ParameterAdapter<P7>::Message,
00084                          typename ParameterAdapter<P8>::Message>
00085 {
00086 private:
00087   typedef ParameterAdapter<P0> A0;
00088   typedef ParameterAdapter<P1> A1;
00089   typedef ParameterAdapter<P2> A2;
00090   typedef ParameterAdapter<P3> A3;
00091   typedef ParameterAdapter<P4> A4;
00092   typedef ParameterAdapter<P5> A5;
00093   typedef ParameterAdapter<P6> A6;
00094   typedef ParameterAdapter<P7> A7;
00095   typedef ParameterAdapter<P8> A8;
00096   typedef typename A0::Event M0Event;
00097   typedef typename A1::Event M1Event;
00098   typedef typename A2::Event M2Event;
00099   typedef typename A3::Event M3Event;
00100   typedef typename A4::Event M4Event;
00101   typedef typename A5::Event M5Event;
00102   typedef typename A6::Event M6Event;
00103   typedef typename A7::Event M7Event;
00104   typedef typename A8::Event M8Event;
00105 
00106 public:
00107   typedef boost::function<void(typename A0::Parameter, typename A1::Parameter, typename A2::Parameter,
00108                                typename A3::Parameter, typename A4::Parameter, typename A5::Parameter,
00109                                typename A6::Parameter, typename A7::Parameter, typename A8::Parameter)> Callback;
00110 
00111   CallbackHelper9T(const Callback& cb)
00112   : callback_(cb)
00113   {
00114   }
00115 
00116   virtual void call(bool nonconst_force_copy, const M0Event& e0, const M1Event& e1, const M2Event& e2, const M3Event& e3,
00117                     const M4Event& e4, const M5Event& e5, const M6Event& e6, const M7Event& e7, const M8Event& e8)
00118   {
00119     M0Event my_e0(e0, nonconst_force_copy || e0.nonConstWillCopy());
00120     M1Event my_e1(e1, nonconst_force_copy || e0.nonConstWillCopy());
00121     M2Event my_e2(e2, nonconst_force_copy || e0.nonConstWillCopy());
00122     M3Event my_e3(e3, nonconst_force_copy || e0.nonConstWillCopy());
00123     M4Event my_e4(e4, nonconst_force_copy || e0.nonConstWillCopy());
00124     M5Event my_e5(e5, nonconst_force_copy || e0.nonConstWillCopy());
00125     M6Event my_e6(e6, nonconst_force_copy || e0.nonConstWillCopy());
00126     M7Event my_e7(e7, nonconst_force_copy || e0.nonConstWillCopy());
00127     M8Event my_e8(e8, nonconst_force_copy || e0.nonConstWillCopy());
00128     callback_(A0::getParameter(e0),
00129               A1::getParameter(e1),
00130               A2::getParameter(e2),
00131               A3::getParameter(e3),
00132               A4::getParameter(e4),
00133               A5::getParameter(e5),
00134               A6::getParameter(e6),
00135               A7::getParameter(e7),
00136               A8::getParameter(e8));
00137   }
00138 
00139 private:
00140   Callback callback_;
00141 };
00142 
00143 template<typename M0, typename M1, typename M2, typename M3, typename M4, typename M5, typename M6, typename M7, typename M8>
00144 class Signal9
00145 {
00146   typedef boost::shared_ptr<CallbackHelper9<M0, M1, M2, M3, M4, M5, M6, M7, M8> > CallbackHelper9Ptr;
00147   typedef std::vector<CallbackHelper9Ptr> V_CallbackHelper9;
00148 
00149 public:
00150   typedef ros::MessageEvent<M0 const> M0Event;
00151   typedef ros::MessageEvent<M1 const> M1Event;
00152   typedef ros::MessageEvent<M2 const> M2Event;
00153   typedef ros::MessageEvent<M3 const> M3Event;
00154   typedef ros::MessageEvent<M4 const> M4Event;
00155   typedef ros::MessageEvent<M5 const> M5Event;
00156   typedef ros::MessageEvent<M6 const> M6Event;
00157   typedef ros::MessageEvent<M7 const> M7Event;
00158   typedef ros::MessageEvent<M8 const> M8Event;
00159   typedef boost::shared_ptr<M0 const> M0ConstPtr;
00160   typedef boost::shared_ptr<M1 const> M1ConstPtr;
00161   typedef boost::shared_ptr<M2 const> M2ConstPtr;
00162   typedef boost::shared_ptr<M3 const> M3ConstPtr;
00163   typedef boost::shared_ptr<M4 const> M4ConstPtr;
00164   typedef boost::shared_ptr<M5 const> M5ConstPtr;
00165   typedef boost::shared_ptr<M6 const> M6ConstPtr;
00166   typedef boost::shared_ptr<M7 const> M7ConstPtr;
00167   typedef boost::shared_ptr<M8 const> M8ConstPtr;
00168   typedef const boost::shared_ptr<NullType const>& NullP;
00169 
00170   template<typename P0, typename P1, typename P2, typename P3, typename P4, typename P5, typename P6, typename P7, typename P8>
00171   Connection addCallback(const boost::function<void(P0, P1, P2, P3, P4, P5, P6, P7, P8)>& callback)
00172   {
00173     CallbackHelper9T<P0, P1, P2, P3, P4, P5, P6, P7, P8>* helper = new CallbackHelper9T<P0, P1, P2, P3, P4, P5, P6, P7, P8>(callback);
00174 
00175     boost::mutex::scoped_lock lock(mutex_);
00176     callbacks_.push_back(CallbackHelper9Ptr(helper));
00177     return Connection(boost::bind(&Signal9::removeCallback, this, callbacks_.back()));
00178   }
00179 
00180   template<typename P0, typename P1>
00181   Connection addCallback(void(*callback)(P0, P1))
00182   {
00183     return addCallback(boost::function<void(P0, P1, NullP, NullP, NullP, NullP, NullP, NullP, NullP)>(boost::bind(callback, _1, _2)));
00184   }
00185 
00186   template<typename P0, typename P1, typename P2>
00187   Connection addCallback(void(*callback)(P0, P1, P2))
00188   {
00189     return addCallback(boost::function<void(P0, P1, P2, NullP, NullP, NullP, NullP, NullP, NullP)>(boost::bind(callback, _1, _2, _3)));
00190   }
00191 
00192   template<typename P0, typename P1, typename P2, typename P3>
00193   Connection addCallback(void(*callback)(P0, P1, P2, P3))
00194   {
00195     return addCallback(boost::function<void(P0, P1, P2, P3, NullP, NullP, NullP, NullP, NullP)>(boost::bind(callback, _1, _2, _3, _4)));
00196   }
00197 
00198   template<typename P0, typename P1, typename P2, typename P3, typename P4>
00199   Connection addCallback(void(*callback)(P0, P1, P2, P3, P4))
00200   {
00201     return addCallback(boost::function<void(P0, P1, P2, P3, P4, NullP, NullP, NullP, NullP)>(boost::bind(callback, _1, _2, _3, _4, _5)));
00202   }
00203 
00204   template<typename P0, typename P1, typename P2, typename P3, typename P4, typename P5>
00205   Connection addCallback(void(*callback)(P0, P1, P2, P3, P4, P5))
00206   {
00207     return addCallback(boost::function<void(P0, P1, P2, P3, P4, P5, NullP, NullP, NullP)>(boost::bind(callback, _1, _2, _3, _4, _5, _6)));
00208   }
00209 
00210   template<typename P0, typename P1, typename P2, typename P3, typename P4, typename P5, typename P6>
00211   Connection addCallback(void(*callback)(P0, P1, P2, P3, P4, P5, P6))
00212   {
00213     return addCallback(boost::function<void(P0, P1, P2, P3, P4, P5, P6, NullP, NullP)>(boost::bind(callback, _1, _2, _3, _4, _5, _6, _7)));
00214   }
00215 
00216   template<typename P0, typename P1, typename P2, typename P3, typename P4, typename P5, typename P6, typename P7>
00217   Connection addCallback(void(*callback)(P0, P1, P2, P3, P4, P5, P6, P7))
00218   {
00219     return addCallback(boost::function<void(P0, P1, P2, P3, P4, P5, P6, P7, NullP)>(boost::bind(callback, _1, _2, _3, _4, _5, _6, _7, _8)));
00220   }
00221 
00222   template<typename P0, typename P1, typename P2, typename P3, typename P4, typename P5, typename P6, typename P7, typename P8>
00223   Connection addCallback(void(*callback)(P0, P1, P2, P3, P4, P5, P6, P7, P8))
00224   {
00225     return addCallback(boost::function<void(P0, P1, P2, P3, P4, P5, P6, P7, P8)>(boost::bind(callback, _1, _2, _3, _4, _5, _6, _7, _8, _9)));
00226   }
00227 
00228   template<typename T, typename P0, typename P1>
00229   Connection addCallback(void(T::*callback)(P0, P1), T* t)
00230   {
00231     return addCallback(boost::function<void(P0, P1, NullP, NullP, NullP, NullP, NullP, NullP, NullP)>(boost::bind(callback, t, _1, _2)));
00232   }
00233 
00234   template<typename T, typename P0, typename P1, typename P2>
00235   Connection addCallback(void(T::*callback)(P0, P1, P2), T* t)
00236   {
00237     return addCallback(boost::function<void(P0, P1, P2, NullP, NullP, NullP, NullP, NullP, NullP)>(boost::bind(callback, t, _1, _2, _3)));
00238   }
00239 
00240   template<typename T, typename P0, typename P1, typename P2, typename P3>
00241   Connection addCallback(void(T::*callback)(P0, P1, P2, P3), T* t)
00242   {
00243     return addCallback(boost::function<void(P0, P1, P2, P3, NullP, NullP, NullP, NullP, NullP)>(boost::bind(callback, t, _1, _2, _3, _4)));
00244   }
00245 
00246   template<typename T, typename P0, typename P1, typename P2, typename P3, typename P4>
00247   Connection addCallback(void(T::*callback)(P0, P1, P2, P3, P4), T* t)
00248   {
00249     return addCallback(boost::function<void(P0, P1, P2, P3, P4, NullP, NullP, NullP, NullP)>(boost::bind(callback, t, _1, _2, _3, _4, _5)));
00250   }
00251 
00252   template<typename T, typename P0, typename P1, typename P2, typename P3, typename P4, typename P5>
00253   Connection addCallback(void(T::*callback)(P0, P1, P2, P3, P4, P5), T* t)
00254   {
00255     return addCallback(boost::function<void(P0, P1, P2, P3, P4, P5, NullP, NullP, NullP)>(boost::bind(callback, t, _1, _2, _3, _4, _5, _6)));
00256   }
00257 
00258   template<typename T, typename P0, typename P1, typename P2, typename P3, typename P4, typename P5, typename P6>
00259   Connection addCallback(void(T::*callback)(P0, P1, P2, P3, P4, P5, P6), T* t)
00260   {
00261     return addCallback(boost::function<void(P0, P1, P2, P3, P4, P5, P6, NullP, NullP)>(boost::bind(callback, t, _1, _2, _3, _4, _5, _6, _7)));
00262   }
00263 
00264   template<typename T, typename P0, typename P1, typename P2, typename P3, typename P4, typename P5, typename P6, typename P7>
00265   Connection addCallback(void(T::*callback)(P0, P1, P2, P3, P4, P5, P6, P7), T* t)
00266   {
00267     return addCallback(boost::function<void(P0, P1, P2, P3, P4, P5, P6, P7, NullP)>(boost::bind(callback, t, _1, _2, _3, _4, _5, _6, _7, _8)));
00268   }
00269 
00270   template<typename C>
00271   Connection addCallback( C& callback)
00272   {
00273     return addCallback<const M0ConstPtr&,
00274                      const M1ConstPtr&,
00275                      const M2ConstPtr&,
00276                      const M3ConstPtr&,
00277                      const M4ConstPtr&,
00278                      const M5ConstPtr&,
00279                      const M6ConstPtr&,
00280                      const M7ConstPtr&,
00281                      const M8ConstPtr&>(boost::bind(callback, _1, _2, _3, _4, _5, _6, _7, _8, _9));
00282   }
00283 
00284   void removeCallback(const CallbackHelper9Ptr& helper)
00285   {
00286     boost::mutex::scoped_lock lock(mutex_);
00287     typename V_CallbackHelper9::iterator it = std::find(callbacks_.begin(), callbacks_.end(), helper);
00288     if (it != callbacks_.end())
00289     {
00290       callbacks_.erase(it);
00291     }
00292   }
00293 
00294   void call(const M0Event& e0, const M1Event& e1, const M2Event& e2, const M3Event& e3, const M4Event& e4,
00295             const M5Event& e5, const M6Event& e6, const M7Event& e7, const M8Event& e8)
00296   {
00297     boost::mutex::scoped_lock lock(mutex_);
00298     bool nonconst_force_copy = callbacks_.size() > 1;
00299     typename V_CallbackHelper9::iterator it = callbacks_.begin();
00300     typename V_CallbackHelper9::iterator end = callbacks_.end();
00301     for (; it != end; ++it)
00302     {
00303       const CallbackHelper9Ptr& helper = *it;
00304       helper->call(nonconst_force_copy, e0, e1, e2, e3, e4, e5, e6, e7, e8);
00305     }
00306   }
00307 
00308 private:
00309   boost::mutex mutex_;
00310   V_CallbackHelper9 callbacks_;
00311 };
00312 
00313 } // message_filters
00314 
00315 #endif // MESSAGE_FILTERS_SIGNAL9_H
00316 
00317 


message_filters
Author(s): Josh Faust, Vijay Pradeep
autogenerated on Mon Oct 6 2014 11:47:35