2015-08-11 03:28:43 -03:00
|
|
|
#include <AP_HAL/AP_HAL.h>
|
2013-09-28 03:28:36 -03:00
|
|
|
|
2014-07-06 23:03:26 -03:00
|
|
|
#if CONFIG_HAL_BOARD == HAL_BOARD_LINUX
|
2013-09-22 03:01:24 -03:00
|
|
|
|
|
|
|
#include "Scheduler.h"
|
2013-09-28 01:59:00 -03:00
|
|
|
#include "Storage.h"
|
2014-08-14 13:48:17 -03:00
|
|
|
#include "RCInput.h"
|
2013-09-28 21:13:51 -03:00
|
|
|
#include "UARTDriver.h"
|
2014-08-23 04:52:43 -03:00
|
|
|
#include "Util.h"
|
2014-11-07 06:17:50 -04:00
|
|
|
#include "SPIUARTDriver.h"
|
2015-08-17 23:39:02 -03:00
|
|
|
#include "RPIOUARTDriver.h"
|
2015-08-03 13:06:12 -03:00
|
|
|
#include <algorithm>
|
2013-09-28 01:59:00 -03:00
|
|
|
#include <poll.h>
|
|
|
|
#include <unistd.h>
|
|
|
|
#include <stdlib.h>
|
2013-09-28 21:32:51 -03:00
|
|
|
#include <stdio.h>
|
2013-10-07 21:09:29 -03:00
|
|
|
#include <errno.h>
|
|
|
|
#include <sys/mman.h>
|
2013-09-22 03:01:24 -03:00
|
|
|
|
2015-12-13 23:19:54 -04:00
|
|
|
#if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_QFLIGHT
|
|
|
|
#include <rpcmem.h>
|
|
|
|
#include <AP_HAL_Linux/qflight/qflight_util.h>
|
|
|
|
#include <AP_HAL_Linux/qflight/qflight_dsp.h>
|
|
|
|
#include <AP_HAL_Linux/qflight/qflight_buffer.h>
|
|
|
|
#endif
|
|
|
|
|
|
|
|
|
2013-09-22 03:01:24 -03:00
|
|
|
using namespace Linux;
|
|
|
|
|
|
|
|
extern const AP_HAL::HAL& hal;
|
|
|
|
|
2014-08-23 04:52:43 -03:00
|
|
|
#define APM_LINUX_TIMER_PRIORITY 15
|
|
|
|
#define APM_LINUX_UART_PRIORITY 14
|
|
|
|
#define APM_LINUX_RCIN_PRIORITY 13
|
|
|
|
#define APM_LINUX_MAIN_PRIORITY 12
|
|
|
|
#define APM_LINUX_TONEALARM_PRIORITY 11
|
|
|
|
#define APM_LINUX_IO_PRIORITY 10
|
2013-09-28 21:16:07 -03:00
|
|
|
|
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 || \
|
|
|
|
CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_PXFMINI
|
2015-04-16 12:19:19 -03:00
|
|
|
#define APM_LINUX_UART_PERIOD 10000
|
2015-08-17 23:39:02 -03:00
|
|
|
#define APM_LINUX_RCIN_PERIOD 500
|
2015-04-16 12:19:19 -03:00
|
|
|
#define APM_LINUX_TONEALARM_PERIOD 10000
|
|
|
|
#define APM_LINUX_IO_PERIOD 20000
|
|
|
|
#else
|
|
|
|
#define APM_LINUX_UART_PERIOD 10000
|
|
|
|
#define APM_LINUX_RCIN_PERIOD 10000
|
|
|
|
#define APM_LINUX_TONEALARM_PERIOD 10000
|
|
|
|
#define APM_LINUX_IO_PERIOD 20000
|
2015-11-28 05:38:56 -04:00
|
|
|
#endif // CONFIG_HAL_BOARD_SUBTYPE
|
2015-04-16 12:19:19 -03:00
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
2015-10-20 18:13:25 -03:00
|
|
|
Scheduler::Scheduler()
|
2013-09-22 03:01:24 -03:00
|
|
|
{}
|
|
|
|
|
2015-10-20 18:13:25 -03:00
|
|
|
void Scheduler::_create_realtime_thread(pthread_t *ctx, int rtprio,
|
2015-03-18 17:59:29 -03:00
|
|
|
const char *name,
|
2015-03-18 16:50:44 -03:00
|
|
|
pthread_startroutine_t start_routine)
|
|
|
|
{
|
|
|
|
struct sched_param param = { .sched_priority = rtprio };
|
|
|
|
pthread_attr_t attr;
|
|
|
|
int r;
|
|
|
|
|
|
|
|
pthread_attr_init(&attr);
|
2015-04-13 20:25:35 -03:00
|
|
|
/*
|
|
|
|
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) {
|
|
|
|
pthread_attr_setinheritsched(&attr, PTHREAD_EXPLICIT_SCHED);
|
|
|
|
pthread_attr_setschedpolicy(&attr, SCHED_FIFO);
|
|
|
|
pthread_attr_setschedparam(&attr, ¶m);
|
|
|
|
}
|
2015-03-18 16:50:44 -03:00
|
|
|
r = pthread_create(ctx, &attr, start_routine, this);
|
|
|
|
if (r != 0) {
|
2015-03-18 17:59:29 -03:00
|
|
|
hal.console->printf("Error creating thread '%s': %s\n",
|
|
|
|
name, strerror(r));
|
2015-11-11 10:02:43 -04:00
|
|
|
AP_HAL::panic("Failed to create thread");
|
2015-03-18 16:50:44 -03:00
|
|
|
}
|
|
|
|
pthread_attr_destroy(&attr);
|
2015-03-18 18:00:24 -03:00
|
|
|
|
|
|
|
if (name) {
|
|
|
|
pthread_setname_np(*ctx, name);
|
|
|
|
}
|
2015-03-18 16:50:44 -03:00
|
|
|
}
|
2013-09-28 01:59:00 -03:00
|
|
|
|
2015-12-02 11:14:20 -04:00
|
|
|
void Scheduler::init()
|
2013-09-22 03:01:24 -03:00
|
|
|
{
|
2015-03-18 16:36:44 -03:00
|
|
|
mlockall(MCL_CURRENT|MCL_FUTURE);
|
2013-09-28 01:59:00 -03:00
|
|
|
|
2015-03-18 16:50:44 -03:00
|
|
|
struct sched_param param = { .sched_priority = APM_LINUX_MAIN_PRIORITY };
|
2013-09-28 21:16:07 -03:00
|
|
|
sched_setscheduler(0, SCHED_FIFO, ¶m);
|
|
|
|
|
2015-03-18 17:59:29 -03:00
|
|
|
struct {
|
|
|
|
pthread_t *ctx;
|
|
|
|
int rtprio;
|
|
|
|
const char *name;
|
|
|
|
pthread_startroutine_t start_routine;
|
|
|
|
} *iter, table[] = {
|
|
|
|
{ .ctx = &_timer_thread_ctx,
|
|
|
|
.rtprio = APM_LINUX_TIMER_PRIORITY,
|
|
|
|
.name = "sched-timer",
|
2015-10-20 18:13:25 -03:00
|
|
|
.start_routine = &Linux::Scheduler::_timer_thread,
|
2015-03-18 17:59:29 -03:00
|
|
|
},
|
|
|
|
{ .ctx = &_uart_thread_ctx,
|
|
|
|
.rtprio = APM_LINUX_UART_PRIORITY,
|
|
|
|
.name = "sched-uart",
|
2015-10-20 18:13:25 -03:00
|
|
|
.start_routine = &Linux::Scheduler::_uart_thread,
|
2015-03-18 17:59:29 -03:00
|
|
|
},
|
|
|
|
{ .ctx = &_rcin_thread_ctx,
|
|
|
|
.rtprio = APM_LINUX_RCIN_PRIORITY,
|
|
|
|
.name = "sched-rcin",
|
2015-10-20 18:13:25 -03:00
|
|
|
.start_routine = &Linux::Scheduler::_rcin_thread,
|
2015-03-18 17:59:29 -03:00
|
|
|
},
|
|
|
|
{ .ctx = &_tonealarm_thread_ctx,
|
|
|
|
.rtprio = APM_LINUX_TONEALARM_PRIORITY,
|
|
|
|
.name = "sched-tonealarm",
|
2015-10-20 18:13:25 -03:00
|
|
|
.start_routine = &Linux::Scheduler::_tonealarm_thread,
|
2015-03-18 17:59:29 -03:00
|
|
|
},
|
|
|
|
{ .ctx = &_io_thread_ctx,
|
|
|
|
.rtprio = APM_LINUX_IO_PRIORITY,
|
|
|
|
.name = "sched-io",
|
2015-10-20 18:13:25 -03:00
|
|
|
.start_routine = &Linux::Scheduler::_io_thread,
|
2015-03-18 17:59:29 -03:00
|
|
|
},
|
|
|
|
{ }
|
|
|
|
};
|
|
|
|
|
2015-04-13 20:25:35 -03:00
|
|
|
if (geteuid() != 0) {
|
|
|
|
printf("WARNING: running as non-root. Will not use realtime scheduling\n");
|
|
|
|
}
|
|
|
|
|
2015-03-18 17:59:29 -03:00
|
|
|
for (iter = table; iter->ctx; iter++)
|
|
|
|
_create_realtime_thread(iter->ctx, iter->rtprio, iter->name,
|
|
|
|
iter->start_routine);
|
2013-09-22 03:01:24 -03:00
|
|
|
}
|
|
|
|
|
2015-10-20 18:13:25 -03: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;
|
|
|
|
}
|
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
|
2013-10-07 21:09:29 -03:00
|
|
|
_microsleep(1000);
|
2013-09-28 21:32:51 -03:00
|
|
|
if (_min_delay_cb_ms <= ms) {
|
|
|
|
if (_delay_cb) {
|
|
|
|
_delay_cb();
|
|
|
|
}
|
|
|
|
}
|
|
|
|
}
|
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;
|
|
|
|
}
|
2013-10-07 21:09:29 -03:00
|
|
|
_microsleep(us);
|
2013-09-22 03:01:24 -03:00
|
|
|
}
|
|
|
|
|
2015-10-20 18:13:25 -03:00
|
|
|
void Scheduler::register_delay_callback(AP_HAL::Proc proc,
|
2013-09-28 01:59:00 -03:00
|
|
|
uint16_t min_time_ms)
|
|
|
|
{
|
|
|
|
_delay_cb = proc;
|
|
|
|
_min_delay_cb_ms = min_time_ms;
|
|
|
|
}
|
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;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
if (_num_timer_procs < LINUX_SCHEDULER_MAX_TIMER_PROCS) {
|
|
|
|
_timer_proc[_num_timer_procs] = proc;
|
|
|
|
_num_timer_procs++;
|
|
|
|
} else {
|
|
|
|
hal.console->printf("Out of timer processes\n");
|
|
|
|
}
|
|
|
|
}
|
2013-09-22 03:01:24 -03:00
|
|
|
|
2015-08-03 13:06:12 -03:00
|
|
|
bool Scheduler::register_timer_process(AP_HAL::MemberProc proc,
|
|
|
|
uint8_t freq_div)
|
|
|
|
{
|
|
|
|
#if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BEBOP
|
|
|
|
if (freq_div > 1) {
|
|
|
|
return _register_timesliced_proc(proc, freq_div);
|
|
|
|
}
|
|
|
|
/* fallback to normal timer process */
|
|
|
|
#endif
|
|
|
|
register_timer_process(proc);
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
|
|
|
|
bool Scheduler::_register_timesliced_proc(AP_HAL::MemberProc proc,
|
|
|
|
uint8_t freq_div)
|
|
|
|
{
|
|
|
|
unsigned int i, j;
|
|
|
|
uint8_t distance, min_distance, best_distance;
|
|
|
|
uint8_t best_timeslot;
|
|
|
|
|
|
|
|
if (_num_timesliced_procs > LINUX_SCHEDULER_MAX_TIMESLICED_PROCS) {
|
|
|
|
hal.console->printf("Out of timesliced processes\n");
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
|
|
|
|
/* if max_freq_div increases, update the timeslots accordingly */
|
|
|
|
if (freq_div > _max_freq_div) {
|
|
|
|
for (i = 0; i < _num_timesliced_procs; i++) {
|
|
|
|
_timesliced_proc[i].timeslot = _timesliced_proc[i].timeslot
|
|
|
|
/ _max_freq_div * freq_div;
|
|
|
|
}
|
|
|
|
_max_freq_div = freq_div;
|
|
|
|
}
|
|
|
|
|
|
|
|
best_distance = 0;
|
|
|
|
best_timeslot = 0;
|
|
|
|
|
|
|
|
/* Look for the timeslot that maximizes the min distance with other timeslots */
|
|
|
|
for (i = 0; i < _max_freq_div; i++) {
|
|
|
|
min_distance = _max_freq_div;
|
|
|
|
for (j = 0; j < _num_timesliced_procs; j++) {
|
|
|
|
distance = std::min(i - _timesliced_proc[j].timeslot,
|
|
|
|
_max_freq_div + _timesliced_proc[j].timeslot - i);
|
|
|
|
if (distance < min_distance) {
|
|
|
|
min_distance = distance;
|
|
|
|
if (min_distance == 0) {
|
|
|
|
break;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
}
|
|
|
|
if (min_distance > best_distance) {
|
|
|
|
best_distance = min_distance;
|
|
|
|
best_timeslot = i;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
_timesliced_proc[_num_timesliced_procs].proc = proc;
|
|
|
|
_timesliced_proc[_num_timesliced_procs].timeslot = best_timeslot;
|
|
|
|
_timesliced_proc[_num_timesliced_procs].freq_div = freq_div;
|
|
|
|
_num_timesliced_procs++;
|
|
|
|
return true;
|
|
|
|
}
|
|
|
|
|
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
|
|
|
|
2015-10-20 18:13:25 -03:00
|
|
|
void Scheduler::suspend_timer_procs()
|
2013-09-28 01:59:00 -03:00
|
|
|
{
|
2014-08-20 18:49:49 -03:00
|
|
|
if (!_timer_semaphore.take(0)) {
|
|
|
|
printf("Failed to take timer semaphore\n");
|
2013-09-28 21:48:22 -03:00
|
|
|
}
|
2013-09-28 01:59:00 -03:00
|
|
|
}
|
2013-09-22 03:01:24 -03:00
|
|
|
|
2015-10-20 18:13:25 -03:00
|
|
|
void Scheduler::resume_timer_procs()
|
2013-09-28 01:59:00 -03:00
|
|
|
{
|
2014-08-20 18:49:49 -03:00
|
|
|
_timer_semaphore.give();
|
2013-09-28 01:59:00 -03:00
|
|
|
}
|
|
|
|
|
2015-10-20 18:13:25 -03:00
|
|
|
void Scheduler::_run_timers(bool called_from_timer_thread)
|
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
|
|
|
if (!_timer_semaphore.take(0)) {
|
|
|
|
printf("Failed to take timer semaphore in _run_timers\n");
|
|
|
|
}
|
|
|
|
// 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
|
|
|
|
|
|
|
#if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_RASPILOT
|
|
|
|
//SPI UART use SPI
|
2015-10-20 18:13:25 -03:00
|
|
|
if (!((RPIOUARTDriver *)hal.uartC)->isExternal() )
|
2015-08-17 23:39:02 -03:00
|
|
|
{
|
2015-10-20 18:13:25 -03:00
|
|
|
((RPIOUARTDriver *)hal.uartC)->_timer_tick();
|
2015-08-17 23:39:02 -03:00
|
|
|
}
|
|
|
|
#endif
|
|
|
|
|
2015-08-03 13:06:12 -03:00
|
|
|
for (i = 0; i < _num_timesliced_procs; i++) {
|
|
|
|
if ((_timeslices_count + _timesliced_proc[i].timeslot)
|
|
|
|
% _timesliced_proc[i].freq_div == 0) {
|
|
|
|
_timesliced_proc[i].proc();
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
if (_max_freq_div != 0) {
|
|
|
|
_timeslices_count++;
|
|
|
|
if (_timeslices_count == _max_freq_div) {
|
|
|
|
_timeslices_count = 0;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
2014-08-20 18:49:49 -03:00
|
|
|
_timer_semaphore.give();
|
2013-09-28 01:59:00 -03:00
|
|
|
|
|
|
|
// and the failsafe, if one is setup
|
|
|
|
if (_failsafe != NULL) {
|
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::_timer_thread(void* arg)
|
2013-09-28 01:59:00 -03:00
|
|
|
{
|
2015-10-20 18:13:25 -03:00
|
|
|
Scheduler* sched = (Scheduler *)arg;
|
2015-03-18 17:23:37 -03:00
|
|
|
|
|
|
|
while (sched->system_initializing()) {
|
|
|
|
poll(NULL, 0, 1);
|
2013-10-26 04:25:27 -03:00
|
|
|
}
|
2015-12-13 23:19:54 -04:00
|
|
|
|
|
|
|
#if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_QFLIGHT
|
|
|
|
printf("Initialising rpcmem\n");
|
|
|
|
rpcmem_init();
|
|
|
|
#endif
|
|
|
|
|
|
|
|
/*
|
2014-08-19 07:03:15 -03:00
|
|
|
this aims to run at an average of 1kHz, so that it can be used
|
|
|
|
to drive 1kHz processes without drift
|
|
|
|
*/
|
2015-11-11 10:02:43 -04:00
|
|
|
uint64_t next_run_usec = AP_HAL::micros64() + 1000;
|
2013-09-28 01:59:00 -03:00
|
|
|
while (true) {
|
2015-11-11 10:02:43 -04:00
|
|
|
uint64_t dt = next_run_usec - AP_HAL::micros64();
|
2014-08-19 07:03:15 -03:00
|
|
|
if (dt > 2000) {
|
|
|
|
// we've lost sync - restart
|
2015-11-11 10:02:43 -04:00
|
|
|
next_run_usec = AP_HAL::micros64();
|
2014-08-19 07:03:15 -03:00
|
|
|
} else {
|
2015-03-18 17:23:37 -03:00
|
|
|
sched->_microsleep(dt);
|
2014-08-19 07:03:15 -03:00
|
|
|
}
|
|
|
|
next_run_usec += 1000;
|
2013-09-28 01:59:00 -03:00
|
|
|
// run registered timers
|
2015-03-18 17:23:37 -03:00
|
|
|
sched->_run_timers(true);
|
2015-12-13 23:19:54 -04:00
|
|
|
|
|
|
|
#if HAL_LINUX_UARTS_ON_TIMER_THREAD
|
|
|
|
/*
|
|
|
|
some boards require that UART calls happen on the same
|
|
|
|
thread as other calls of the same time. This impacts the
|
|
|
|
QFLIGHT calls where UART output is an RPC call to the DSPs
|
|
|
|
*/
|
|
|
|
_run_uarts();
|
|
|
|
RCInput::from(hal.rcin)->_timer_tick();
|
|
|
|
#endif
|
2013-09-28 01:59:00 -03:00
|
|
|
}
|
|
|
|
return NULL;
|
|
|
|
}
|
|
|
|
|
2015-10-20 18:13:25 -03:00
|
|
|
void Scheduler::_run_io(void)
|
2013-09-28 01:59:00 -03:00
|
|
|
{
|
2014-12-07 20:24:39 -04:00
|
|
|
if (!_io_semaphore.take(0)) {
|
2013-09-28 01:59:00 -03:00
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
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-10-20 18:13:25 -03:00
|
|
|
void *Scheduler::_rcin_thread(void *arg)
|
2014-08-14 13:48:17 -03:00
|
|
|
{
|
2015-10-20 18:13:25 -03:00
|
|
|
Scheduler* sched = (Scheduler *)arg;
|
2015-03-18 17:23:37 -03:00
|
|
|
|
|
|
|
while (sched->system_initializing()) {
|
|
|
|
poll(NULL, 0, 1);
|
2014-08-14 13:48:17 -03:00
|
|
|
}
|
|
|
|
while (true) {
|
2015-04-16 12:19:19 -03:00
|
|
|
sched->_microsleep(APM_LINUX_RCIN_PERIOD);
|
2015-12-13 23:19:54 -04:00
|
|
|
#if !HAL_LINUX_UARTS_ON_TIMER_THREAD
|
2015-10-20 18:13:25 -03:00
|
|
|
RCInput::from(hal.rcin)->_timer_tick();
|
2015-12-13 23:19:54 -04:00
|
|
|
#endif
|
2014-08-14 13:48:17 -03:00
|
|
|
}
|
|
|
|
return NULL;
|
|
|
|
}
|
|
|
|
|
2015-12-13 23:19:54 -04:00
|
|
|
|
|
|
|
/*
|
|
|
|
run timers for all UARTs
|
|
|
|
*/
|
|
|
|
void Scheduler::_run_uarts(void)
|
|
|
|
{
|
|
|
|
// process any pending serial bytes
|
|
|
|
UARTDriver::from(hal.uartA)->_timer_tick();
|
|
|
|
UARTDriver::from(hal.uartB)->_timer_tick();
|
|
|
|
#if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_RASPILOT
|
|
|
|
//SPI UART not use SPI
|
|
|
|
if (RPIOUARTDriver::from(hal.uartC)->isExternal()) {
|
|
|
|
RPIOUARTDriver::from(hal.uartC)->_timer_tick();
|
|
|
|
}
|
|
|
|
#else
|
|
|
|
UARTDriver::from(hal.uartC)->_timer_tick();
|
|
|
|
#endif
|
|
|
|
UARTDriver::from(hal.uartE)->_timer_tick();
|
|
|
|
}
|
|
|
|
|
2015-10-20 18:13:25 -03:00
|
|
|
void *Scheduler::_uart_thread(void* arg)
|
2013-09-28 01:59:00 -03:00
|
|
|
{
|
2015-10-20 18:13:25 -03:00
|
|
|
Scheduler* sched = (Scheduler *)arg;
|
2015-03-18 17:23:37 -03:00
|
|
|
|
|
|
|
while (sched->system_initializing()) {
|
|
|
|
poll(NULL, 0, 1);
|
2013-10-26 04:25:27 -03:00
|
|
|
}
|
2013-09-28 01:59:00 -03:00
|
|
|
while (true) {
|
2015-04-16 12:19:19 -03:00
|
|
|
sched->_microsleep(APM_LINUX_UART_PERIOD);
|
2015-12-13 23:19:54 -04:00
|
|
|
#if !HAL_LINUX_UARTS_ON_TIMER_THREAD
|
|
|
|
_run_uarts();
|
2015-08-17 23:39:02 -03:00
|
|
|
#endif
|
2013-09-28 01:59:00 -03:00
|
|
|
}
|
|
|
|
return NULL;
|
|
|
|
}
|
|
|
|
|
2015-10-20 18:13:25 -03:00
|
|
|
void *Scheduler::_tonealarm_thread(void* arg)
|
2014-08-23 04:52:43 -03:00
|
|
|
{
|
2015-10-20 18:13:25 -03:00
|
|
|
Scheduler* sched = (Scheduler *)arg;
|
2015-03-18 17:23:37 -03:00
|
|
|
|
|
|
|
while (sched->system_initializing()) {
|
|
|
|
poll(NULL, 0, 1);
|
2014-08-23 04:52:43 -03:00
|
|
|
}
|
|
|
|
while (true) {
|
2015-04-16 12:19:19 -03:00
|
|
|
sched->_microsleep(APM_LINUX_TONEALARM_PERIOD);
|
2014-08-23 04:52:43 -03:00
|
|
|
|
|
|
|
// process tone command
|
2015-10-20 18:13:25 -03:00
|
|
|
Util::from(hal.util)->_toneAlarm_timer_tick();
|
2014-08-23 04:52:43 -03:00
|
|
|
}
|
|
|
|
return NULL;
|
|
|
|
}
|
|
|
|
|
2015-10-20 18:13:25 -03:00
|
|
|
void *Scheduler::_io_thread(void* arg)
|
2013-09-28 01:59:00 -03:00
|
|
|
{
|
2015-10-20 18:13:25 -03:00
|
|
|
Scheduler* sched = (Scheduler *)arg;
|
2015-03-18 17:23:37 -03:00
|
|
|
|
|
|
|
while (sched->system_initializing()) {
|
|
|
|
poll(NULL, 0, 1);
|
2013-10-26 04:25:27 -03:00
|
|
|
}
|
2013-09-28 01:59:00 -03:00
|
|
|
while (true) {
|
2015-04-16 12:19:19 -03:00
|
|
|
sched->_microsleep(APM_LINUX_IO_PERIOD);
|
2013-09-28 01:59:00 -03:00
|
|
|
|
|
|
|
// process any pending storage writes
|
2015-10-20 18:13:25 -03:00
|
|
|
Storage::from(hal.storage)->_timer_tick();
|
2013-09-28 01:59:00 -03:00
|
|
|
|
2015-04-16 12:19:19 -03:00
|
|
|
// run registered IO procepsses
|
2015-03-18 17:23:37 -03:00
|
|
|
sched->_run_io();
|
2013-09-28 01:59:00 -03:00
|
|
|
}
|
|
|
|
return NULL;
|
|
|
|
}
|
|
|
|
|
2015-10-20 18:13:25 -03:00
|
|
|
bool Scheduler::in_timerprocess()
|
2013-09-28 01:59:00 -03:00
|
|
|
{
|
|
|
|
return _in_timer_proc;
|
2013-09-22 03:01:24 -03:00
|
|
|
}
|
|
|
|
|
2015-10-20 18:13:25 -03:00
|
|
|
void Scheduler::begin_atomic()
|
2013-09-22 03:01:24 -03:00
|
|
|
{}
|
|
|
|
|
2015-10-20 18:13:25 -03:00
|
|
|
void Scheduler::end_atomic()
|
2013-09-22 03:01:24 -03:00
|
|
|
{}
|
|
|
|
|
2015-10-20 18:13:25 -03:00
|
|
|
bool Scheduler::system_initializing() {
|
2013-09-28 01:59:00 -03:00
|
|
|
return !_initialized;
|
2013-09-22 03:01:24 -03:00
|
|
|
}
|
|
|
|
|
2015-10-20 18:13:25 -03:00
|
|
|
void Scheduler::system_initialized()
|
2013-09-28 01:59:00 -03:00
|
|
|
{
|
|
|
|
if (_initialized) {
|
2015-11-11 10:02:43 -04:00
|
|
|
AP_HAL::panic("PANIC: scheduler::system_initialized called more than once");
|
2013-09-28 01:59:00 -03:00
|
|
|
}
|
|
|
|
_initialized = true;
|
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
|
|
|
|
2015-10-20 18:13:25 -03:00
|
|
|
void Scheduler::stop_clock(uint64_t time_usec)
|
2013-12-29 18:31:33 -04:00
|
|
|
{
|
2015-11-11 10:02:43 -04:00
|
|
|
if (time_usec >= _stopped_clock_usec) {
|
|
|
|
_stopped_clock_usec = time_usec;
|
2015-04-20 01:04:23 -03:00
|
|
|
_run_io();
|
|
|
|
}
|
2013-12-31 05:05:07 -04:00
|
|
|
}
|
|
|
|
|
2013-09-28 03:28:36 -03:00
|
|
|
#endif // CONFIG_HAL_BOARD
|