Program Listing for File sigslot.hpp

Return to documentation for file (/tmp/ws/src/ecl_core/ecl_sigslots/include/ecl/sigslots/sigslot.hpp)

/*****************************************************************************
** Ifdefs
*****************************************************************************/

#ifndef ECL_SIGSLOTS_SIGSLOT_HPP_
#define ECL_SIGSLOTS_SIGSLOT_HPP_

/*****************************************************************************
** Includes
*****************************************************************************/

#include <map>
#include <set>
#include <string>
#include <ecl/config/macros.hpp>
#include <ecl/threads/mutex.hpp>
#include <ecl/utilities/function_objects.hpp>
#include <ecl/utilities/void.hpp>
#include "manager.hpp"

/*****************************************************************************
** Namespaces
*****************************************************************************/

namespace ecl {

/*****************************************************************************
** Interface [General]
*****************************************************************************/
template <typename Data=Void>
class SigSlot {
public:
    /*********************
    ** Typedefs
    **********************/
    typedef typename Topic<Data>::Subscribers Subscribers;
    typedef typename std::map<std::string, const Subscribers*> PublicationMap;
    /*********************
    ** C&D
    **********************/
    SigSlot() : processing_count(0), number_of_handles(1) {
        function = new PartiallyBoundUnaryMemberFunction< SigSlot<Data> ,Data,void >( &SigSlot<Data>::emit, *this);
    }
    SigSlot(void (*f)(Data)) : processing_count(0), number_of_handles(1) {
        function = new UnaryFreeFunction<Data>(f);
    }
    template<typename C>
    SigSlot(void (C::*f)(Data), C &c) : processing_count(0), number_of_handles(1) {
        function = new PartiallyBoundUnaryMemberFunction<C,Data,void>(f,c);
    }

    ~SigSlot() {
        disconnect(); // stop any new processing from connected signals
        mutex.lock(); // acts like a barrier - holds up here if function still processing stuff.
        delete function;
    }

    const unsigned int& handles() const { return number_of_handles; }
    void incrHandles() { ++number_of_handles; }
    void decrHandles() { --number_of_handles; }
    void emit(Data data) {
        typename PublicationMap::const_iterator topic_iter;
        typename Subscribers::const_iterator slots_iter;
        for ( topic_iter = publications.begin(); topic_iter != publications.end(); ++topic_iter ) {
            const Subscribers* subscribers = topic_iter->second;
            for ( slots_iter = subscribers->begin(); slots_iter != subscribers->end(); ++slots_iter ) {
                SigSlot<Data> *sigslot = *slots_iter;
                sigslot->process(data);
            }
        }
    }
    void process(Data data) {
        mutex.trylock(); // Only lock if its not already locked.
        ++processing_count;
        (*function)(data);
        if ( --processing_count == 0 ) {
            mutex.unlock();
        }
    }
    void connectSignal(const std::string& topic) {
        // Logic:
        //   - if already publishing to this topic
        //     - don't do anything
        //   - else
        //     - if topic doesn't exist
        //       - Manager will automatically create a new topic
        //     - Manager returns the subscribers handle
        //     - Topic name and subscribers handle are stored locally here in publications
        publications.insert( std::pair<std::string, const Subscribers*>(topic, SigSlotsManager<Data>::connectSignal(topic,this)) );
    }
    void connectSlot(const std::string& topic) {
        std::pair< std::set<std::string>::iterator,bool > ret;
    //  std::cout << "Topic: " << topic << std::endl;
        ret = subscriptions.insert(topic); // Doesn't matter if it already exists.
        if ( ret.second ) {
            SigSlotsManager<Data>::connectSlot(topic,this);
        } // else { already subscribed to this topic }
    }
    void disconnect(const std::string &topic) {
        // std::set<std::string>::const_iterator listen_iter = subscriptions.find(topic);
        publications.erase(topic); // Doesn't matter if it finds it or not.
        SigSlotsManager<Void>::disconnect(topic,this);
    }
    void disconnect() {
        std::set<std::string>::iterator iter;
        for ( iter = subscriptions.begin(); iter != subscriptions.end(); ++iter ) {
            SigSlotsManager<Data>::disconnect(*iter, this);
        }
        subscriptions.clear();
        typename std::map<std::string,const Subscribers*>::iterator emit_iter;
        for ( emit_iter = publications.begin(); emit_iter != publications.end(); ++emit_iter ) {
            SigSlotsManager<Data>::disconnect(emit_iter->first, this);
        }
        publications.clear();
    }

    const std::set<std::string>& subscribedTopics() { return subscriptions; }

private:
    Mutex mutex;
    unsigned int processing_count; // number of running process()'
    unsigned int number_of_handles; // number of handles to this sigslot (allows copying)
    std::set<std::string> subscriptions; // topics this sigslot is listening to
    PublicationMap publications; // topics this sigslot is posting to, as well as the subscribers on the other end

    UnaryFunction<Data,void> *function;
};

/*****************************************************************************
** Interface [Void]
*****************************************************************************/

template<>
class SigSlot<Void> {
public:
    // typedef std::set<SigSlot<Void>*> Subscribers
    typedef Topic<Void>::Subscribers Subscribers;
    typedef std::map<std::string, const Subscribers*> PublicationMap;
    SigSlot() : processing_count(0), number_of_handles(1) {
        function = new BoundNullaryMemberFunction<SigSlot,void>(&SigSlot::emit,*this);
    }
    SigSlot(VoidFunction f) : processing_count(0), number_of_handles(1) {
        function = new NullaryFreeFunction<void>(f);
    }
    template<typename C>
    SigSlot(void (C::*f)(void), C &c) : processing_count(0), number_of_handles(1) {
        function = new BoundNullaryMemberFunction<C,void>(f,c);
    }

    ~SigSlot() {
        disconnect(); // stop any new processing from connected signals
        mutex.lock(); // acts like a barrier - holds up here if function still processing stuff.
        delete function;
    }

    const unsigned int& handles() const { return number_of_handles; }
    void incrHandles() { ++number_of_handles; }
    void decrHandles() { --number_of_handles; }
    void emit() {
        PublicationMap::const_iterator topic_iter;
        Subscribers::const_iterator slots_iter;
        for ( topic_iter = publications.begin(); topic_iter != publications.end(); ++topic_iter ) {
            const Subscribers* subscribers = topic_iter->second;
            for ( slots_iter = subscribers->begin(); slots_iter != subscribers->end(); ++slots_iter ) {
                SigSlot *sigslot = *slots_iter;
                sigslot->process();
            }
        }
    }
    void process(Void void_arg = Void()) {
        (void)void_arg;
        mutex.trylock(); // Only lock if its not already locked.
        ++processing_count;
        (*function)();
        if ( --processing_count == 0 ) {
            mutex.unlock();
        }
    }
    void connectSignal(const std::string& topic) {
        // Logic:
        //   - if already publishing to this topic
        //     - don't do anything
        //   - else
        //     - if topic doesn't exist
        //       - Manager will automatically create a new topic
        //     - Manager returns the subscribers handle
        //     - Topic name and subscribers handle are stored locally here in publications
        publications.insert( std::pair<std::string, const Subscribers*>(topic, SigSlotsManager<Void>::connectSignal(topic,this)) );
    }
    void connectSlot(const std::string& topic){
        std::pair< std::set<std::string>::iterator,bool > ret;
        ret = subscriptions.insert(topic); // Doesn't matter if it already exists.
        if ( ret.second ) {
            SigSlotsManager<Void>::connectSlot(topic,this);
        } // else { already subscribed to this topic }
    }
    void disconnect(const std::string &topic) {
        publications.erase(topic); // Doesn't matter if it finds it or not.
        SigSlotsManager<Void>::disconnect(topic,this);
    }
    void disconnect() {
        std::set<std::string>::iterator iter;
        for ( iter = subscriptions.begin(); iter != subscriptions.end(); ++iter ) {
            SigSlotsManager<Void>::disconnect(*iter, this);
        }
        subscriptions.clear();
        std::map<std::string,const Subscribers*>::iterator emit_iter;
        for ( emit_iter = publications.begin(); emit_iter != publications.end(); ++emit_iter ) {
            SigSlotsManager<Void>::disconnect(emit_iter->first, this);
        }
        publications.clear();
    }

private:
    Mutex mutex;
    unsigned int processing_count; // number of running process()'
    unsigned int number_of_handles; // number of handles to this sigslot (allows copying)
    std::set<std::string> subscriptions; // topics this sigslot is listening to
    PublicationMap publications; // topics this sigslot is posting to, as well as the subscribers on the other end

    NullaryFunction<void> *function;
};

} // namespace ecl

#endif /* ECL_SIGSLOTS_SIGSLOT_HPP_ */