YARP
Yet Another Robot Platform
Thread.cpp
Go to the documentation of this file.
1 /*
2  * SPDX-FileCopyrightText: 2006-2021 Istituto Italiano di Tecnologia (IIT)
3  * SPDX-FileCopyrightText: 2006-2010 RobotCub Consortium
4  * SPDX-License-Identifier: BSD-3-Clause
5  */
6 
7 #include <yarp/os/Thread.h>
8 
10 
11 using namespace yarp::os::impl;
12 using namespace yarp::os;
13 
15 {
16 private:
17  Thread& owner;
18 
19 public:
20  explicit Private(Thread& owner) :
21  owner(owner),
22  stopping(false)
23  {
24  }
25 
26  ~Private() override = default;
27 
28  void beforeStart() override
29  {
30  owner.beforeStart();
31  }
32 
33  void afterStart(bool success) override
34  {
35  owner.afterStart(success);
36  }
37 
38  void run() override
39  {
40  owner.run();
41  }
42 
43  void close() override
44  {
45  if (isRunning()) {
46  owner.onStop();
47  }
49  }
50 
51  bool threadInit() override
52  {
53  return owner.threadInit();
54  }
55 
56  void threadRelease() override
57  {
58  owner.threadRelease();
59  }
60 
61  bool stopping;
62 };
63 
64 
66  mPriv(new Private(*this))
67 {
68 }
69 
71 {
72  mPriv->close();
73  delete mPriv;
74 }
75 
76 bool Thread::join(double seconds)
77 {
78  return mPriv->join(seconds) == 0;
79 }
80 
82 {
83  mPriv->stopping = true;
84  mPriv->close();
85  return true;
86 }
87 
89 {
90  // by default this does nothing
91 }
92 
94 {
95  mPriv->stopping = false;
96  return mPriv->start();
97 }
98 
100 {
101  //return mPriv->isClosing();
102  return mPriv->stopping;
103 }
104 
106 {
107  return mPriv->isRunning();
108 }
109 
111 {
112 }
113 
114 void Thread::afterStart(bool success)
115 {
116  YARP_UNUSED(success);
117 }
118 
120 {
121  return ThreadImpl::getCount();
122 }
123 
124 // get a unique key
125 long int Thread::getKey()
126 {
127  return mPriv->getKey();
128 }
129 
131 {
132  return ThreadImpl::getKeyOfCaller();
133 }
134 
135 int Thread::setPriority(int priority, int policy)
136 {
137  return mPriv->setPriority(priority, policy);
138 }
139 
141 {
142  return mPriv->getPriority();
143 }
144 
146 {
147  return mPriv->getPolicy();
148 }
149 
151 {
153 }
void close() override
Definition: Thread.cpp:43
void beforeStart() override
Definition: Thread.cpp:28
void threadRelease() override
Definition: Thread.cpp:56
void afterStart(bool success) override
Definition: Thread.cpp:33
void run() override
Definition: Thread.cpp:38
Private(Thread &owner)
Definition: Thread.cpp:20
~Private() override=default
bool threadInit() override
Definition: Thread.cpp:51
An abstraction for a thread of execution.
Definition: Thread.h:22
virtual void threadRelease()
Release method.
Definition: Thread.h:116
virtual bool threadInit()
Initialization method.
Definition: Thread.h:105
static long int getKeyOfCaller()
Get a unique identifier for the calling thread.
Definition: Thread.cpp:130
virtual ~Thread()
Destructor.
Definition: Thread.cpp:70
bool stop()
Stop the thread.
Definition: Thread.cpp:81
virtual void onStop()
Call-back, called while halting the thread (before join).
Definition: Thread.cpp:88
static void yield()
Reschedule the execution of current thread, allowing other threads to run.
Definition: Thread.cpp:150
static int getCount()
Check how many threads are running.
Definition: Thread.cpp:119
bool join(double seconds=-1)
The function returns when the thread execution has completed.
Definition: Thread.cpp:76
virtual void beforeStart()
Called just before a new thread starts.
Definition: Thread.cpp:110
Thread()
Constructor.
Definition: Thread.cpp:65
bool isStopping()
Returns true if the thread is stopping (Thread::stop has been called).
Definition: Thread.cpp:99
int getPolicy()
Query the current scheduling policy of the thread, if the OS supports that.
Definition: Thread.cpp:145
bool isRunning()
Returns true if the thread is running (Thread::start has been called successfully and the thread has ...
Definition: Thread.cpp:105
long int getKey()
Get a unique identifier for the thread.
Definition: Thread.cpp:125
bool start()
Start the new thread running.
Definition: Thread.cpp:93
int setPriority(int priority, int policy=-1)
Set the priority and scheduling policy of the thread, if the OS supports that.
Definition: Thread.cpp:135
virtual void afterStart(bool success)
Called just after a new thread starts (or fails to start), this is executed by the same thread that c...
Definition: Thread.cpp:114
int getPriority()
Query the current priority of the thread, if the OS supports that.
Definition: Thread.cpp:140
virtual void run()=0
Main body of the new thread.
An abstraction for a thread of execution.
Definition: ThreadImpl.h:23
void yield()
The calling thread releases its remaining quantum upon calling this function.
Definition: Time.cpp:138
The components from which ports and connections are built.
An interface to the operating system, including Port based communication.
#define YARP_UNUSED(var)
Definition: api.h:162