EEROS  1.0.0.0
API for the EEROS Real-Time Robotics Framework
Async.hpp
Go to the documentation of this file.
1 #ifndef ORG_EEROS_TASK_ASYNC_HPP_
2 #define ORG_EEROS_TASK_ASYNC_HPP_
3 
4 #include <thread>
5 
9 
10 namespace eeros {
11  namespace task {
12 
13  class Async : public Runnable
14  {
15  public:
16  Async(Runnable &task, bool realtime = false, int nice = 0);
17  Async(Runnable *task, bool realtime = false, int nice = 0);
18  virtual ~Async();
19  virtual void run();
20  void stop();
21  void join();
22 
24 
25  private:
26  void run_thread();
27  Runnable &task;
28  bool realtime;
29  int nice;
30  Semaphore semaphore;
31  std::thread thread;
32  bool finished;
33  };
34 
35  }
36 }
37 
38 #endif // ORG_EEROS_TASK_ASYNC_HPP_
Definition: PeriodicCounter.hpp:14
Definition: Semaphore.hpp:10
Definition: Config.hpp:14
virtual void run()
Definition: Async.cpp:34
Definition: Runnable.hpp:6
PeriodicCounter counter
Definition: Async.hpp:23
virtual ~Async()
Definition: Async.cpp:29
void stop()
Definition: Async.cpp:38
Async(Runnable &task, bool realtime=false, int nice=0)
Definition: Async.cpp:23
void join()
Definition: Async.cpp:43
Definition: Async.hpp:13