2016-02-02 18:01:57 -04:00
|
|
|
/*
|
|
|
|
* Copyright (C) 2016 Intel Corporation. All rights reserved.
|
|
|
|
*
|
|
|
|
* This file is free software: you can redistribute it and/or modify it
|
|
|
|
* under the terms of the GNU General Public License as published by the
|
|
|
|
* Free Software Foundation, either version 3 of the License, or
|
|
|
|
* (at your option) any later version.
|
|
|
|
*
|
|
|
|
* This file is distributed in the hope that it will be useful, but
|
|
|
|
* WITHOUT ANY WARRANTY; without even the implied warranty of
|
|
|
|
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
|
|
|
|
* See the GNU General Public License for more details.
|
|
|
|
*
|
|
|
|
* You should have received a copy of the GNU General Public License along
|
|
|
|
* with this program. If not, see <http://www.gnu.org/licenses/>.
|
|
|
|
*/
|
|
|
|
#include "Thread.h"
|
|
|
|
|
2016-04-23 02:00:33 -03:00
|
|
|
#include <alloca.h>
|
2018-09-06 12:23:14 -03:00
|
|
|
#include <limits.h>
|
2016-02-02 18:01:57 -04:00
|
|
|
#include <sys/types.h>
|
2016-04-23 02:00:33 -03:00
|
|
|
#include <stdio.h>
|
2016-02-02 18:01:57 -04:00
|
|
|
#include <unistd.h>
|
2016-04-23 02:00:33 -03:00
|
|
|
#include <utility>
|
2016-02-02 18:01:57 -04:00
|
|
|
|
|
|
|
#include <AP_HAL/AP_HAL.h>
|
|
|
|
#include <AP_Math/AP_Math.h>
|
|
|
|
#include "Scheduler.h"
|
|
|
|
|
2016-04-23 02:00:33 -03:00
|
|
|
#define STACK_POISON 0xBEBACAFE
|
|
|
|
|
2016-02-02 18:01:57 -04:00
|
|
|
extern const AP_HAL::HAL &hal;
|
|
|
|
|
|
|
|
namespace Linux {
|
|
|
|
|
|
|
|
|
|
|
|
void *Thread::_run_trampoline(void *arg)
|
|
|
|
{
|
|
|
|
Thread *thread = static_cast<Thread *>(arg);
|
2016-04-23 02:00:33 -03:00
|
|
|
thread->_poison_stack();
|
2016-02-02 19:08:26 -04:00
|
|
|
thread->_run();
|
2016-02-02 18:01:57 -04:00
|
|
|
|
2018-07-10 19:07:00 -03:00
|
|
|
if (thread->_auto_free) {
|
|
|
|
delete thread;
|
|
|
|
}
|
|
|
|
|
2016-02-02 18:01:57 -04:00
|
|
|
return nullptr;
|
|
|
|
}
|
|
|
|
|
2016-02-02 19:08:26 -04:00
|
|
|
bool Thread::_run()
|
|
|
|
{
|
|
|
|
if (!_task) {
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
|
|
|
|
_task();
|
|
|
|
|
|
|
|
return true;
|
|
|
|
}
|
|
|
|
|
2016-05-20 15:46:05 -03:00
|
|
|
/* Round up to the specified alignment.
|
|
|
|
*
|
|
|
|
* Let u be the address p rounded up to the alignment a. Then:
|
|
|
|
* u = p + a - 1 - r, where r = (p + a - 1) % a
|
|
|
|
*
|
|
|
|
* If p % a = 0, i.e. if p is already aligned, then:
|
|
|
|
* r = a - 1 ==> u = p
|
|
|
|
*
|
|
|
|
* Otherwise:
|
|
|
|
* r = p % a -1 ==> u = p + a - p % a
|
|
|
|
*
|
|
|
|
* p can be written p = q + p % a, where q is rounded down to the
|
|
|
|
* alignment a. Then u = q + a.
|
|
|
|
*/
|
2016-05-19 12:36:11 -03:00
|
|
|
static inline void *align_to(void *p, size_t align)
|
|
|
|
{
|
|
|
|
return (void *)(((uintptr_t)p + align - 1) & ~(align - 1));
|
|
|
|
}
|
|
|
|
|
2016-04-23 02:00:33 -03:00
|
|
|
void Thread::_poison_stack()
|
|
|
|
{
|
|
|
|
pthread_attr_t attr;
|
|
|
|
size_t stack_size, guard_size;
|
|
|
|
void *stackp;
|
2016-05-19 12:18:28 -03:00
|
|
|
uint32_t *p, *curr, *begin, *end;
|
2016-04-23 02:00:33 -03:00
|
|
|
|
2020-07-06 12:26:15 -03:00
|
|
|
// `pthread_self` should be used here since _ctx could be not initialized
|
|
|
|
// in a race condition.
|
|
|
|
if (pthread_getattr_np(pthread_self(), &attr) != 0 ||
|
2016-04-23 02:00:33 -03:00
|
|
|
pthread_attr_getstack(&attr, &stackp, &stack_size) != 0 ||
|
|
|
|
pthread_attr_getguardsize(&attr, &guard_size) != 0) {
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
2016-05-19 12:18:28 -03:00
|
|
|
stack_size /= sizeof(uint32_t);
|
|
|
|
guard_size /= sizeof(uint32_t);
|
|
|
|
|
2016-04-23 02:00:33 -03:00
|
|
|
/* The stack either grows upward or downard. The guard part always
|
|
|
|
* protects the end */
|
2016-05-19 12:18:28 -03:00
|
|
|
end = (uint32_t *)stackp;
|
2016-05-19 12:07:56 -03:00
|
|
|
begin = end + stack_size;
|
2016-05-19 12:36:11 -03:00
|
|
|
curr = (uint32_t *)align_to(alloca(sizeof(uint32_t)), alignof(uint32_t));
|
2016-04-23 02:00:33 -03:00
|
|
|
|
|
|
|
/* if curr is closer to @end, the stack actually grows from low to high
|
|
|
|
* virtual address: this is because this function should be executing very
|
|
|
|
* early in the thread's life and close to the thread creation, assuming
|
|
|
|
* the actual stack size is greater than the guard size and the stack
|
|
|
|
* until now is resonably small */
|
2016-05-19 12:07:56 -03:00
|
|
|
if (abs(curr - begin) > abs(curr - end)) {
|
|
|
|
std::swap(end, begin);
|
2016-04-23 02:00:33 -03:00
|
|
|
end -= guard_size;
|
|
|
|
|
2016-05-19 12:18:28 -03:00
|
|
|
for (p = end; p > curr; p--) {
|
2016-04-23 02:00:33 -03:00
|
|
|
*p = STACK_POISON;
|
|
|
|
}
|
|
|
|
} else {
|
|
|
|
end += guard_size;
|
|
|
|
|
2016-05-19 12:36:11 -03:00
|
|
|
/* we aligned curr to the up boundary, make sure this didn't cause us
|
|
|
|
* to lose some bytes */
|
|
|
|
curr--;
|
|
|
|
|
2016-05-19 12:18:28 -03:00
|
|
|
for (p = end; p < curr; p++) {
|
2016-04-23 02:00:33 -03:00
|
|
|
*p = STACK_POISON;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
2016-05-19 12:18:28 -03:00
|
|
|
_stack_debug.start = begin;
|
|
|
|
_stack_debug.end = end;
|
2016-04-23 02:00:33 -03:00
|
|
|
}
|
|
|
|
|
|
|
|
size_t Thread::get_stack_usage()
|
|
|
|
{
|
|
|
|
uint32_t *p;
|
|
|
|
size_t result = 0;
|
|
|
|
|
|
|
|
/* Make sure we are tracking usage for this thread */
|
|
|
|
if (_stack_debug.start == 0 || _stack_debug.end == 0) {
|
|
|
|
return 0;
|
|
|
|
}
|
|
|
|
|
|
|
|
if (_stack_debug.start < _stack_debug.end) {
|
|
|
|
for (p = _stack_debug.end; p > _stack_debug.start; p--) {
|
|
|
|
if (*p != STACK_POISON) {
|
|
|
|
break;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
result = p - _stack_debug.start;
|
|
|
|
} else {
|
|
|
|
for (p = _stack_debug.end; p < _stack_debug.start; p++) {
|
|
|
|
if (*p != STACK_POISON) {
|
|
|
|
break;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
result = _stack_debug.start - p;
|
|
|
|
}
|
|
|
|
|
|
|
|
return result;
|
|
|
|
}
|
|
|
|
|
2016-02-02 18:01:57 -04:00
|
|
|
bool Thread::start(const char *name, int policy, int prio)
|
|
|
|
{
|
|
|
|
if (_started) {
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
|
|
|
|
struct sched_param param = { .sched_priority = prio };
|
|
|
|
pthread_attr_t attr;
|
|
|
|
int r;
|
|
|
|
|
|
|
|
pthread_attr_init(&attr);
|
|
|
|
|
|
|
|
/*
|
|
|
|
we need to run as root to get realtime scheduling. Allow it to
|
|
|
|
run as non-root for debugging purposes, plus to allow the Replay
|
|
|
|
tool to run
|
|
|
|
*/
|
|
|
|
if (geteuid() == 0) {
|
|
|
|
if ((r = pthread_attr_setinheritsched(&attr, PTHREAD_EXPLICIT_SCHED)) != 0 ||
|
|
|
|
(r = pthread_attr_setschedpolicy(&attr, policy)) != 0 ||
|
2017-04-18 19:04:27 -03:00
|
|
|
(r = pthread_attr_setschedparam(&attr, ¶m)) != 0) {
|
2016-02-02 18:01:57 -04:00
|
|
|
AP_HAL::panic("Failed to set attributes for thread '%s': %s",
|
|
|
|
name, strerror(r));
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
2016-04-23 02:16:54 -03:00
|
|
|
if (_stack_size) {
|
|
|
|
if (pthread_attr_setstacksize(&attr, _stack_size) != 0) {
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
2016-02-02 18:01:57 -04:00
|
|
|
r = pthread_create(&_ctx, &attr, &Thread::_run_trampoline, this);
|
|
|
|
if (r != 0) {
|
|
|
|
AP_HAL::panic("Failed to create thread '%s': %s",
|
|
|
|
name, strerror(r));
|
|
|
|
}
|
|
|
|
pthread_attr_destroy(&attr);
|
|
|
|
|
|
|
|
if (name) {
|
|
|
|
pthread_setname_np(_ctx, name);
|
|
|
|
}
|
|
|
|
|
|
|
|
_started = true;
|
|
|
|
|
|
|
|
return true;
|
|
|
|
}
|
|
|
|
|
2016-02-03 00:12:23 -04:00
|
|
|
bool Thread::is_current_thread()
|
|
|
|
{
|
|
|
|
return pthread_equal(pthread_self(), _ctx);
|
|
|
|
}
|
|
|
|
|
2016-10-26 10:36:29 -03:00
|
|
|
bool Thread::join()
|
|
|
|
{
|
|
|
|
void *ret;
|
|
|
|
|
|
|
|
if (_ctx == 0) {
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
|
|
|
|
if (pthread_join(_ctx, &ret) != 0 ||
|
|
|
|
(intptr_t)ret != 0) {
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
|
|
|
|
return true;
|
|
|
|
}
|
|
|
|
|
|
|
|
|
2016-02-03 01:11:16 -04:00
|
|
|
bool PeriodicThread::set_rate(uint32_t rate_hz)
|
|
|
|
{
|
|
|
|
if (_started || rate_hz == 0) {
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
|
|
|
|
_period_usec = hz_to_usec(rate_hz);
|
|
|
|
|
|
|
|
return true;
|
|
|
|
}
|
|
|
|
|
2016-04-23 02:16:54 -03:00
|
|
|
bool Thread::set_stack_size(size_t stack_size)
|
|
|
|
{
|
|
|
|
if (_started) {
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
|
2018-09-06 12:23:14 -03:00
|
|
|
_stack_size = MAX(stack_size, (size_t) PTHREAD_STACK_MIN);
|
2016-04-23 02:16:54 -03:00
|
|
|
|
|
|
|
return true;
|
|
|
|
}
|
|
|
|
|
2016-02-03 01:11:16 -04:00
|
|
|
bool PeriodicThread::_run()
|
|
|
|
{
|
2016-10-25 15:50:08 -03:00
|
|
|
if (_period_usec == 0) {
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
|
2016-02-03 01:11:16 -04:00
|
|
|
uint64_t next_run_usec = AP_HAL::micros64() + _period_usec;
|
|
|
|
|
2016-10-26 10:14:28 -03:00
|
|
|
while (!_should_exit) {
|
2016-02-03 01:11:16 -04:00
|
|
|
uint64_t dt = next_run_usec - AP_HAL::micros64();
|
|
|
|
if (dt > _period_usec) {
|
|
|
|
// we've lost sync - restart
|
|
|
|
next_run_usec = AP_HAL::micros64();
|
|
|
|
} else {
|
|
|
|
Scheduler::from(hal.scheduler)->microsleep(dt);
|
|
|
|
}
|
|
|
|
next_run_usec += _period_usec;
|
|
|
|
|
|
|
|
_task();
|
|
|
|
}
|
|
|
|
|
2016-10-26 10:14:28 -03:00
|
|
|
_started = false;
|
|
|
|
_should_exit = false;
|
|
|
|
|
|
|
|
return true;
|
|
|
|
}
|
|
|
|
|
|
|
|
bool PeriodicThread::stop()
|
|
|
|
{
|
|
|
|
if (!is_started()) {
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
|
|
|
|
_should_exit = true;
|
|
|
|
|
2016-02-03 01:11:16 -04:00
|
|
|
return true;
|
|
|
|
}
|
|
|
|
|
2016-02-02 18:01:57 -04:00
|
|
|
}
|