Program Listing for File thread_pos.hpp

Return to documentation for file (/tmp/ws/src/ecl_core/ecl_threads/include/ecl/threads/thread_pos.hpp)

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

#ifndef ECL_THREADS_THREAD_POS_HPP_
#define ECL_THREADS_THREAD_POS_HPP_

/*****************************************************************************
** Platform Check
*****************************************************************************/

#include <ecl/config/ecl.hpp>
#if defined(ECL_IS_POSIX)

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

#include <pthread.h>
#include "thread_exceptions_pos.hpp"
#include <ecl/config/macros.hpp>
#include <ecl/concepts/nullary_function.hpp>
#include <ecl/exceptions/standard_exception.hpp>
#include <ecl/utilities/void.hpp>
#include <ecl/utilities/function_objects.hpp>
#include "priority_pos.hpp"

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

namespace ecl {
namespace threads {

/*****************************************************************************
** Interface [ThreadTask]
*****************************************************************************/
class ECL_LOCAL ThreadTaskBase {
public:
    virtual ~ThreadTaskBase() {};

protected:
    ThreadTaskBase(const Priority& priority) : priority_level(priority) {};
    ecl::Priority priority_level;
};
template <typename F, bool IsReferenceWrapper = false>
class ECL_LOCAL ThreadTask : public ThreadTaskBase {
public:
    ThreadTask(const F &f, const Priority &priority) : ThreadTaskBase(priority), function(f) {
        ecl_compile_time_concept_check(ecl::NullaryFunction<F>);
    };
    virtual ~ThreadTask() {};
    static void* EntryPoint(void *ptr_this) {
        ThreadTask< F, false > *ptr = static_cast< ThreadTask< F, false > * >(ptr_this);
        ecl::set_priority(ptr->priority_level);
        (ptr->function)();
        delete ptr;
        ptr_this = NULL;
        return ptr_this;
    }

private:
    F function;
};

template <typename F>
class ECL_LOCAL ThreadTask<F, true> : public ThreadTaskBase {
public:
    ThreadTask(const F &f, const Priority &priority) : ThreadTaskBase(priority), function(f.reference()) {
        ecl_compile_time_concept_check(ecl::NullaryFunction< typename F::type>);
    };
    virtual ~ThreadTask() {};
    static void* EntryPoint(void *ptr_this) {
        ThreadTask< F, true > *ptr = static_cast< ThreadTask< F, true > * >(ptr_this);
        ecl::set_priority(ptr->priority_level);
        (ptr->function)();
        delete ptr;
        ptr_this = NULL;
        return ptr_this;
    }

private:
    typename F::type &function;
};

} // namespace threads

/*****************************************************************************
** Interface [Thread]
*****************************************************************************/
class ECL_PUBLIC Thread {
public:
    Thread() :
        thread_task(NULL),
        has_started(false),
        join_requested(false)
    {
        (void) schedule_parameters;
    }
    Thread(VoidFunction function, const Priority &priority = DefaultPriority, const long &stack_size = -1 );
    Error start(VoidFunction function, const Priority &priority = DefaultPriority, const long &stack_size = -1 );
    template <typename C>
    Thread(void (C::*function)(), C &c, const Priority &priority = DefaultPriority,  const long &stack_size = -1 );
    template <typename C>
    Error start(void (C::*function)(), C &c, const Priority &priority = DefaultPriority,  const long &stack_size = -1 );

    template <typename F>
    Thread(const F &function, const Priority &priority = DefaultPriority,  const long &stack_size = -1 );
    template <typename F>
    Error start(const F &function, const Priority &priority = DefaultPriority,  const long &stack_size = -1 );

    virtual ~Thread();

    bool isRunning() const { if ( thread_task == NULL ) { return false; } else { return true; } }

    void cancel();

    void join();


private:
    pthread_t thread_handle;
    pthread_attr_t attrs;
    sched_param schedule_parameters;
    threads::ThreadTaskBase *thread_task;
    bool has_started;
    bool join_requested;

    void initialise(const long &stack_size);

    enum ThreadProperties {
        DefaultStackSize = -1
    };
};

/*****************************************************************************
** Template Implementation [Thread]
*****************************************************************************/

template <typename C>
Thread::Thread(void (C::*function)(), C &c, const Priority &priority, const long &stack_size) :
    thread_task(NULL),
    has_started(false),
    join_requested(false)
{
    start<C>(function, c, priority, stack_size);

}

template <typename F>
Thread::Thread(const F &function, const Priority &priority, const long &stack_size) :
    thread_task(NULL),
    has_started(false),
    join_requested(false)
{
    start<F>(function, priority, stack_size);
}

template <typename C>
Error Thread::start(void (C::*function)(), C &c, const Priority &priority, const long &stack_size)
{
    if ( has_started ) {
        ecl_debug_throw(StandardException(LOC,BusyError,"The thread has already been started."));
        return Error(BusyError); // if in release mode, gracefully fall back to return values.
    } else {
        has_started = true;
    }
    initialise(stack_size);
    thread_task = new threads::ThreadTask< BoundNullaryMemberFunction<C,void> >(generateFunctionObject( function, c ), priority);
    int result = pthread_create(&(this->thread_handle), &(this->attrs), threads::ThreadTask< BoundNullaryMemberFunction<C,void> >::EntryPoint, thread_task);
    pthread_attr_destroy(&attrs);
    if ( result != 0 ) {
        delete thread_task;
        thread_task = NULL;
        ecl_debug_throw(threads::throwPthreadCreateException(LOC,result));
        return threads::handlePthreadCreateError(result); // if in release mode, gracefully fall back to return values.
    }
    return Error(NoError);
}

template <typename F>
Error Thread::start(const F &function, const Priority &priority, const long &stack_size)
{
    if ( has_started ) {
        ecl_debug_throw(StandardException(LOC,BusyError,"The thread has already been started."));
        return Error(BusyError); // if in release mode, gracefully fall back to return values.
    } else {
        has_started = true;
    }
    initialise(stack_size);
    thread_task = new threads::ThreadTask<F, is_reference_wrapper<F>::value >(function, priority);
    int result = pthread_create(&(this->thread_handle), &(this->attrs), threads::ThreadTask<F, is_reference_wrapper<F>::value>::EntryPoint, thread_task);
    pthread_attr_destroy(&attrs);
    if ( result != 0 ) {
        delete thread_task;
        thread_task = NULL;
        ecl_debug_throw(threads::throwPthreadCreateException(LOC,result));
        return threads::handlePthreadCreateError(result); // if in release mode, gracefully fall back to return values.
    }
    return Error(NoError);
}

} // namespace ecl

#endif /* ECL_IS_POSIX */
#endif /* ECL_THREADS_THREAD_POS_HPP_ */