FusedFunctorDataSource.hpp
Go to the documentation of this file.
00001 /***************************************************************************
00002   tag: The SourceWorks  Tue Sep 7 00:55:18 CEST 2010  FusedFunctorDataSource.hpp
00003 
00004                         FusedFunctorDataSource.hpp -  description
00005                            -------------------
00006     begin                : Tue September 07 2010
00007     copyright            : (C) 2010 The SourceWorks
00008     email                : peter@thesourceworks.com
00009 
00010  ***************************************************************************
00011  *   This library is free software; you can redistribute it and/or         *
00012  *   modify it under the terms of the GNU General Public                   *
00013  *   License as published by the Free Software Foundation;                 *
00014  *   version 2 of the License.                                             *
00015  *                                                                         *
00016  *   As a special exception, you may use this file as part of a free       *
00017  *   software library without restriction.  Specifically, if other files   *
00018  *   instantiate templates or use macros or inline functions from this     *
00019  *   file, or you compile this file and link it with other files to        *
00020  *   produce an executable, this file does not by itself cause the         *
00021  *   resulting executable to be covered by the GNU General Public          *
00022  *   License.  This exception does not however invalidate any other        *
00023  *   reasons why the executable file might be covered by the GNU General   *
00024  *   Public License.                                                       *
00025  *                                                                         *
00026  *   This library is distributed in the hope that it will be useful,       *
00027  *   but WITHOUT ANY WARRANTY; without even the implied warranty of        *
00028  *   MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the GNU     *
00029  *   Lesser General Public License for more details.                       *
00030  *                                                                         *
00031  *   You should have received a copy of the GNU General Public             *
00032  *   License along with this library; if not, write to the Free Software   *
00033  *   Foundation, Inc., 59 Temple Place,                                    *
00034  *   Suite 330, Boston, MA  02111-1307  USA                                *
00035  *                                                                         *
00036  ***************************************************************************/
00037 
00038 
00039 #ifndef ORO_FUSEDFUNCTORDATASOURCE_HPP_
00040 #define ORO_FUSEDFUNCTORDATASOURCE_HPP_
00041 
00042 #include "DataSource.hpp"
00043 #include "CreateSequence.hpp"
00044 #include "../SendStatus.hpp"
00045 #include "BindStorage.hpp"
00046 #include "../ExecutionEngine.hpp"
00047 #include "../os/oro_allocator.hpp"
00048 #include <boost/bind.hpp>
00049 #include <boost/type_traits.hpp>
00050 #include <boost/function.hpp>
00051 #include <boost/function_types/function_type.hpp>
00052 #include <boost/fusion/include/invoke.hpp>
00053 #include <boost/fusion/include/invoke_procedure.hpp>
00054 #include <boost/mpl/bool.hpp>
00055 #include <boost/make_shared.hpp>
00056 
00057 namespace RTT
00058 {
00059     namespace internal
00060     {
00061         namespace bf = boost::fusion;
00062 
00068         template<typename Signature, class Enable=void>
00069         struct FusedFunctorDataSource
00070         : public DataSource<
00071                   typename remove_cr<typename boost::function_traits<Signature>::result_type>::type >
00072           {
00073               //BOOST_STATIC_ASSERT( boost::mpl::false_::value );
00074               typedef typename boost::function_traits<Signature>::result_type
00075                       result_type;
00076               typedef typename remove_cr<result_type>::type value_t;
00077               typedef typename DataSource<value_t>::const_reference_t const_reference_t;
00078               typedef create_sequence<
00079                       typename boost::function_types::parameter_types<Signature>::type> SequenceFactory;
00080               typedef typename SequenceFactory::type DataSourceSequence;
00081               typedef boost::function<Signature> call_type;
00082               typedef typename SequenceFactory::data_type arg_type;
00083               boost::function<Signature> ff;
00084               DataSourceSequence args;
00085               mutable RStore<result_type> ret;
00086           public:
00087               typedef boost::intrusive_ptr<FusedFunctorDataSource<Signature> >
00088                       shared_ptr;
00089 
00090               template<class Func>
00091               FusedFunctorDataSource(Func g,
00092                                      const DataSourceSequence& s = DataSourceSequence() ) :
00093                   ff(g), args(s)
00094               {
00095               }
00096 
00097               void setArguments(const DataSourceSequence& a1)
00098               {
00099                   args = a1;
00100               }
00101 
00102               value_t value() const
00103               {
00104                   return ret.result();
00105               }
00106 
00107               const_reference_t rvalue() const
00108               {
00109                   return ret.result();
00110               }
00111 
00112               bool evaluate() const {
00113                   // forward invoke to ret object, which stores return value.
00114                   // this foo pointer dance is because older compilers don't handle using
00115                   // &bf::invoke<call_type,arg_type> directly.
00116                   typedef typename bf::result_of::invoke<call_type,arg_type>::type iret;
00117                   typedef iret(*IType)(call_type, arg_type const&);
00118                   IType foo = &bf::invoke<call_type,arg_type>;
00119                   ret.exec( boost::bind(foo, boost::ref(ff), SequenceFactory::data(args)));
00120                   SequenceFactory::update(args);
00121                   return true;
00122               }
00123 
00124               value_t get() const
00125               {
00126                   FusedFunctorDataSource<Signature>::evaluate();
00127                   return ret.result();
00128               }
00129 
00130               virtual FusedFunctorDataSource<Signature>* clone() const
00131               {
00132                   return new FusedFunctorDataSource<Signature> (ff, args);
00133               }
00134               virtual FusedFunctorDataSource<Signature>* copy(
00135                                                           std::map<
00136                                                                   const base::DataSourceBase*,
00137                                                                   base::DataSourceBase*>& alreadyCloned) const
00138               {
00139                   return new FusedFunctorDataSource<Signature> (ff, SequenceFactory::copy(args, alreadyCloned));
00140               }
00141           };
00142 
00143         template<typename Signature>
00144         struct FusedFunctorDataSource<Signature, typename boost::enable_if< is_pure_reference<typename boost::function_traits<Signature>::result_type> >::type >
00145         : public AssignableDataSource<
00146                   typename remove_cr<typename boost::function_traits<Signature>::result_type>::type >
00147           {
00148             //BOOST_STATIC_ASSERT( boost::mpl::false_::value );
00149               typedef typename boost::function_traits<Signature>::result_type
00150                       result_type;
00151               typedef typename remove_cr<result_type>::type value_t;
00152               typedef typename DataSource<value_t>::const_reference_t const_reference_t;
00153               typedef typename AssignableDataSource<value_t>::reference_t reference_t;
00154               typedef create_sequence<
00155                       typename boost::function_types::parameter_types<Signature>::type> SequenceFactory;
00156               typedef typename SequenceFactory::type DataSourceSequence;
00157               typedef boost::function<Signature> call_type;
00158               typedef typename SequenceFactory::data_type arg_type;
00159               boost::function<Signature> ff;
00160               DataSourceSequence args;
00161               mutable RStore<result_type> ret;
00162           public:
00163               typedef boost::intrusive_ptr<FusedFunctorDataSource<Signature> >
00164                       shared_ptr;
00165 
00166               template<class Func>
00167               FusedFunctorDataSource(Func g,
00168                                      const DataSourceSequence& s = DataSourceSequence() ) :
00169                   ff(g), args(s)
00170               {
00171               }
00172 
00173               void setArguments(const DataSourceSequence& a1)
00174               {
00175                   args = a1;
00176               }
00177 
00178               value_t value() const
00179               {
00180                   return ret.result();
00181               }
00182 
00183               const_reference_t rvalue() const
00184               {
00185                   return ret.result();
00186               }
00187 
00188               bool evaluate() const {
00189                   // forward invoke to ret object, which stores return value.
00190                   // this foo pointer dance is because older compilers don't handle using
00191                   // &bf::invoke<call_type,arg_type> directly.
00192                   typedef typename bf::result_of::invoke<call_type,arg_type>::type iret;
00193                   typedef iret(*IType)(call_type, arg_type const&);
00194                   IType foo = &bf::invoke<call_type,arg_type>;
00195                   ret.exec( boost::bind(foo, boost::ref(ff), SequenceFactory::data(args)));
00196                   SequenceFactory::update(args);
00197                   return true;
00198               }
00199               value_t get() const
00200               {
00201                   FusedFunctorDataSource<Signature>::evaluate();
00202                   return ret.result();
00203               }
00204 
00205               void set( typename AssignableDataSource<value_t>::param_t arg) {
00206                   // we need to get the new reference before we set the arg.
00207                   get(); ret.result() = arg;
00208               }
00209 
00210               reference_t set() {
00211                   get(); return ret.result();
00212               }
00213 
00214               virtual FusedFunctorDataSource<Signature>* clone() const
00215               {
00216                   return new FusedFunctorDataSource<Signature> (ff, args);
00217               }
00218               virtual FusedFunctorDataSource<Signature>* copy(
00219                                                           std::map<
00220                                                                   const base::DataSourceBase*,
00221                                                                   base::DataSourceBase*>& alreadyCloned) const
00222               {
00223                   return new FusedFunctorDataSource<Signature> (ff, SequenceFactory::copy(args, alreadyCloned));
00224               }
00225           };
00236         template<class Function>
00237         base::DataSourceBase* newFunctorDataSource(Function f, const std::vector<base::DataSourceBase::shared_ptr>& args)
00238         {
00239             typedef typename boost::function_types::function_type<Function>::type Signature;
00240             typedef internal::create_sequence<typename boost::function_types::parameter_types<Signature>::type> SequenceFactory;
00241             if ( args.size() != boost::function_traits<Signature>::arity )
00242                 throw wrong_number_of_args_exception(boost::function_traits<Signature>::arity, args.size() );
00243             return new FusedFunctorDataSource<Signature>(f, SequenceFactory::sources(args.begin()));
00244         }
00245 
00251         template<typename Signature>
00252         struct FusedMCallDataSource
00253         : public DataSource<
00254               typename remove_cr<typename boost::function_traits<Signature>::result_type>::type >
00255         {
00256               typedef typename boost::function_traits<Signature>::result_type
00257                       result_type;
00258               typedef typename remove_cr<result_type>::type value_t;
00259               typedef typename DataSource<value_t>::const_reference_t const_reference_t;
00260               typedef create_sequence<
00261                       typename boost::function_types::parameter_types<Signature>::type> SequenceFactory;
00262               typedef typename SequenceFactory::type DataSourceSequence;
00263               typename base::OperationCallerBase<Signature>::shared_ptr ff;
00264               DataSourceSequence args;
00265               mutable RStore<result_type> ret;
00266           public:
00267               typedef boost::intrusive_ptr<FusedMCallDataSource<Signature> >
00268                       shared_ptr;
00269 
00270               FusedMCallDataSource(typename base::OperationCallerBase<Signature>::shared_ptr g,
00271                                      const DataSourceSequence& s = DataSourceSequence() ) :
00272                   ff(g), args(s)
00273               {
00274               }
00275 
00276               void setArguments(const DataSourceSequence& a1)
00277               {
00278                   args = a1;
00279               }
00280 
00281               value_t value() const
00282               {
00283                   return ret.result();
00284               }
00285 
00286               const_reference_t rvalue() const
00287               {
00288                   return ret.result();
00289               }
00290 
00291               bool evaluate() const {
00292                   // put the member's object as first since SequenceFactory does not know about the OperationCallerBase type.
00293                   typedef bf::cons<base::OperationCallerBase<Signature>*, typename SequenceFactory::data_type> arg_type;
00294                   typedef typename AddMember<Signature,base::OperationCallerBase<Signature>* >::type call_type;
00295                   // this foo pointer dance is because older compilers don't handle using
00296                   // &bf::invoke<call_type,arg_type> directly.
00297                   typedef typename bf::result_of::invoke<call_type,arg_type>::type iret;
00298                   typedef iret(*IType)(call_type, arg_type const&);
00299                   IType foo = &bf::invoke<call_type,arg_type>;
00300                   // we need to store the ret value ourselves.
00301                   ret.exec( boost::bind(foo, &base::OperationCallerBase<Signature>::call, arg_type(ff.get(), SequenceFactory::data(args))) );
00302                   if(ret.isError()) {
00303                     ff->reportError();
00304                     ret.checkError();
00305                   }
00306                   SequenceFactory::update(args);
00307                   return true;
00308               }
00309 
00310               value_t get() const
00311               {
00312                   evaluate();
00313                   return ret.result();
00314               }
00315 
00316               virtual FusedMCallDataSource<Signature>* clone() const
00317               {
00318                   return new FusedMCallDataSource<Signature> (ff, args);
00319               }
00320               virtual FusedMCallDataSource<Signature>* copy(
00321                                                           std::map<
00322                                                                   const base::DataSourceBase*,
00323                                                                   base::DataSourceBase*>& alreadyCloned) const
00324               {
00325                   return new FusedMCallDataSource<Signature> (ff, SequenceFactory::copy(args, alreadyCloned));
00326               }
00327           };
00328 
00333         template<typename Signature>
00334         struct FusedMSendDataSource
00335         : public DataSource<SendHandle<Signature> >
00336           {
00337               typedef SendHandle<Signature> result_type;
00338               typedef result_type value_t;
00339               typedef typename DataSource<value_t>::const_reference_t const_reference_t;
00340               typedef create_sequence<
00341                       typename boost::function_types::parameter_types<Signature>::type> SequenceFactory;
00342               typedef typename SequenceFactory::type DataSourceSequence;
00343               typename base::OperationCallerBase<Signature>::shared_ptr ff;
00344               DataSourceSequence args;
00345               mutable SendHandle<Signature> sh; // mutable because of get() const
00346           public:
00347               typedef boost::intrusive_ptr<FusedMSendDataSource<Signature> >
00348                       shared_ptr;
00349 
00350               FusedMSendDataSource(typename base::OperationCallerBase<Signature>::shared_ptr g,
00351                                      const DataSourceSequence& s = DataSourceSequence() ) :
00352                   ff(g), args(s)
00353               {
00354               }
00355 
00356               void setArguments(const DataSourceSequence& a1)
00357               {
00358                   args = a1;
00359               }
00360 
00361               value_t value() const
00362               {
00363                   return sh;
00364               }
00365 
00366               const_reference_t rvalue() const
00367               {
00368                   return sh;
00369               }
00370 
00371               value_t get() const
00372               {
00373                   // put the member's object as first since SequenceFactory does not know about the OperationCallerBase type.
00374                   sh = bf::invoke(&base::OperationCallerBase<Signature>::send, bf::cons<base::OperationCallerBase<Signature>*, typename SequenceFactory::data_type>(ff.get(), SequenceFactory::data(args)));
00375                   return sh;
00376               }
00377 
00378               virtual FusedMSendDataSource<Signature>* clone() const
00379               {
00380                   return new FusedMSendDataSource<Signature> (ff, args);
00381               }
00382               virtual FusedMSendDataSource<Signature>* copy(
00383                                                           std::map<
00384                                                                   const base::DataSourceBase*,
00385                                                                   base::DataSourceBase*>& alreadyCloned) const
00386               {
00387                   return new FusedMSendDataSource<Signature> (ff, SequenceFactory::copy(args, alreadyCloned));
00388               }
00389           };
00390 
00397         template<typename Signature>
00398         struct FusedMCollectDataSource
00399         : public DataSource<SendStatus>
00400           {
00401               typedef SendStatus result_type;
00402               typedef result_type value_t;
00403               typedef DataSource<SendStatus>::const_reference_t const_reference_t;
00404               // push the SendHandle pointer in front.
00405               typedef typename CollectType<Signature>::type CollectSignature;
00406               typedef typename boost::function_types::parameter_types<CollectSignature>::type arg_types;
00407               typedef typename mpl::push_front<arg_types, SendHandle<Signature>& >::type handle_and_arg_types;
00408               typedef create_sequence< handle_and_arg_types
00409                       > SequenceFactory;
00410               typedef typename SequenceFactory::type DataSourceSequence;
00411               DataSourceSequence args;
00412               DataSource<bool>::shared_ptr isblocking;
00413               mutable SendStatus ss; // because of get() const
00414           public:
00415               typedef boost::intrusive_ptr<FusedMCollectDataSource<Signature> >
00416                       shared_ptr;
00417 
00418               FusedMCollectDataSource(
00419                                      const DataSourceSequence& s, DataSource<bool>::shared_ptr blocking ) :
00420                   args(s), isblocking(blocking), ss(SendFailure)
00421               {
00422               }
00423 
00424               void setArguments(const DataSourceSequence& a1)
00425               {
00426                   args = a1;
00427               }
00428 
00429               value_t value() const
00430               {
00431                   return ss;
00432               }
00433 
00434               const_reference_t rvalue() const
00435               {
00436                   return ss;
00437               }
00438 
00439               value_t get() const
00440               {
00441                   // put the member's object as first since SequenceFactory does not know about the OperationCallerBase type.
00442                   if (isblocking->get())
00443                       ss = bf::invoke(&SendHandle<Signature>::CBase::collect, SequenceFactory::data(args));
00444                   else
00445                       ss = bf::invoke(&SendHandle<Signature>::CBase::collectIfDone, SequenceFactory::data(args));
00446                   SequenceFactory::update(args);
00447                   return ss;
00448               }
00449 
00450               virtual FusedMCollectDataSource<Signature>* clone() const
00451               {
00452                   return new FusedMCollectDataSource<Signature> ( args, isblocking);
00453               }
00454               virtual FusedMCollectDataSource<Signature>* copy(
00455                                                           std::map<
00456                                                                   const base::DataSourceBase*,
00457                                                                   base::DataSourceBase*>& alreadyCloned) const
00458               {
00459                   return new FusedMCollectDataSource<Signature> ( SequenceFactory::copy(args, alreadyCloned), isblocking);
00460               }
00461           };
00462 
00467         template<typename Signature>
00468         struct FusedMSignal : public base::DisposableInterface
00469         {
00470             typedef typename boost::function_traits<Signature>::result_type
00471                     result_type;
00472             typedef result_type value_t;
00473             typedef create_sequence<
00474                     typename boost::function_types::parameter_types<Signature>::type> SequenceFactory;
00475             typedef typename SequenceFactory::atype DataSourceSequence;
00476             boost::shared_ptr<base::ActionInterface> mact;
00477             DataSourceSequence args;
00478             ExecutionEngine* subscriber;
00484             boost::shared_ptr<FusedMSignal<Signature> > self;
00485         public:
00486             typedef boost::shared_ptr<FusedMSignal<Signature> > shared_ptr;
00487 
00495             FusedMSignal(base::ActionInterface* act,
00496                          const DataSourceSequence& s, 
00497                          ExecutionEngine* subscr ) :
00498                 mact(act), args(s), subscriber(subscr), self()
00499             {
00500             }
00501 
00502             ~FusedMSignal() {
00503             }
00504 
00510             result_type invoke(typename SequenceFactory::data_type seq) {
00511                 if ( subscriber ) {
00512                     // asynchronous
00513                     shared_ptr sg = this->cloneRT();
00514                     SequenceFactory::set( seq, sg->args );
00515                   
00516                     sg->self = sg;
00517                     if ( subscriber->process( sg.get() ) ) {
00518                         // all ok
00519                     } else {
00520                         sg->dispose();
00521                     }
00522                 } else {
00523                     // synchronous
00524                     SequenceFactory::set( seq, args );
00525                     mact->execute();
00526                 }
00527 
00528                 return NA<result_type>::na();
00529             }
00530 
00531             void executeAndDispose() {
00532                 mact->execute();
00533                 dispose();
00534             }
00535 
00540             void dispose() {
00541                 self.reset();
00542             }
00543 
00544 
00545             void setArguments(const DataSourceSequence& a1)
00546             {
00547                 args = a1;
00548             }
00549 
00550             typename FusedMSignal<Signature>::shared_ptr cloneRT() const
00551             {
00552                 // returns identical copy of this;
00553                 return boost::allocate_shared<FusedMSignal<Signature> >(os::rt_allocator<FusedMSignal<Signature> >(), *this);
00554             }
00555         };
00556 
00557     }
00558 }
00559 
00560 #endif /* ORO_FUSEDFUNCTORDATASOURCE_HPP_ */


rtt
Author(s): RTT Developers
autogenerated on Sat Jun 8 2019 18:46:12