2013-09-22 03:01:24 -03:00
|
|
|
#include "Scheduler.h"
|
2016-02-02 18:09:39 -04:00
|
|
|
|
2015-08-03 13:06:12 -03:00
|
|
|
#include <algorithm>
|
2016-02-02 18:09:39 -04:00
|
|
|
#include <errno.h>
|
2013-09-28 01:59:00 -03:00
|
|
|
#include <poll.h>
|
2013-09-28 21:32:51 -03:00
|
|
|
#include <stdio.h>
|
2016-02-02 18:09:39 -04:00
|
|
|
#include <stdlib.h>
|
2013-10-07 21:09:29 -03:00
|
|
|
#include <sys/mman.h>
|
2016-02-02 18:09:39 -04:00
|
|
|
#include <sys/time.h>
|
|
|
|
#include <unistd.h>
|
|
|
|
|
|
|
|
#include <AP_HAL/AP_HAL.h>
|
2018-07-06 21:25:39 -03:00
|
|
|
#include <AP_Math/AP_Math.h>
|
2016-11-15 22:20:31 -04:00
|
|
|
#include <AP_Vehicle/AP_Vehicle_Type.h>
|
2016-02-02 18:09:39 -04:00
|
|
|
|
|
|
|
#include "RCInput.h"
|
|
|
|
#include "SPIUARTDriver.h"
|
|
|
|
#include "Storage.h"
|
|
|
|
#include "UARTDriver.h"
|
|
|
|
#include "Util.h"
|
2013-09-22 03:01:24 -03:00
|
|
|
|
|
|
|
using namespace Linux;
|
|
|
|
|
|
|
|
extern const AP_HAL::HAL& hal;
|
|
|
|
|
2018-07-06 21:25:39 -03:00
|
|
|
#define APM_LINUX_MAX_PRIORITY 20
|
2014-08-23 04:52:43 -03:00
|
|
|
#define APM_LINUX_TIMER_PRIORITY 15
|
|
|
|
#define APM_LINUX_UART_PRIORITY 14
|
2023-12-24 23:25:19 -04:00
|
|
|
#define APM_LINUX_NET_PRIORITY 14
|
2014-08-23 04:52:43 -03:00
|
|
|
#define APM_LINUX_RCIN_PRIORITY 13
|
|
|
|
#define APM_LINUX_MAIN_PRIORITY 12
|
|
|
|
#define APM_LINUX_IO_PRIORITY 10
|
2018-09-27 20:17:48 -03:00
|
|
|
#define APM_LINUX_SCRIPTING_PRIORITY 1
|
2013-09-28 21:16:07 -03:00
|
|
|
|
2016-02-03 01:13:57 -04:00
|
|
|
#define APM_LINUX_TIMER_RATE 1000
|
|
|
|
#define APM_LINUX_UART_RATE 100
|
2015-11-28 05:38:56 -04:00
|
|
|
#if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_NAVIO || \
|
|
|
|
CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_ERLEBRAIN2 || \
|
2016-01-05 06:33:48 -04:00
|
|
|
CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BH || \
|
2016-10-17 15:02:48 -03:00
|
|
|
CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_DARK || \
|
2023-10-22 14:50:57 -03:00
|
|
|
CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_PXFMINI || \
|
|
|
|
CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_CANZERO
|
2018-12-10 05:01:08 -04:00
|
|
|
#define APM_LINUX_RCIN_RATE 500
|
2016-02-03 01:13:57 -04:00
|
|
|
#define APM_LINUX_IO_RATE 50
|
2021-09-07 02:17:32 -03:00
|
|
|
#elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_OBAL_V1
|
|
|
|
#define APM_LINUX_RCIN_RATE 50
|
|
|
|
#define APM_LINUX_IO_RATE 50
|
2015-04-16 12:19:19 -03:00
|
|
|
#else
|
2016-02-03 01:13:57 -04:00
|
|
|
#define APM_LINUX_RCIN_RATE 100
|
|
|
|
#define APM_LINUX_IO_RATE 50
|
|
|
|
#endif
|
2015-04-16 12:19:19 -03:00
|
|
|
|
2016-02-04 13:18:57 -04:00
|
|
|
#define SCHED_THREAD(name_, UPPER_NAME_) \
|
|
|
|
{ \
|
2016-08-10 18:09:47 -03:00
|
|
|
.name = "ap-" #name_, \
|
2016-02-04 13:18:57 -04:00
|
|
|
.thread = &_##name_##_thread, \
|
|
|
|
.policy = SCHED_FIFO, \
|
|
|
|
.prio = APM_LINUX_##UPPER_NAME_##_PRIORITY, \
|
|
|
|
.rate = APM_LINUX_##UPPER_NAME_##_RATE, \
|
|
|
|
}
|
|
|
|
|
2015-10-20 18:13:25 -03:00
|
|
|
Scheduler::Scheduler()
|
2021-09-17 00:28:40 -03:00
|
|
|
{
|
|
|
|
CPU_ZERO(&_cpu_affinity);
|
|
|
|
}
|
2013-09-28 01:59:00 -03:00
|
|
|
|
2016-11-15 22:20:31 -04:00
|
|
|
|
|
|
|
void Scheduler::init_realtime()
|
|
|
|
{
|
|
|
|
#if APM_BUILD_TYPE(APM_BUILD_Replay)
|
|
|
|
// we don't run Replay in real-time...
|
|
|
|
return;
|
|
|
|
#endif
|
2017-08-02 04:53:18 -03:00
|
|
|
#if APM_BUILD_TYPE(APM_BUILD_UNKNOWN)
|
|
|
|
// we opportunistically run examples/tools in realtime
|
|
|
|
if (geteuid() != 0) {
|
2018-09-20 03:21:13 -03:00
|
|
|
fprintf(stderr, "WARNING: not running as root. Will not use realtime scheduling\n");
|
2017-08-02 04:53:18 -03:00
|
|
|
return;
|
|
|
|
}
|
|
|
|
#endif
|
2016-11-15 22:20:31 -04:00
|
|
|
|
|
|
|
mlockall(MCL_CURRENT|MCL_FUTURE);
|
|
|
|
|
|
|
|
struct sched_param param = { .sched_priority = APM_LINUX_MAIN_PRIORITY };
|
2020-07-06 11:14:22 -03:00
|
|
|
if (pthread_setschedparam(pthread_self(), SCHED_FIFO, ¶m) == -1) {
|
2016-11-15 22:20:31 -04:00
|
|
|
AP_HAL::panic("Scheduler: failed to set scheduling parameters: %s",
|
|
|
|
strerror(errno));
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
2021-09-17 00:28:40 -03:00
|
|
|
void Scheduler::init_cpu_affinity()
|
|
|
|
{
|
|
|
|
if (!CPU_COUNT(&_cpu_affinity)) {
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
|
|
|
if (sched_setaffinity(0, sizeof(_cpu_affinity), &_cpu_affinity) != 0) {
|
|
|
|
AP_HAL::panic("Failed to set affinity for main process: %m");
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
2015-12-02 11:14:20 -04:00
|
|
|
void Scheduler::init()
|
2013-09-22 03:01:24 -03:00
|
|
|
{
|
2016-11-03 15:40:55 -03:00
|
|
|
int ret;
|
2016-02-04 13:18:57 -04:00
|
|
|
const struct sched_table {
|
|
|
|
const char *name;
|
|
|
|
SchedulerThread *thread;
|
|
|
|
int policy;
|
|
|
|
int prio;
|
|
|
|
uint32_t rate;
|
|
|
|
} sched_table[] = {
|
|
|
|
SCHED_THREAD(timer, TIMER),
|
|
|
|
SCHED_THREAD(uart, UART),
|
|
|
|
SCHED_THREAD(rcin, RCIN),
|
|
|
|
SCHED_THREAD(io, IO),
|
|
|
|
};
|
|
|
|
|
2017-07-31 18:41:43 -03:00
|
|
|
_main_ctx = pthread_self();
|
|
|
|
|
2016-11-15 22:20:31 -04:00
|
|
|
init_realtime();
|
2021-09-17 00:28:40 -03:00
|
|
|
init_cpu_affinity();
|
2016-02-02 18:12:07 -04:00
|
|
|
|
2016-02-04 13:18:57 -04:00
|
|
|
/* set barrier to N + 1 threads: worker threads + main */
|
|
|
|
unsigned n_threads = ARRAY_SIZE(sched_table) + 1;
|
2016-11-03 15:40:55 -03:00
|
|
|
ret = pthread_barrier_init(&_initialized_barrier, nullptr, n_threads);
|
|
|
|
if (ret) {
|
|
|
|
AP_HAL::panic("Scheduler: Failed to initialise barrier object: %s",
|
|
|
|
strerror(ret));
|
|
|
|
}
|
2016-02-04 13:18:57 -04:00
|
|
|
|
|
|
|
for (size_t i = 0; i < ARRAY_SIZE(sched_table); i++) {
|
|
|
|
const struct sched_table *t = &sched_table[i];
|
|
|
|
|
|
|
|
t->thread->set_rate(t->rate);
|
2017-05-22 17:43:41 -03:00
|
|
|
t->thread->set_stack_size(1024 * 1024);
|
2016-02-04 13:18:57 -04:00
|
|
|
t->thread->start(t->name, t->policy, t->prio);
|
|
|
|
}
|
2016-04-23 02:01:22 -03:00
|
|
|
|
|
|
|
#if defined(DEBUG_STACK) && DEBUG_STACK
|
|
|
|
register_timer_process(FUNCTOR_BIND_MEMBER(&Scheduler::_debug_stack, void));
|
|
|
|
#endif
|
|
|
|
}
|
|
|
|
|
|
|
|
void Scheduler::_debug_stack()
|
|
|
|
{
|
|
|
|
uint64_t now = AP_HAL::millis64();
|
|
|
|
|
|
|
|
if (now - _last_stack_debug_msec > 5000) {
|
|
|
|
fprintf(stderr, "Stack Usage:\n"
|
|
|
|
"\ttimer = %zu\n"
|
|
|
|
"\tio = %zu\n"
|
|
|
|
"\trcin = %zu\n"
|
2018-08-07 18:24:00 -03:00
|
|
|
"\tuart = %zu\n",
|
2016-04-23 02:01:22 -03:00
|
|
|
_timer_thread.get_stack_usage(),
|
|
|
|
_io_thread.get_stack_usage(),
|
|
|
|
_rcin_thread.get_stack_usage(),
|
2018-07-25 19:28:50 -03:00
|
|
|
_uart_thread.get_stack_usage());
|
2016-04-23 02:01:22 -03:00
|
|
|
_last_stack_debug_msec = now;
|
|
|
|
}
|
2013-09-22 03:01:24 -03:00
|
|
|
}
|
|
|
|
|
2016-02-01 18:17:54 -04:00
|
|
|
void Scheduler::microsleep(uint32_t usec)
|
2013-10-07 21:09:29 -03:00
|
|
|
{
|
|
|
|
struct timespec ts;
|
|
|
|
ts.tv_sec = 0;
|
|
|
|
ts.tv_nsec = usec*1000UL;
|
|
|
|
while (nanosleep(&ts, &ts) == -1 && errno == EINTR) ;
|
|
|
|
}
|
|
|
|
|
2015-10-20 18:13:25 -03:00
|
|
|
void Scheduler::delay(uint16_t ms)
|
2013-09-22 03:01:24 -03:00
|
|
|
{
|
2015-11-11 10:02:43 -04:00
|
|
|
if (_stopped_clock_usec) {
|
2014-01-04 20:39:29 -04:00
|
|
|
return;
|
|
|
|
}
|
2017-07-31 18:41:43 -03:00
|
|
|
|
2015-11-11 10:02:43 -04:00
|
|
|
uint64_t start = AP_HAL::millis64();
|
2015-08-17 23:39:02 -03:00
|
|
|
|
2015-11-11 10:02:43 -04:00
|
|
|
while ((AP_HAL::millis64() - start) < ms) {
|
2013-09-28 21:32:51 -03:00
|
|
|
// this yields the CPU to other apps
|
2016-02-01 18:17:54 -04:00
|
|
|
microsleep(1000);
|
2018-07-06 22:51:19 -03:00
|
|
|
if (in_main_thread() && _min_delay_cb_ms <= ms) {
|
2018-05-08 02:55:11 -03:00
|
|
|
call_delay_cb();
|
2013-09-28 21:32:51 -03:00
|
|
|
}
|
|
|
|
}
|
2013-09-22 03:01:24 -03:00
|
|
|
}
|
|
|
|
|
2015-10-20 18:13:25 -03:00
|
|
|
void Scheduler::delay_microseconds(uint16_t us)
|
2013-09-22 03:01:24 -03:00
|
|
|
{
|
2015-11-11 10:02:43 -04:00
|
|
|
if (_stopped_clock_usec) {
|
2014-11-15 21:30:50 -04:00
|
|
|
return;
|
|
|
|
}
|
2016-02-01 18:17:54 -04:00
|
|
|
microsleep(us);
|
2013-09-22 03:01:24 -03:00
|
|
|
}
|
|
|
|
|
2015-10-20 18:13:25 -03:00
|
|
|
void Scheduler::register_timer_process(AP_HAL::MemberProc proc)
|
2013-09-28 01:59:00 -03:00
|
|
|
{
|
|
|
|
for (uint8_t i = 0; i < _num_timer_procs; i++) {
|
|
|
|
if (_timer_proc[i] == proc) {
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
2017-07-31 16:34:16 -03:00
|
|
|
if (_num_timer_procs >= LINUX_SCHEDULER_MAX_TIMER_PROCS) {
|
2013-09-28 01:59:00 -03:00
|
|
|
hal.console->printf("Out of timer processes\n");
|
2017-07-31 16:34:16 -03:00
|
|
|
return;
|
2013-09-28 01:59:00 -03:00
|
|
|
}
|
2013-09-22 03:01:24 -03:00
|
|
|
|
2017-07-31 16:34:16 -03:00
|
|
|
_timer_proc[_num_timer_procs] = proc;
|
|
|
|
_num_timer_procs++;
|
2015-08-03 13:06:12 -03:00
|
|
|
}
|
|
|
|
|
2015-10-20 18:13:25 -03:00
|
|
|
void Scheduler::register_io_process(AP_HAL::MemberProc proc)
|
2013-09-28 01:59:00 -03:00
|
|
|
{
|
|
|
|
for (uint8_t i = 0; i < _num_io_procs; i++) {
|
|
|
|
if (_io_proc[i] == proc) {
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
2015-01-26 02:45:17 -04:00
|
|
|
if (_num_io_procs < LINUX_SCHEDULER_MAX_IO_PROCS) {
|
2013-09-28 01:59:00 -03:00
|
|
|
_io_proc[_num_io_procs] = proc;
|
|
|
|
_num_io_procs++;
|
|
|
|
} else {
|
|
|
|
hal.console->printf("Out of IO processes\n");
|
|
|
|
}
|
|
|
|
}
|
2013-09-22 03:01:24 -03:00
|
|
|
|
2015-10-20 18:13:25 -03:00
|
|
|
void Scheduler::register_timer_failsafe(AP_HAL::Proc failsafe, uint32_t period_us)
|
2013-09-28 01:59:00 -03:00
|
|
|
{
|
|
|
|
_failsafe = failsafe;
|
|
|
|
}
|
2013-09-22 03:01:24 -03:00
|
|
|
|
2016-02-03 01:13:57 -04:00
|
|
|
void Scheduler::_timer_task()
|
2013-09-28 01:59:00 -03:00
|
|
|
{
|
2015-08-03 13:06:12 -03:00
|
|
|
int i;
|
|
|
|
|
2013-09-28 01:59:00 -03:00
|
|
|
if (_in_timer_proc) {
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
_in_timer_proc = true;
|
|
|
|
|
2014-08-20 18:49:49 -03:00
|
|
|
// now call the timer based drivers
|
2015-08-03 13:06:12 -03:00
|
|
|
for (i = 0; i < _num_timer_procs; i++) {
|
2015-05-26 02:14:50 -03:00
|
|
|
if (_timer_proc[i]) {
|
2014-08-20 18:49:49 -03:00
|
|
|
_timer_proc[i]();
|
2013-09-28 01:59:00 -03:00
|
|
|
}
|
|
|
|
}
|
2015-08-17 23:39:02 -03:00
|
|
|
|
2013-09-28 01:59:00 -03:00
|
|
|
// and the failsafe, if one is setup
|
2016-10-30 02:24:21 -03:00
|
|
|
if (_failsafe != nullptr) {
|
2013-09-30 23:09:46 -03:00
|
|
|
_failsafe();
|
2013-09-28 01:59:00 -03:00
|
|
|
}
|
|
|
|
|
|
|
|
_in_timer_proc = false;
|
|
|
|
}
|
|
|
|
|
2015-10-20 18:13:25 -03:00
|
|
|
void Scheduler::_run_io(void)
|
2013-09-28 01:59:00 -03:00
|
|
|
{
|
2020-01-18 17:42:33 -04:00
|
|
|
_io_semaphore.take_blocking();
|
2013-09-28 01:59:00 -03:00
|
|
|
|
2014-08-20 18:49:49 -03:00
|
|
|
// now call the IO based drivers
|
|
|
|
for (int i = 0; i < _num_io_procs; i++) {
|
2015-05-26 02:14:50 -03:00
|
|
|
if (_io_proc[i]) {
|
2014-08-20 18:49:49 -03:00
|
|
|
_io_proc[i]();
|
2013-09-28 01:59:00 -03:00
|
|
|
}
|
|
|
|
}
|
|
|
|
|
2014-12-07 20:24:39 -04:00
|
|
|
_io_semaphore.give();
|
2013-09-28 01:59:00 -03:00
|
|
|
}
|
|
|
|
|
2015-12-13 23:19:54 -04:00
|
|
|
/*
|
|
|
|
run timers for all UARTs
|
|
|
|
*/
|
2016-02-02 18:12:07 -04:00
|
|
|
void Scheduler::_run_uarts()
|
2015-12-13 23:19:54 -04:00
|
|
|
{
|
|
|
|
// process any pending serial bytes
|
2020-12-10 20:56:02 -04:00
|
|
|
for (uint8_t i=0;i<hal.num_serial; i++) {
|
|
|
|
hal.serial(i)->_timer_tick();
|
|
|
|
}
|
2015-12-13 23:19:54 -04:00
|
|
|
}
|
|
|
|
|
2016-02-03 01:13:57 -04:00
|
|
|
void Scheduler::_rcin_task()
|
|
|
|
{
|
|
|
|
RCInput::from(hal.rcin)->_timer_tick();
|
|
|
|
}
|
|
|
|
|
2016-02-02 18:12:07 -04:00
|
|
|
void Scheduler::_uart_task()
|
2013-09-28 01:59:00 -03:00
|
|
|
{
|
2016-02-03 01:13:57 -04:00
|
|
|
_run_uarts();
|
2013-09-28 01:59:00 -03:00
|
|
|
}
|
|
|
|
|
2016-02-02 18:12:07 -04:00
|
|
|
void Scheduler::_io_task()
|
2013-09-28 01:59:00 -03:00
|
|
|
{
|
2016-02-03 01:13:57 -04:00
|
|
|
// process any pending storage writes
|
2018-01-26 22:32:05 -04:00
|
|
|
hal.storage->_timer_tick();
|
2013-09-28 01:59:00 -03:00
|
|
|
|
2016-02-03 01:13:57 -04:00
|
|
|
// run registered IO processes
|
|
|
|
_run_io();
|
2013-09-28 01:59:00 -03:00
|
|
|
}
|
|
|
|
|
2017-09-17 22:02:54 -03:00
|
|
|
bool Scheduler::in_main_thread() const
|
2017-07-31 18:41:43 -03:00
|
|
|
{
|
|
|
|
return pthread_equal(pthread_self(), _main_ctx);
|
|
|
|
}
|
|
|
|
|
2016-02-02 23:42:47 -04:00
|
|
|
void Scheduler::_wait_all_threads()
|
|
|
|
{
|
|
|
|
int r = pthread_barrier_wait(&_initialized_barrier);
|
|
|
|
if (r == PTHREAD_BARRIER_SERIAL_THREAD) {
|
|
|
|
pthread_barrier_destroy(&_initialized_barrier);
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
2020-12-23 07:27:27 -04:00
|
|
|
void Scheduler::set_system_initialized()
|
2013-09-28 01:59:00 -03:00
|
|
|
{
|
|
|
|
if (_initialized) {
|
2020-12-23 07:27:27 -04:00
|
|
|
AP_HAL::panic("PANIC: scheduler::set_system_initialized called more than once");
|
2013-09-28 01:59:00 -03:00
|
|
|
}
|
2016-02-02 23:42:47 -04:00
|
|
|
|
2013-09-28 01:59:00 -03:00
|
|
|
_initialized = true;
|
2016-02-02 23:42:47 -04:00
|
|
|
|
|
|
|
_wait_all_threads();
|
2013-09-22 03:01:24 -03:00
|
|
|
}
|
|
|
|
|
2015-10-20 18:13:25 -03:00
|
|
|
void Scheduler::reboot(bool hold_in_bootloader)
|
2013-09-28 01:59:00 -03:00
|
|
|
{
|
2014-10-19 22:40:08 -03:00
|
|
|
exit(1);
|
2013-09-22 03:01:24 -03:00
|
|
|
}
|
2013-09-28 03:28:36 -03:00
|
|
|
|
2022-04-22 13:22:00 -03:00
|
|
|
#if APM_BUILD_TYPE(APM_BUILD_Replay) || APM_BUILD_TYPE(APM_BUILD_UNKNOWN)
|
2015-10-20 18:13:25 -03:00
|
|
|
void Scheduler::stop_clock(uint64_t time_usec)
|
2013-12-29 18:31:33 -04:00
|
|
|
{
|
2020-03-11 21:37:54 -03:00
|
|
|
if (time_usec < _stopped_clock_usec) {
|
|
|
|
::fprintf(stderr, "Warning: setting time backwards from (%" PRIu64 ") to (%" PRIu64 ")\n", _stopped_clock_usec, time_usec);
|
|
|
|
return;
|
2015-04-20 01:04:23 -03:00
|
|
|
}
|
2020-03-11 21:37:54 -03:00
|
|
|
|
|
|
|
_stopped_clock_usec = time_usec;
|
|
|
|
_run_io();
|
2013-12-31 05:05:07 -04:00
|
|
|
}
|
2020-03-11 21:37:54 -03:00
|
|
|
#else
|
|
|
|
void Scheduler::stop_clock(uint64_t time_usec)
|
|
|
|
{
|
|
|
|
// stop_clock() is not called outside of Replay, but we can't
|
|
|
|
// guard it in the header because of the vehicle-dependent-library
|
|
|
|
// checks in waf.
|
|
|
|
}
|
|
|
|
#endif
|
2016-02-02 19:07:23 -04:00
|
|
|
|
|
|
|
bool Scheduler::SchedulerThread::_run()
|
|
|
|
{
|
2016-02-02 23:42:47 -04:00
|
|
|
_sched._wait_all_threads();
|
2016-02-02 19:07:23 -04:00
|
|
|
|
2016-02-03 01:13:57 -04:00
|
|
|
return PeriodicThread::_run();
|
2016-02-02 19:07:23 -04:00
|
|
|
}
|
2016-10-26 18:58:57 -03:00
|
|
|
|
|
|
|
void Scheduler::teardown()
|
|
|
|
{
|
|
|
|
_timer_thread.stop();
|
|
|
|
_io_thread.stop();
|
|
|
|
_rcin_thread.stop();
|
|
|
|
_uart_thread.stop();
|
|
|
|
|
|
|
|
_timer_thread.join();
|
|
|
|
_io_thread.join();
|
|
|
|
_rcin_thread.join();
|
|
|
|
_uart_thread.join();
|
|
|
|
}
|
2018-07-06 21:25:39 -03:00
|
|
|
|
2021-03-18 22:40:56 -03:00
|
|
|
// calculates an integer to be used as the priority for a newly-created thread
|
|
|
|
uint8_t Scheduler::calculate_thread_priority(priority_base base, int8_t priority) const
|
2018-07-06 21:25:39 -03:00
|
|
|
{
|
|
|
|
uint8_t thread_priority = APM_LINUX_IO_PRIORITY;
|
|
|
|
static const struct {
|
|
|
|
priority_base base;
|
|
|
|
uint8_t p;
|
|
|
|
} priority_map[] = {
|
|
|
|
{ PRIORITY_BOOST, APM_LINUX_MAIN_PRIORITY},
|
|
|
|
{ PRIORITY_MAIN, APM_LINUX_MAIN_PRIORITY},
|
|
|
|
{ PRIORITY_SPI, AP_LINUX_SENSORS_SCHED_PRIO},
|
|
|
|
{ PRIORITY_I2C, AP_LINUX_SENSORS_SCHED_PRIO},
|
|
|
|
{ PRIORITY_CAN, APM_LINUX_TIMER_PRIORITY},
|
|
|
|
{ PRIORITY_TIMER, APM_LINUX_TIMER_PRIORITY},
|
|
|
|
{ PRIORITY_RCIN, APM_LINUX_RCIN_PRIORITY},
|
|
|
|
{ PRIORITY_IO, APM_LINUX_IO_PRIORITY},
|
|
|
|
{ PRIORITY_UART, APM_LINUX_UART_PRIORITY},
|
|
|
|
{ PRIORITY_STORAGE, APM_LINUX_IO_PRIORITY},
|
2018-09-27 20:17:48 -03:00
|
|
|
{ PRIORITY_SCRIPTING, APM_LINUX_SCRIPTING_PRIORITY},
|
2023-12-24 23:25:19 -04:00
|
|
|
{ PRIORITY_NET, APM_LINUX_NET_PRIORITY},
|
2018-07-06 21:25:39 -03:00
|
|
|
};
|
|
|
|
for (uint8_t i=0; i<ARRAY_SIZE(priority_map); i++) {
|
|
|
|
if (priority_map[i].base == base) {
|
|
|
|
thread_priority = constrain_int16(priority_map[i].p + priority, 1, APM_LINUX_MAX_PRIORITY);
|
|
|
|
break;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
2021-03-18 22:40:56 -03:00
|
|
|
return thread_priority;
|
|
|
|
}
|
|
|
|
|
|
|
|
/*
|
|
|
|
create a new thread
|
|
|
|
*/
|
|
|
|
bool Scheduler::thread_create(AP_HAL::MemberProc proc, const char *name, uint32_t stack_size, priority_base base, int8_t priority)
|
|
|
|
{
|
|
|
|
Thread *thread = new Thread{(Thread::task_t)proc};
|
|
|
|
if (!thread) {
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
|
|
|
|
const uint8_t thread_priority = calculate_thread_priority(base, priority);
|
|
|
|
|
2018-09-06 12:23:14 -03:00
|
|
|
// Add 256k to HAL-independent requested stack size
|
|
|
|
thread->set_stack_size(256 * 1024 + stack_size);
|
2018-07-06 21:25:39 -03:00
|
|
|
|
2018-07-10 18:48:39 -03:00
|
|
|
/*
|
|
|
|
* We should probably store the thread handlers and join() when exiting,
|
|
|
|
* but let's the thread manage itself for now.
|
|
|
|
*/
|
|
|
|
thread->set_auto_free(true);
|
2018-07-06 21:25:39 -03:00
|
|
|
|
2018-07-10 18:48:39 -03:00
|
|
|
if (!thread->start(name, SCHED_FIFO, thread_priority)) {
|
|
|
|
delete thread;
|
2018-07-06 21:25:39 -03:00
|
|
|
return false;
|
|
|
|
}
|
2018-07-10 18:48:39 -03:00
|
|
|
|
2018-07-06 21:25:39 -03:00
|
|
|
return true;
|
|
|
|
}
|