ConnectionManager.hpp
Go to the documentation of this file.
00001 /***************************************************************************
00002   tag: Peter Soetens  Thu Oct 22 11:59:08 CEST 2009  ConnectionManager.hpp
00003 
00004                         ConnectionManager.hpp -  description
00005                            -------------------
00006     begin                : Thu October 22 2009
00007     copyright            : (C) 2009 Peter Soetens
00008     email                : peter@thesourcworks.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 /*
00040  * ConnectionManager.hpp
00041  *
00042  *  Created on: Oct 9, 2009
00043  *      Author: kaltan
00044  */
00045 
00046 #ifndef CONNECTIONMANAGER_HPP_
00047 #define CONNECTIONMANAGER_HPP_
00048 
00049 
00050 #include "ConnID.hpp"
00051 #include "List.hpp"
00052 #include "../ConnPolicy.hpp"
00053 #include "../os/Mutex.hpp"
00054 #include "../base/rtt-base-fwd.hpp"
00055 #include "../base/ChannelElementBase.hpp"
00056 #include <boost/tuple/tuple.hpp>
00057 #include <boost/bind.hpp>
00058 #include <boost/shared_ptr.hpp>
00059 #include <boost/lambda/lambda.hpp>
00060 
00061 #include <rtt/os/Mutex.hpp>
00062 #include <rtt/os/MutexLock.hpp>
00063 #include <list>
00064 
00065 
00066 namespace RTT
00067 {
00068 
00069     namespace internal
00070     {
00077         class RTT_API ConnectionManager
00078         {
00079         public:
00086             typedef boost::tuple<boost::shared_ptr<ConnID>, base::ChannelElementBase::shared_ptr, ConnPolicy> ChannelDescriptor;
00087 
00093             ConnectionManager(base::PortInterface* port);
00094             ~ConnectionManager();
00095 
00101             void addConnection(ConnID* port_id, base::ChannelElementBase::shared_ptr channel_input, ConnPolicy policy);
00102 
00103             bool removeConnection(ConnID* port_id);
00104 
00108             void disconnect();
00109 
00113             bool connected() const;
00114 
00116             bool disconnect(base::PortInterface* port);
00117 
00118             template<typename Pred>
00119             bool delete_if(Pred pred) {
00120                 RTT::os::MutexLock lock(connection_lock);
00121                 bool result = false;
00122                 std::list<ChannelDescriptor>::iterator it = connections.begin();
00123                 while (it != connections.end())
00124                 {
00125                     if (pred(*it))
00126                     {
00127                         result = true;
00128                         it = connections.erase(it);
00129                     }
00130                     else ++it;
00131                 }
00132                 return result;
00133             }
00134 
00143             template<typename Pred>
00144             void select_reader_channel(Pred pred, bool copy_old_data) {
00145                 RTT::os::MutexLock lock(connection_lock);
00146                 std::pair<bool, ChannelDescriptor> new_channel =
00147                     find_if(pred, copy_old_data);
00148                 if (new_channel.first)
00149                 {
00150                     // We don't clear the current channel (to get it to NoData state), because there is a race
00151                     // between find_if and this line. We have to accept (in other parts of the code) that eventually,
00152                     // all channels return 'OldData'.
00153                     cur_channel = new_channel.second;
00154                 }
00155             }
00156 
00157             template<typename Pred>
00158             std::pair<bool, ChannelDescriptor> find_if(Pred pred, bool copy_old_data) {
00159                 // We only copy OldData in the initial read of the current channel.
00160                 // if it has no new data, the search over the other channels starts,
00161                 // but no old data is needed.
00162                 ChannelDescriptor channel = cur_channel;
00163                 if ( channel.get<1>() )
00164                     if ( pred( copy_old_data, channel ) )
00165                         return std::make_pair(true, channel);
00166 
00167                 std::list<ChannelDescriptor>::iterator result;
00168                 for (result = connections.begin(); result != connections.end(); ++result)
00169                     if ( pred(false, *result) == true)
00170                         return std::make_pair(true, *result);
00171                 return std::make_pair(false, ChannelDescriptor());
00172             }
00173 
00178             bool isSingleConnection() const { return connections.size() == 1; }
00179 
00185             base::ChannelElementBase* getCurrentChannel() const {
00186                 return cur_channel.get<1>().get();
00187             }
00188 
00192             std::list<ChannelDescriptor> getChannels() const {
00193                 return connections;
00194             }
00195 
00201             void clear();
00202 
00203         protected:
00204 
00205             void updateCurrentChannel(bool reset_current);
00206 
00215             bool findMatchingPort(ConnID const* conn_id, ChannelDescriptor const& descriptor);
00216 
00221             bool eraseConnection(ChannelDescriptor& descriptor);
00222 
00224             os::Mutex connection_resize_mtx;
00225 
00229             base::PortInterface* mport;
00230 
00235             std::list< ChannelDescriptor > connections;
00236 
00240             ChannelDescriptor cur_channel;
00241 
00246             RTT::os::Mutex connection_lock;
00247         };
00248 
00249     }
00250 
00251 }
00252 
00253 #endif /* CONNECTIONMANAGER_HPP_ */


rtt
Author(s): RTT Developers
autogenerated on Thu Jan 2 2014 11:35:19