2016-09-27 11:46:23 -03:00
|
|
|
#include <AP_HAL/AP_HAL.h>
|
|
|
|
#if CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN
|
|
|
|
|
|
|
|
#include "AP_HAL_VRBRAIN.h"
|
|
|
|
#include "Scheduler.h"
|
|
|
|
|
|
|
|
#include <unistd.h>
|
|
|
|
#include <stdlib.h>
|
|
|
|
#include <sched.h>
|
|
|
|
#include <errno.h>
|
|
|
|
#include <stdio.h>
|
|
|
|
#include <drivers/drv_hrt.h>
|
|
|
|
#include <nuttx/arch.h>
|
|
|
|
#include <systemlib/systemlib.h>
|
|
|
|
#include <pthread.h>
|
|
|
|
#include <poll.h>
|
|
|
|
|
|
|
|
#include "UARTDriver.h"
|
|
|
|
#include "AnalogIn.h"
|
|
|
|
#include "Storage.h"
|
|
|
|
#include "RCOutput.h"
|
|
|
|
#include "RCInput.h"
|
2018-02-03 09:46:18 -04:00
|
|
|
|
2016-09-27 11:46:23 -03:00
|
|
|
#include <AP_Scheduler/AP_Scheduler.h>
|
2018-02-03 09:46:18 -04:00
|
|
|
#include <AP_BoardConfig/AP_BoardConfig.h>
|
|
|
|
|
|
|
|
#if HAL_WITH_UAVCAN
|
|
|
|
#include "CAN.h"
|
|
|
|
#include <AP_UAVCAN/AP_UAVCAN.h>
|
|
|
|
#endif
|
2016-09-27 11:46:23 -03:00
|
|
|
|
|
|
|
using namespace VRBRAIN;
|
|
|
|
|
|
|
|
extern const AP_HAL::HAL& hal;
|
|
|
|
|
|
|
|
extern bool _vrbrain_thread_should_exit;
|
|
|
|
|
|
|
|
VRBRAINScheduler::VRBRAINScheduler() :
|
|
|
|
_perf_timers(perf_alloc(PC_ELAPSED, "APM_timers")),
|
|
|
|
_perf_io_timers(perf_alloc(PC_ELAPSED, "APM_IO_timers")),
|
|
|
|
_perf_storage_timer(perf_alloc(PC_ELAPSED, "APM_storage_timers")),
|
2018-02-03 09:46:18 -04:00
|
|
|
_perf_delay(perf_alloc(PC_ELAPSED, "APM_delay"))
|
2016-09-27 11:46:23 -03:00
|
|
|
{}
|
|
|
|
|
|
|
|
void VRBRAINScheduler::init()
|
|
|
|
{
|
|
|
|
_main_task_pid = getpid();
|
|
|
|
|
|
|
|
// setup the timer thread - this will call tasks at 1kHz
|
2018-02-03 09:46:18 -04:00
|
|
|
pthread_attr_t thread_attr;
|
|
|
|
struct sched_param param;
|
2016-09-27 11:46:23 -03:00
|
|
|
|
2018-02-03 09:46:18 -04:00
|
|
|
pthread_attr_init(&thread_attr);
|
|
|
|
pthread_attr_setstacksize(&thread_attr, 2048);
|
2016-09-27 11:46:23 -03:00
|
|
|
|
2018-02-03 09:46:18 -04:00
|
|
|
param.sched_priority = APM_TIMER_PRIORITY;
|
|
|
|
(void)pthread_attr_setschedparam(&thread_attr, ¶m);
|
2016-09-27 11:46:23 -03:00
|
|
|
pthread_attr_setschedpolicy(&thread_attr, SCHED_FIFO);
|
|
|
|
|
|
|
|
pthread_create(&_timer_thread_ctx, &thread_attr, &VRBRAIN::VRBRAINScheduler::_timer_thread, this);
|
|
|
|
|
|
|
|
// the UART thread runs at a medium priority
|
2018-02-03 09:46:18 -04:00
|
|
|
pthread_attr_init(&thread_attr);
|
|
|
|
pthread_attr_setstacksize(&thread_attr, 2048);
|
2016-09-27 11:46:23 -03:00
|
|
|
|
2018-02-03 09:46:18 -04:00
|
|
|
param.sched_priority = APM_UART_PRIORITY;
|
|
|
|
(void)pthread_attr_setschedparam(&thread_attr, ¶m);
|
2016-09-27 11:46:23 -03:00
|
|
|
pthread_attr_setschedpolicy(&thread_attr, SCHED_FIFO);
|
|
|
|
|
|
|
|
pthread_create(&_uart_thread_ctx, &thread_attr, &VRBRAIN::VRBRAINScheduler::_uart_thread, this);
|
|
|
|
|
|
|
|
// the IO thread runs at lower priority
|
2018-02-03 09:46:18 -04:00
|
|
|
pthread_attr_init(&thread_attr);
|
|
|
|
pthread_attr_setstacksize(&thread_attr, 2048);
|
2016-09-27 11:46:23 -03:00
|
|
|
|
2018-02-03 09:46:18 -04:00
|
|
|
param.sched_priority = APM_IO_PRIORITY;
|
|
|
|
(void)pthread_attr_setschedparam(&thread_attr, ¶m);
|
2016-09-27 11:46:23 -03:00
|
|
|
pthread_attr_setschedpolicy(&thread_attr, SCHED_FIFO);
|
|
|
|
|
|
|
|
pthread_create(&_io_thread_ctx, &thread_attr, &VRBRAIN::VRBRAINScheduler::_io_thread, this);
|
|
|
|
|
|
|
|
// the storage thread runs at just above IO priority
|
|
|
|
pthread_attr_init(&thread_attr);
|
|
|
|
pthread_attr_setstacksize(&thread_attr, 1024);
|
|
|
|
|
|
|
|
param.sched_priority = APM_STORAGE_PRIORITY;
|
|
|
|
(void)pthread_attr_setschedparam(&thread_attr, ¶m);
|
|
|
|
pthread_attr_setschedpolicy(&thread_attr, SCHED_FIFO);
|
|
|
|
|
|
|
|
pthread_create(&_storage_thread_ctx, &thread_attr, &VRBRAIN::VRBRAINScheduler::_storage_thread, this);
|
|
|
|
}
|
|
|
|
|
2018-02-03 09:46:18 -04:00
|
|
|
void VRBRAINScheduler::create_uavcan_thread()
|
|
|
|
{
|
|
|
|
#if HAL_WITH_UAVCAN
|
|
|
|
pthread_attr_t thread_attr;
|
|
|
|
struct sched_param param;
|
|
|
|
|
|
|
|
//the UAVCAN thread runs at medium priority
|
|
|
|
pthread_attr_init(&thread_attr);
|
|
|
|
pthread_attr_setstacksize(&thread_attr, 8192);
|
|
|
|
|
|
|
|
param.sched_priority = APM_CAN_PRIORITY;
|
|
|
|
(void) pthread_attr_setschedparam(&thread_attr, ¶m);
|
|
|
|
pthread_attr_setschedpolicy(&thread_attr, SCHED_FIFO);
|
|
|
|
|
|
|
|
for (uint8_t i = 0; i < MAX_NUMBER_OF_CAN_DRIVERS; i++) {
|
2018-03-11 06:50:18 -03:00
|
|
|
if (AP_UAVCAN::get_uavcan(i) == nullptr) {
|
2018-03-09 04:31:06 -04:00
|
|
|
continue;
|
|
|
|
}
|
|
|
|
|
|
|
|
_uavcan_thread_arg *arg = new _uavcan_thread_arg;
|
|
|
|
arg->sched = this;
|
|
|
|
arg->uavcan_number = i;
|
|
|
|
|
|
|
|
pthread_create(&_uavcan_thread_ctx, &thread_attr, &VRBRAINScheduler::_uavcan_thread, arg);
|
2018-02-03 09:46:18 -04:00
|
|
|
}
|
|
|
|
#endif
|
|
|
|
}
|
|
|
|
|
2016-09-27 11:46:23 -03:00
|
|
|
/**
|
|
|
|
delay for a specified number of microseconds using a semaphore wait
|
|
|
|
*/
|
|
|
|
void VRBRAINScheduler::delay_microseconds_semaphore(uint16_t usec)
|
|
|
|
{
|
|
|
|
sem_t wait_semaphore;
|
|
|
|
struct hrt_call wait_call;
|
|
|
|
sem_init(&wait_semaphore, 0, 0);
|
|
|
|
memset(&wait_call, 0, sizeof(wait_call));
|
|
|
|
hrt_call_after(&wait_call, usec, (hrt_callout)sem_post, &wait_semaphore);
|
|
|
|
sem_wait(&wait_semaphore);
|
|
|
|
}
|
|
|
|
|
|
|
|
void VRBRAINScheduler::delay_microseconds(uint16_t usec)
|
|
|
|
{
|
|
|
|
perf_begin(_perf_delay);
|
|
|
|
delay_microseconds_semaphore(usec);
|
|
|
|
perf_end(_perf_delay);
|
|
|
|
}
|
|
|
|
|
|
|
|
/*
|
|
|
|
wrapper around sem_post that boosts main thread priority
|
|
|
|
*/
|
|
|
|
static void sem_post_boost(sem_t *sem)
|
|
|
|
{
|
|
|
|
hal_vrbrain_set_priority(APM_MAIN_PRIORITY_BOOST);
|
|
|
|
sem_post(sem);
|
|
|
|
}
|
|
|
|
|
|
|
|
/*
|
|
|
|
return the main thread to normal priority
|
|
|
|
*/
|
|
|
|
static void set_normal_priority(void *sem)
|
|
|
|
{
|
|
|
|
hal_vrbrain_set_priority(APM_MAIN_PRIORITY);
|
|
|
|
}
|
|
|
|
|
|
|
|
/*
|
|
|
|
a variant of delay_microseconds that boosts priority to
|
|
|
|
APM_MAIN_PRIORITY_BOOST for APM_MAIN_PRIORITY_BOOST_USEC
|
|
|
|
microseconds when the time completes. This significantly improves
|
2018-02-03 09:46:18 -04:00
|
|
|
the regularity of timing of the main loop as it takes
|
2016-09-27 11:46:23 -03:00
|
|
|
*/
|
|
|
|
void VRBRAINScheduler::delay_microseconds_boost(uint16_t usec)
|
|
|
|
{
|
|
|
|
sem_t wait_semaphore;
|
|
|
|
static struct hrt_call wait_call;
|
|
|
|
sem_init(&wait_semaphore, 0, 0);
|
|
|
|
hrt_call_after(&wait_call, usec, (hrt_callout)sem_post_boost, &wait_semaphore);
|
|
|
|
sem_wait(&wait_semaphore);
|
2016-10-30 02:24:21 -03:00
|
|
|
hrt_call_after(&wait_call, APM_MAIN_PRIORITY_BOOST_USEC, (hrt_callout)set_normal_priority, nullptr);
|
2016-09-27 11:46:23 -03:00
|
|
|
}
|
|
|
|
|
|
|
|
void VRBRAINScheduler::delay(uint16_t ms)
|
|
|
|
{
|
2017-08-02 05:46:17 -03:00
|
|
|
if (!in_main_thread()) {
|
2016-09-27 11:46:23 -03:00
|
|
|
::printf("ERROR: delay() from timer process\n");
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
perf_begin(_perf_delay);
|
2018-02-03 09:46:18 -04:00
|
|
|
uint64_t start = AP_HAL::micros64();
|
|
|
|
|
|
|
|
while ((AP_HAL::micros64() - start)/1000 < ms &&
|
2016-09-27 11:46:23 -03:00
|
|
|
!_vrbrain_thread_should_exit) {
|
|
|
|
delay_microseconds_semaphore(1000);
|
|
|
|
if (_min_delay_cb_ms <= ms) {
|
2018-05-08 02:56:32 -03:00
|
|
|
call_delay_cb();
|
2016-09-27 11:46:23 -03:00
|
|
|
}
|
|
|
|
}
|
|
|
|
perf_end(_perf_delay);
|
|
|
|
if (_vrbrain_thread_should_exit) {
|
|
|
|
exit(1);
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
void VRBRAINScheduler::register_timer_process(AP_HAL::MemberProc proc)
|
|
|
|
{
|
|
|
|
for (uint8_t i = 0; i < _num_timer_procs; i++) {
|
|
|
|
if (_timer_proc[i] == proc) {
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
if (_num_timer_procs < VRBRAIN_SCHEDULER_MAX_TIMER_PROCS) {
|
|
|
|
_timer_proc[_num_timer_procs] = proc;
|
|
|
|
_num_timer_procs++;
|
|
|
|
} else {
|
|
|
|
hal.console->printf("Out of timer processes\n");
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
void VRBRAINScheduler::register_io_process(AP_HAL::MemberProc proc)
|
|
|
|
{
|
|
|
|
for (uint8_t i = 0; i < _num_io_procs; i++) {
|
|
|
|
if (_io_proc[i] == proc) {
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
if (_num_io_procs < VRBRAIN_SCHEDULER_MAX_TIMER_PROCS) {
|
|
|
|
_io_proc[_num_io_procs] = proc;
|
|
|
|
_num_io_procs++;
|
|
|
|
} else {
|
|
|
|
hal.console->printf("Out of IO processes\n");
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
void VRBRAINScheduler::register_timer_failsafe(AP_HAL::Proc failsafe, uint32_t period_us)
|
|
|
|
{
|
|
|
|
_failsafe = failsafe;
|
|
|
|
}
|
|
|
|
|
|
|
|
void VRBRAINScheduler::reboot(bool hold_in_bootloader)
|
|
|
|
{
|
|
|
|
// disarm motors to ensure they are off during a bootloader upload
|
|
|
|
hal.rcout->force_safety_on();
|
|
|
|
hal.rcout->force_safety_no_wait();
|
|
|
|
|
|
|
|
// delay to ensure the async force_saftey operation completes
|
|
|
|
delay(500);
|
|
|
|
|
2018-02-03 09:46:18 -04:00
|
|
|
px4_systemreset(hold_in_bootloader);
|
2016-09-27 11:46:23 -03:00
|
|
|
}
|
|
|
|
|
2018-05-13 19:47:35 -03:00
|
|
|
void VRBRAINScheduler::_run_timers()
|
2016-09-27 11:46:23 -03:00
|
|
|
{
|
|
|
|
if (_in_timer_proc) {
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
_in_timer_proc = true;
|
|
|
|
|
2018-05-13 19:47:35 -03:00
|
|
|
// now call the timer based drivers
|
|
|
|
for (int i = 0; i < _num_timer_procs; i++) {
|
|
|
|
if (_timer_proc[i]) {
|
|
|
|
_timer_proc[i]();
|
2016-09-27 11:46:23 -03:00
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
// and the failsafe, if one is setup
|
2016-10-30 02:24:21 -03:00
|
|
|
if (_failsafe != nullptr) {
|
2016-09-27 11:46:23 -03:00
|
|
|
_failsafe();
|
|
|
|
}
|
|
|
|
|
|
|
|
// process analog input
|
|
|
|
((VRBRAINAnalogIn *)hal.analogin)->_timer_tick();
|
|
|
|
|
|
|
|
_in_timer_proc = false;
|
|
|
|
}
|
|
|
|
|
|
|
|
extern bool vrbrain_ran_overtime;
|
|
|
|
|
|
|
|
void *VRBRAINScheduler::_timer_thread(void *arg)
|
|
|
|
{
|
|
|
|
VRBRAINScheduler *sched = (VRBRAINScheduler *)arg;
|
|
|
|
uint32_t last_ran_overtime = 0;
|
|
|
|
|
2018-02-03 09:46:18 -04:00
|
|
|
pthread_setname_np(pthread_self(), "apm_timer");
|
|
|
|
|
2016-09-27 11:46:23 -03:00
|
|
|
while (!sched->_hal_initialized) {
|
2016-10-30 02:24:21 -03:00
|
|
|
poll(nullptr, 0, 1);
|
2016-09-27 11:46:23 -03:00
|
|
|
}
|
|
|
|
while (!_vrbrain_thread_should_exit) {
|
|
|
|
sched->delay_microseconds_semaphore(1000);
|
|
|
|
|
|
|
|
// run registered timers
|
|
|
|
perf_begin(sched->_perf_timers);
|
2018-05-13 19:47:35 -03:00
|
|
|
sched->_run_timers();
|
2016-09-27 11:46:23 -03:00
|
|
|
perf_end(sched->_perf_timers);
|
|
|
|
|
|
|
|
// process any pending RC output requests
|
2018-02-03 09:46:18 -04:00
|
|
|
hal.rcout->timer_tick();
|
2016-09-27 11:46:23 -03:00
|
|
|
|
|
|
|
// process any pending RC input requests
|
|
|
|
((VRBRAINRCInput *)hal.rcin)->_timer_tick();
|
|
|
|
|
|
|
|
if (vrbrain_ran_overtime && AP_HAL::millis() - last_ran_overtime > 2000) {
|
|
|
|
last_ran_overtime = AP_HAL::millis();
|
|
|
|
#if 0
|
|
|
|
printf("Overtime in task %d\n", (int)AP_Scheduler::current_task);
|
|
|
|
hal.console->printf("Overtime in task %d\n", (int)AP_Scheduler::current_task);
|
|
|
|
#endif
|
|
|
|
}
|
|
|
|
}
|
2016-10-30 02:24:21 -03:00
|
|
|
return nullptr;
|
2016-09-27 11:46:23 -03:00
|
|
|
}
|
|
|
|
|
|
|
|
void VRBRAINScheduler::_run_io(void)
|
|
|
|
{
|
|
|
|
if (_in_io_proc) {
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
_in_io_proc = true;
|
|
|
|
|
2018-05-13 19:47:35 -03:00
|
|
|
// now call the IO based drivers
|
|
|
|
for (int i = 0; i < _num_io_procs; i++) {
|
|
|
|
if (_io_proc[i]) {
|
|
|
|
_io_proc[i]();
|
2016-09-27 11:46:23 -03:00
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
_in_io_proc = false;
|
|
|
|
}
|
|
|
|
|
|
|
|
void *VRBRAINScheduler::_uart_thread(void *arg)
|
|
|
|
{
|
|
|
|
VRBRAINScheduler *sched = (VRBRAINScheduler *)arg;
|
|
|
|
|
2018-02-03 09:46:18 -04:00
|
|
|
pthread_setname_np(pthread_self(), "apm_uart");
|
|
|
|
|
2016-09-27 11:46:23 -03:00
|
|
|
while (!sched->_hal_initialized) {
|
2016-10-30 02:24:21 -03:00
|
|
|
poll(nullptr, 0, 1);
|
2016-09-27 11:46:23 -03:00
|
|
|
}
|
|
|
|
while (!_vrbrain_thread_should_exit) {
|
|
|
|
sched->delay_microseconds_semaphore(1000);
|
|
|
|
|
|
|
|
// process any pending serial bytes
|
2018-01-21 15:45:31 -04:00
|
|
|
hal.uartA->_timer_tick();
|
|
|
|
hal.uartB->_timer_tick();
|
|
|
|
hal.uartC->_timer_tick();
|
|
|
|
hal.uartD->_timer_tick();
|
|
|
|
hal.uartE->_timer_tick();
|
|
|
|
hal.uartF->_timer_tick();
|
2016-09-27 11:46:23 -03:00
|
|
|
}
|
2016-10-30 02:24:21 -03:00
|
|
|
return nullptr;
|
2016-09-27 11:46:23 -03:00
|
|
|
}
|
|
|
|
|
|
|
|
void *VRBRAINScheduler::_io_thread(void *arg)
|
|
|
|
{
|
|
|
|
VRBRAINScheduler *sched = (VRBRAINScheduler *)arg;
|
|
|
|
|
2018-02-03 09:46:18 -04:00
|
|
|
pthread_setname_np(pthread_self(), "apm_io");
|
|
|
|
|
2016-09-27 11:46:23 -03:00
|
|
|
while (!sched->_hal_initialized) {
|
2016-10-30 02:24:21 -03:00
|
|
|
poll(nullptr, 0, 1);
|
2016-09-27 11:46:23 -03:00
|
|
|
}
|
|
|
|
while (!_vrbrain_thread_should_exit) {
|
2018-02-03 09:46:18 -04:00
|
|
|
sched->delay_microseconds_semaphore(1000);
|
2016-09-27 11:46:23 -03:00
|
|
|
|
|
|
|
// run registered IO processes
|
|
|
|
perf_begin(sched->_perf_io_timers);
|
|
|
|
sched->_run_io();
|
|
|
|
perf_end(sched->_perf_io_timers);
|
|
|
|
}
|
2016-10-30 02:24:21 -03:00
|
|
|
return nullptr;
|
2016-09-27 11:46:23 -03:00
|
|
|
}
|
|
|
|
|
|
|
|
void *VRBRAINScheduler::_storage_thread(void *arg)
|
|
|
|
{
|
|
|
|
VRBRAINScheduler *sched = (VRBRAINScheduler *)arg;
|
|
|
|
|
2018-02-03 09:46:18 -04:00
|
|
|
pthread_setname_np(pthread_self(), "apm_storage");
|
|
|
|
|
2016-09-27 11:46:23 -03:00
|
|
|
while (!sched->_hal_initialized) {
|
2016-10-30 02:24:21 -03:00
|
|
|
poll(nullptr, 0, 1);
|
2016-09-27 11:46:23 -03:00
|
|
|
}
|
|
|
|
while (!_vrbrain_thread_should_exit) {
|
2018-02-03 09:46:18 -04:00
|
|
|
sched->delay_microseconds_semaphore(10000);
|
2016-09-27 11:46:23 -03:00
|
|
|
|
|
|
|
// process any pending storage writes
|
|
|
|
perf_begin(sched->_perf_storage_timer);
|
2018-01-26 22:32:19 -04:00
|
|
|
hal.storage->_timer_tick();
|
2016-09-27 11:46:23 -03:00
|
|
|
perf_end(sched->_perf_storage_timer);
|
|
|
|
}
|
2016-10-30 02:24:21 -03:00
|
|
|
return nullptr;
|
2016-09-27 11:46:23 -03:00
|
|
|
}
|
|
|
|
|
2018-02-03 09:46:18 -04:00
|
|
|
#if HAL_WITH_UAVCAN
|
|
|
|
void *VRBRAINScheduler::_uavcan_thread(void *arg)
|
|
|
|
{
|
|
|
|
VRBRAINScheduler *sched = ((_uavcan_thread_arg *) arg)->sched;
|
|
|
|
uint8_t uavcan_number = ((_uavcan_thread_arg *) arg)->uavcan_number;
|
|
|
|
|
|
|
|
char name[15];
|
|
|
|
snprintf(name, sizeof(name), "apm_uavcan:%u", uavcan_number);
|
|
|
|
pthread_setname_np(pthread_self(), name);
|
|
|
|
|
|
|
|
while (!sched->_hal_initialized) {
|
|
|
|
poll(nullptr, 0, 1);
|
|
|
|
}
|
|
|
|
|
|
|
|
while (!_px4_thread_should_exit) {
|
|
|
|
if (((VRBRAINCANManager *)hal.can_mgr[uavcan_number])->is_initialized()) {
|
|
|
|
if (((VRBRAINCANManager *)hal.can_mgr[uavcan_number])->get_UAVCAN() != nullptr) {
|
|
|
|
(((VRBRAINCANManager *)hal.can_mgr[uavcan_number])->get_UAVCAN())->do_cyclic();
|
|
|
|
} else {
|
|
|
|
sched->delay_microseconds_semaphore(10000);
|
|
|
|
}
|
|
|
|
} else {
|
|
|
|
sched->delay_microseconds_semaphore(10000);
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
return nullptr;
|
|
|
|
}
|
|
|
|
#endif
|
|
|
|
|
2017-09-17 22:30:31 -03:00
|
|
|
bool VRBRAINScheduler::in_main_thread() const
|
2017-08-02 05:46:17 -03:00
|
|
|
{
|
|
|
|
return getpid() == _main_task_pid;
|
|
|
|
}
|
|
|
|
|
2018-02-03 09:46:18 -04:00
|
|
|
void VRBRAINScheduler::system_initialized()
|
|
|
|
{
|
2016-09-27 11:46:23 -03:00
|
|
|
if (_initialized) {
|
|
|
|
AP_HAL::panic("PANIC: scheduler::system_initialized called"
|
2018-02-03 09:46:18 -04:00
|
|
|
"more than once");
|
2016-09-27 11:46:23 -03:00
|
|
|
}
|
|
|
|
_initialized = true;
|
|
|
|
}
|
|
|
|
|
|
|
|
#endif
|