APM:Libraries
Thread.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2016 Intel Corporation. All rights reserved.
3  *
4  * This file is free software: you can redistribute it and/or modify it
5  * under the terms of the GNU General Public License as published by the
6  * Free Software Foundation, either version 3 of the License, or
7  * (at your option) any later version.
8  *
9  * This file is distributed in the hope that it will be useful, but
10  * WITHOUT ANY WARRANTY; without even the implied warranty of
11  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
12  * See the GNU General Public License for more details.
13  *
14  * You should have received a copy of the GNU General Public License along
15  * with this program. If not, see <http://www.gnu.org/licenses/>.
16  */
17 #include "Thread.h"
18 
19 #include <alloca.h>
20 #include <sys/types.h>
21 #include <stdio.h>
22 #include <unistd.h>
23 #include <utility>
24 
25 #include <AP_HAL/AP_HAL.h>
26 #include <AP_Math/AP_Math.h>
27 
28 #include "Scheduler.h"
29 
30 #define STACK_POISON 0xBEBACAFE
31 
32 extern const AP_HAL::HAL &hal;
33 
34 namespace Linux {
35 
36 
37 void *Thread::_run_trampoline(void *arg)
38 {
39  Thread *thread = static_cast<Thread *>(arg);
40  thread->_poison_stack();
41  thread->_run();
42 
43  return nullptr;
44 }
45 
47 {
48  if (!_task) {
49  return false;
50  }
51 
52  _task();
53 
54  return true;
55 }
56 
57 /* Round up to the specified alignment.
58  *
59  * Let u be the address p rounded up to the alignment a. Then:
60  * u = p + a - 1 - r, where r = (p + a - 1) % a
61  *
62  * If p % a = 0, i.e. if p is already aligned, then:
63  * r = a - 1 ==> u = p
64  *
65  * Otherwise:
66  * r = p % a -1 ==> u = p + a - p % a
67  *
68  * p can be written p = q + p % a, where q is rounded down to the
69  * alignment a. Then u = q + a.
70  */
71 static inline void *align_to(void *p, size_t align)
72 {
73  return (void *)(((uintptr_t)p + align - 1) & ~(align - 1));
74 }
75 
77 {
78  pthread_attr_t attr;
79  size_t stack_size, guard_size;
80  void *stackp;
81  uint32_t *p, *curr, *begin, *end;
82 
83  if (pthread_getattr_np(_ctx, &attr) != 0 ||
84  pthread_attr_getstack(&attr, &stackp, &stack_size) != 0 ||
85  pthread_attr_getguardsize(&attr, &guard_size) != 0) {
86  return;
87  }
88 
89  stack_size /= sizeof(uint32_t);
90  guard_size /= sizeof(uint32_t);
91 
92  /* The stack either grows upward or downard. The guard part always
93  * protects the end */
94  end = (uint32_t *)stackp;
95  begin = end + stack_size;
96  curr = (uint32_t *)align_to(alloca(sizeof(uint32_t)), alignof(uint32_t));
97 
98  /* if curr is closer to @end, the stack actually grows from low to high
99  * virtual address: this is because this function should be executing very
100  * early in the thread's life and close to the thread creation, assuming
101  * the actual stack size is greater than the guard size and the stack
102  * until now is resonably small */
103  if (abs(curr - begin) > abs(curr - end)) {
104  std::swap(end, begin);
105  end -= guard_size;
106 
107  for (p = end; p > curr; p--) {
108  *p = STACK_POISON;
109  }
110  } else {
111  end += guard_size;
112 
113  /* we aligned curr to the up boundary, make sure this didn't cause us
114  * to lose some bytes */
115  curr--;
116 
117  for (p = end; p < curr; p++) {
118  *p = STACK_POISON;
119  }
120  }
121 
122  _stack_debug.start = begin;
123  _stack_debug.end = end;
124 }
125 
127 {
128  uint32_t *p;
129  size_t result = 0;
130 
131  /* Make sure we are tracking usage for this thread */
132  if (_stack_debug.start == 0 || _stack_debug.end == 0) {
133  return 0;
134  }
135 
137  for (p = _stack_debug.end; p > _stack_debug.start; p--) {
138  if (*p != STACK_POISON) {
139  break;
140  }
141  }
142  result = p - _stack_debug.start;
143  } else {
144  for (p = _stack_debug.end; p < _stack_debug.start; p++) {
145  if (*p != STACK_POISON) {
146  break;
147  }
148  }
149  result = _stack_debug.start - p;
150  }
151 
152  return result;
153 }
154 
155 bool Thread::start(const char *name, int policy, int prio)
156 {
157  if (_started) {
158  return false;
159  }
160 
161  struct sched_param param = { .sched_priority = prio };
162  pthread_attr_t attr;
163  int r;
164 
165  pthread_attr_init(&attr);
166 
167  /*
168  we need to run as root to get realtime scheduling. Allow it to
169  run as non-root for debugging purposes, plus to allow the Replay
170  tool to run
171  */
172  if (geteuid() == 0) {
173  if ((r = pthread_attr_setinheritsched(&attr, PTHREAD_EXPLICIT_SCHED)) != 0 ||
174  (r = pthread_attr_setschedpolicy(&attr, policy)) != 0 ||
175  (r = pthread_attr_setschedparam(&attr, &param)) != 0) {
176  AP_HAL::panic("Failed to set attributes for thread '%s': %s",
177  name, strerror(r));
178  }
179  }
180 
181  if (_stack_size) {
182  if (pthread_attr_setstacksize(&attr, _stack_size) != 0) {
183  return false;
184  }
185  }
186 
187  r = pthread_create(&_ctx, &attr, &Thread::_run_trampoline, this);
188  if (r != 0) {
189  AP_HAL::panic("Failed to create thread '%s': %s",
190  name, strerror(r));
191  }
192  pthread_attr_destroy(&attr);
193 
194  if (name) {
195  pthread_setname_np(_ctx, name);
196  }
197 
198  _started = true;
199 
200  return true;
201 }
202 
204 {
205  return pthread_equal(pthread_self(), _ctx);
206 }
207 
209 {
210  void *ret;
211 
212  if (_ctx == 0) {
213  return false;
214  }
215 
216  if (pthread_join(_ctx, &ret) != 0 ||
217  (intptr_t)ret != 0) {
218  return false;
219  }
220 
221  return true;
222 }
223 
224 
225 bool PeriodicThread::set_rate(uint32_t rate_hz)
226 {
227  if (_started || rate_hz == 0) {
228  return false;
229  }
230 
231  _period_usec = hz_to_usec(rate_hz);
232 
233  return true;
234 }
235 
236 bool Thread::set_stack_size(size_t stack_size)
237 {
238  if (_started) {
239  return false;
240  }
241 
242  _stack_size = stack_size;
243 
244  return true;
245 }
246 
248 {
249  if (_period_usec == 0) {
250  return false;
251  }
252 
253  uint64_t next_run_usec = AP_HAL::micros64() + _period_usec;
254 
255  while (!_should_exit) {
256  uint64_t dt = next_run_usec - AP_HAL::micros64();
257  if (dt > _period_usec) {
258  // we've lost sync - restart
259  next_run_usec = AP_HAL::micros64();
260  } else {
262  }
263  next_run_usec += _period_usec;
264 
265  _task();
266  }
267 
268  _started = false;
269  _should_exit = false;
270 
271  return true;
272 }
273 
275 {
276  if (!is_started()) {
277  return false;
278  }
279 
280  _should_exit = true;
281 
282  return true;
283 }
284 
285 }
bool join()
Definition: Thread.cpp:208
void microsleep(uint32_t usec)
Definition: Scheduler.cpp:135
task_t _task
Definition: Thread.h:64
bool _started
Definition: Thread.h:65
char * strerror(int errnum)
POSIX strerror() - convert POSIX errno to text with user message.
Definition: posix.c:1852
static Scheduler * from(AP_HAL::Scheduler *scheduler)
Definition: Scheduler.h:23
static void swap(float &a, float &b)
Definition: matrix_alg.cpp:57
#define STACK_POISON
Definition: Thread.cpp:30
virtual bool _run()
Definition: Thread.cpp:46
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
Definition: AC_PID_test.cpp:14
const char * result
Definition: Printf.cpp:16
const char * name
Definition: BusTest.cpp:11
bool _run() override
Definition: Thread.cpp:247
bool is_started() const
Definition: Thread.h:42
void _poison_stack()
Definition: Thread.cpp:76
struct Linux::Thread::stack_debug _stack_debug
size_t _stack_size
Definition: Thread.h:74
bool set_rate(uint32_t rate_hz)
Definition: Thread.cpp:225
uint64_t micros64()
Definition: system.cpp:162
static void * align_to(void *p, size_t align)
Definition: Thread.cpp:71
static void * _run_trampoline(void *arg)
Definition: Thread.cpp:37
bool stop() override
Definition: Thread.cpp:274
bool is_current_thread()
Definition: Thread.cpp:203
bool set_stack_size(size_t stack_size)
Definition: Thread.cpp:236
size_t get_stack_usage()
Definition: Thread.cpp:126
bool start(const char *name, int policy, int prio)
Definition: Thread.cpp:155
bool _should_exit
Definition: Thread.h:66
void panic(const char *errormsg,...) FMT_PRINTF(1
Definition: system.cpp:140
uint32_t hz_to_usec(uint32_t freq)
Definition: AP_Math.h:227
AP_HAL::Scheduler * scheduler
Definition: HAL.h:114
pthread_t _ctx
Definition: Thread.h:67