thread_pos.hpp
Go to the documentation of this file.
00001 
00008 /*****************************************************************************
00009 ** Ifdefs
00010 *****************************************************************************/
00011 
00012 #ifndef ECL_THREADS_THREAD_POS_HPP_
00013 #define ECL_THREADS_THREAD_POS_HPP_
00014 
00015 /*****************************************************************************
00016 ** Platform Check
00017 *****************************************************************************/
00018 
00019 #include <ecl/config/ecl.hpp>
00020 #if defined(ECL_IS_POSIX)
00021 
00022 /*****************************************************************************
00023 ** Includes
00024 *****************************************************************************/
00025 
00026 #include <pthread.h>
00027 #include "thread_exceptions_pos.hpp"
00028 #include <ecl/config/macros.hpp>
00029 #include <ecl/concepts/nullary_function.hpp>
00030 #include <ecl/exceptions/standard_exception.hpp>
00031 #include <ecl/utilities/void.hpp>
00032 #include <ecl/utilities/function_objects.hpp>
00033 #include "priority_pos.hpp"
00034 
00035 /*****************************************************************************
00036 ** Namespaces
00037 *****************************************************************************/
00038 
00039 namespace ecl {
00040 namespace threads {
00041 
00042 /*****************************************************************************
00043 ** Interface [ThreadTask]
00044 *****************************************************************************/
00051 class ECL_LOCAL ThreadTaskBase {
00052 public:
00053         virtual ~ThreadTaskBase() {};
00054 
00055 protected:
00056         ThreadTaskBase(const Priority& priority) : priority_level(priority) {}; 
00057         ecl::Priority priority_level;
00058 };
00068 template <typename F, bool IsReferenceWrapper = false>
00069 class ECL_LOCAL ThreadTask : public ThreadTaskBase {
00070 public:
00079         ThreadTask(const F &f, const Priority &priority) : ThreadTaskBase(priority), function(f) {
00080                 ecl_compile_time_concept_check(ecl::NullaryFunction<F>);
00081         };
00082         virtual ~ThreadTask() {}; 
00094         static void* EntryPoint(void *ptr_this) {
00095             ThreadTask< F, false > *ptr = static_cast< ThreadTask< F, false > * >(ptr_this);
00096             ecl::set_priority(ptr->priority_level);
00097             (ptr->function)();
00098             delete ptr;
00099             ptr_this = NULL;
00100             return ptr_this;
00101         }
00102 
00103 private:
00104         F function;
00105 };
00106 
00116 template <typename F>
00117 class ECL_LOCAL ThreadTask<F, true> : public ThreadTaskBase {
00118 public:
00127         ThreadTask(const F &f, const Priority &priority) : ThreadTaskBase(priority), function(f.reference()) {
00128                 ecl_compile_time_concept_check(ecl::NullaryFunction< typename F::type>);
00129         };
00130         virtual ~ThreadTask() {}; 
00142         static void* EntryPoint(void *ptr_this) {
00143             ThreadTask< F, true > *ptr = static_cast< ThreadTask< F, true > * >(ptr_this);
00144             ecl::set_priority(ptr->priority_level);
00145             (ptr->function)();
00146             delete ptr;
00147             ptr_this = NULL;
00148             return ptr_this;
00149         }
00150 
00151 private:
00152         typename F::type &function;
00153 };
00154 
00155 }; // namespace threads
00156 
00157 /*****************************************************************************
00158 ** Interface [Thread]
00159 *****************************************************************************/
00233 class ECL_PUBLIC Thread {
00234 public:
00242         Thread() :
00243                 thread_task(NULL),
00244                 has_started(false),
00245                 join_requested(false)
00246         {}
00266         Thread(VoidFunction function, const Priority &priority = DefaultPriority, const long &stack_size = -1 ) ecl_debug_throw_decl(StandardException);
00276         Error start(VoidFunction function, const Priority &priority = DefaultPriority, const long &stack_size = -1 ) ecl_debug_throw_decl(StandardException);
00300         template <typename C>
00301         Thread(void (C::*function)(), C &c, const Priority &priority = DefaultPriority,  const long &stack_size = -1 ) ecl_debug_throw_decl(StandardException);
00312         template <typename C>
00313         Error start(void (C::*function)(), C &c, const Priority &priority = DefaultPriority,  const long &stack_size = -1 ) ecl_debug_throw_decl(StandardException);
00314 
00353         template <typename F>
00354         Thread(const F &function, const Priority &priority = DefaultPriority,  const long &stack_size = -1 ) ecl_debug_throw_decl(StandardException);
00364         template <typename F>
00365         Error start(const F &function, const Priority &priority = DefaultPriority,  const long &stack_size = -1 ) ecl_debug_throw_decl(StandardException);
00366 
00375         virtual ~Thread();
00376 
00382         bool isRunning() { if ( thread_task == NULL ) { return false; } else { return true; } }
00383 
00402         void cancel() ecl_debug_throw_decl(StandardException);
00403 
00411         void join() ecl_assert_throw_decl(StandardException);
00412 
00413 
00414 private:
00415         pthread_t thread_handle;
00416     pthread_attr_t attrs;
00417     sched_param schedule_parameters;
00418     threads::ThreadTaskBase *thread_task;
00419     bool has_started;
00420     bool join_requested;
00421 
00422         void initialise(const long &stack_size) ecl_assert_throw_decl(StandardException);
00423 
00424         enum ThreadProperties {
00425                 DefaultStackSize = -1
00426         };
00427 };
00428 
00429 /*****************************************************************************
00430 ** Template Implementation [Thread]
00431 *****************************************************************************/
00432 
00433 template <typename C>
00434 Thread::Thread(void (C::*function)(), C &c, const Priority &priority, const long &stack_size) ecl_debug_throw_decl(StandardException) :
00435         thread_task(NULL),
00436         has_started(false),
00437         join_requested(false)
00438 {
00439         start<C>(function, c, priority, stack_size);
00440 
00441 }
00442 
00443 template <typename F>
00444 Thread::Thread(const F &function, const Priority &priority, const long &stack_size) ecl_debug_throw_decl(StandardException) :
00445         thread_task(NULL),
00446         has_started(false),
00447         join_requested(false)
00448 {
00449         start<F>(function, priority, stack_size);
00450 }
00451 
00452 template <typename C>
00453 Error Thread::start(void (C::*function)(), C &c, const Priority &priority, const long &stack_size) ecl_debug_throw_decl(StandardException)
00454 {
00455         if ( has_started ) {
00456                 ecl_debug_throw(StandardException(LOC,BusyError,"The thread has already been started."));
00457                 return Error(BusyError); // if in release mode, gracefully fall back to return values.
00458         } else {
00459                 has_started = true;
00460         }
00461         initialise(stack_size);
00462         thread_task = new threads::ThreadTask< BoundNullaryMemberFunction<C,void> >(generateFunctionObject( function, c ), priority);
00463     int result = pthread_create(&(this->thread_handle), &(this->attrs), threads::ThreadTask< BoundNullaryMemberFunction<C,void> >::EntryPoint, thread_task);
00464         pthread_attr_destroy(&attrs);
00465     if ( result != 0 ) {
00466         delete thread_task;
00467         thread_task = NULL;
00468         ecl_debug_throw(threads::throwPthreadCreateException(LOC,result));
00469                 return threads::handlePthreadCreateError(result); // if in release mode, gracefully fall back to return values.
00470     }
00471     return Error(NoError);
00472 }
00473 
00474 template <typename F>
00475 Error Thread::start(const F &function, const Priority &priority, const long &stack_size) ecl_debug_throw_decl(StandardException)
00476 {
00477         if ( has_started ) {
00478                 ecl_debug_throw(StandardException(LOC,BusyError,"The thread has already been started."));
00479                 return Error(BusyError); // if in release mode, gracefully fall back to return values.
00480         } else {
00481                 has_started = true;
00482         }
00483         initialise(stack_size);
00484         thread_task = new threads::ThreadTask<F, is_reference_wrapper<F>::value >(function, priority);
00485     int result = pthread_create(&(this->thread_handle), &(this->attrs), threads::ThreadTask<F, is_reference_wrapper<F>::value>::EntryPoint, thread_task);
00486         pthread_attr_destroy(&attrs);
00487     if ( result != 0 ) {
00488         delete thread_task;
00489         thread_task = NULL;
00490         ecl_debug_throw(threads::throwPthreadCreateException(LOC,result));
00491                 return threads::handlePthreadCreateError(result); // if in release mode, gracefully fall back to return values.
00492     }
00493     return Error(NoError);
00494 }
00495 
00496 }; // namespace ecl
00497 
00498 #endif /* ECL_IS_POSIX */
00499 #endif /* ECL_THREADS_THREAD_POS_HPP_ */


ecl_threads
Author(s): Daniel Stonier
autogenerated on Sun Oct 5 2014 23:35:37