Program Listing for File thread_win.hpp

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

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

#ifndef ECL_THREADS_THREAD_WIN_HPP_
#define ECL_THREADS_THREAD_WIN_HPP_

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

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

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

#include <windows.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_win.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 unsigned int EntryPoint(void *ptr_this) {
        ThreadTask< F, false > *ptr = static_cast< ThreadTask< F, false > * >(ptr_this);
        (ptr->function)();
        return 0;
    }

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 unsigned int EntryPoint(void *ptr_this) {
        ThreadTask< F, true > *ptr = static_cast< ThreadTask< F, true > * >(ptr_this);
        (ptr->function)();
        return 0;
    }

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

}; // namespace threads

/*****************************************************************************
** Interface [Thread]
*****************************************************************************/
class ecl_threads_PUBLIC Thread {
public:
    Thread() :
        thread_handle(NULL),
        thread_task(NULL),
        has_started(false),
        join_requested(false)
    {}
    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() { if ( thread_task == NULL ) { return false; } else { return true; } }

    void cancel();

    void join();


private:
    HANDLE thread_handle;
    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_handle(NULL),
    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_handle(NULL),
    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)
{
    // stack_size is ignored

    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;
    }

    thread_task = new threads::ThreadTask< BoundNullaryMemberFunction<C,void> >(generateFunctionObject( function, c ), priority);

    DWORD threadid;

    thread_handle = CreateThread(NULL,
        0,
        (LPTHREAD_START_ROUTINE)threads::ThreadTask< BoundNullaryMemberFunction<C,void> >::EntryPoint,
        thread_task,
        0,
        &threadid);

    if (!thread_handle) {
        ecl_debug_throw(StandardException(LOC, UnknownError, "Failed to create thread."));
        return Error(UnknownError);
    }

    BOOL bResult = FALSE;

    if (priority >= RealTimePriority1) {
        bResult = SetThreadPriority(thread_handle, THREAD_PRIORITY_TIME_CRITICAL);
    }

    switch (priority) {
        case CriticalPriority:
            bResult = SetThreadPriority(thread_handle, HIGH_PRIORITY_CLASS);
            break;
        case HighPriority:
            bResult = SetThreadPriority(thread_handle, THREAD_PRIORITY_ABOVE_NORMAL);
            break;
        case LowPriority:
            bResult = SetThreadPriority(thread_handle, THREAD_PRIORITY_BELOW_NORMAL);
            break;
        case BackgroundPriority:
            bResult = SetThreadPriority(thread_handle, THREAD_PRIORITY_IDLE);
            break;
        default:
            break;
    }

    if (!bResult) {
        ecl_debug_throw(threads::throwPriorityException(LOC));
    }

    return Error(NoError);
}

template <typename F>
Error Thread::start(const F &function, const Priority &priority, const long &stack_size)
{
    // stack_size is ignored

    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;
    }

    thread_task = new threads::ThreadTask<F, is_reference_wrapper<F>::value >(function, priority);

    DWORD threadid;

    thread_handle = CreateThread(NULL,
        0,
        (LPTHREAD_START_ROUTINE)threads::ThreadTask<F, is_reference_wrapper<F>::value >::EntryPoint,
        thread_task,
        0,
        &threadid);

    if (!thread_handle) {
        ecl_debug_throw(StandardException(LOC, UnknownError, "Failed to create thread."));
        return Error(UnknownError);
    }

    BOOL bResult = FALSE;

    if (priority >= RealTimePriority1) {
        bResult = SetThreadPriority(thread_handle, THREAD_PRIORITY_TIME_CRITICAL);
    }

    switch (priority) {
        case CriticalPriority:
            bResult = SetThreadPriority(thread_handle, HIGH_PRIORITY_CLASS);
            break;
        case HighPriority:
            bResult = SetThreadPriority(thread_handle, THREAD_PRIORITY_ABOVE_NORMAL);
            break;
        case LowPriority:
            bResult = SetThreadPriority(thread_handle, THREAD_PRIORITY_BELOW_NORMAL);
            break;
        case BackgroundPriority:
            bResult = SetThreadPriority(thread_handle, THREAD_PRIORITY_IDLE);
            break;
        default:
            break;
    }

    if (!bResult) {
        ecl_debug_throw(threads::throwPriorityException(LOC));
    }

    return Error(NoError);
}

} // namespace ecl

#endif /* ECL_IS_WIN32 */
#endif /* ECL_THREADS_THREAD_WIN_HPP_ */