2015-08-11 03:28:43 -03:00
|
|
|
#include <AP_HAL/AP_HAL.h>
|
2015-05-04 03:15:12 -03:00
|
|
|
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
2012-12-12 18:04:27 -04:00
|
|
|
|
2015-05-04 03:15:12 -03:00
|
|
|
#include "AP_HAL_SITL.h"
|
2012-12-12 18:04:27 -04:00
|
|
|
#include "Scheduler.h"
|
2016-01-10 02:17:32 -04:00
|
|
|
#include "UARTDriver.h"
|
2012-12-12 18:04:27 -04:00
|
|
|
#include <sys/time.h>
|
2014-11-15 20:04:55 -04:00
|
|
|
#include <fenv.h>
|
2012-12-12 18:04:27 -04:00
|
|
|
|
2015-05-04 03:15:12 -03:00
|
|
|
using namespace HALSITL;
|
2012-12-12 18:04:27 -04:00
|
|
|
|
|
|
|
extern const AP_HAL::HAL& hal;
|
|
|
|
|
|
|
|
|
2016-10-30 02:24:21 -03:00
|
|
|
AP_HAL::Proc Scheduler::_failsafe = nullptr;
|
2016-01-10 02:23:32 -04:00
|
|
|
volatile bool Scheduler::_timer_suspended = false;
|
|
|
|
volatile bool Scheduler::_timer_event_missed = false;
|
2013-04-17 08:33:50 -03:00
|
|
|
|
2016-10-30 02:24:21 -03:00
|
|
|
AP_HAL::MemberProc Scheduler::_timer_proc[SITL_SCHEDULER_MAX_TIMER_PROCS] = {nullptr};
|
2016-01-10 02:23:32 -04:00
|
|
|
uint8_t Scheduler::_num_timer_procs = 0;
|
|
|
|
bool Scheduler::_in_timer_proc = false;
|
2013-04-17 08:33:50 -03:00
|
|
|
|
2016-10-30 02:24:21 -03:00
|
|
|
AP_HAL::MemberProc Scheduler::_io_proc[SITL_SCHEDULER_MAX_TIMER_PROCS] = {nullptr};
|
2016-01-10 02:23:32 -04:00
|
|
|
uint8_t Scheduler::_num_io_procs = 0;
|
|
|
|
bool Scheduler::_in_io_proc = false;
|
2013-04-17 08:33:50 -03:00
|
|
|
|
2016-01-10 02:23:32 -04:00
|
|
|
Scheduler::Scheduler(SITL_State *sitlState) :
|
2015-03-21 11:27:25 -03:00
|
|
|
_sitlState(sitlState),
|
2015-11-11 09:43:18 -04:00
|
|
|
_stopped_clock_usec(0)
|
2015-03-21 11:27:25 -03:00
|
|
|
{
|
|
|
|
}
|
2012-12-12 18:04:27 -04:00
|
|
|
|
2016-01-10 02:23:32 -04:00
|
|
|
void Scheduler::init()
|
2012-12-12 18:04:27 -04:00
|
|
|
{
|
|
|
|
}
|
|
|
|
|
2016-01-10 02:23:32 -04:00
|
|
|
void Scheduler::delay_microseconds(uint16_t usec)
|
2012-12-12 18:04:27 -04:00
|
|
|
{
|
2015-11-11 09:43:18 -04:00
|
|
|
uint64_t start = AP_HAL::micros64();
|
2016-12-02 06:16:57 -04:00
|
|
|
do {
|
|
|
|
uint64_t dtime = AP_HAL::micros64() - start;
|
|
|
|
if (dtime >= usec) {
|
|
|
|
break;
|
|
|
|
}
|
2017-01-09 08:33:52 -04:00
|
|
|
_sitlState->wait_clock(start + usec);
|
2016-12-02 06:16:57 -04:00
|
|
|
} while (true);
|
2012-12-12 18:04:27 -04:00
|
|
|
}
|
|
|
|
|
2016-01-10 02:23:32 -04:00
|
|
|
void Scheduler::delay(uint16_t ms)
|
2012-12-12 18:04:27 -04:00
|
|
|
{
|
|
|
|
while (ms > 0) {
|
2015-03-21 11:27:25 -03:00
|
|
|
delay_microseconds(1000);
|
|
|
|
ms--;
|
2012-12-12 18:04:27 -04:00
|
|
|
if (_min_delay_cb_ms <= ms) {
|
|
|
|
if (_delay_cb) {
|
|
|
|
_delay_cb();
|
|
|
|
}
|
|
|
|
}
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
2016-01-10 02:23:32 -04:00
|
|
|
void Scheduler::register_delay_callback(AP_HAL::Proc proc,
|
2015-05-04 21:59:07 -03:00
|
|
|
uint16_t min_time_ms)
|
2012-12-12 18:04:27 -04:00
|
|
|
{
|
|
|
|
_delay_cb = proc;
|
|
|
|
_min_delay_cb_ms = min_time_ms;
|
|
|
|
}
|
|
|
|
|
2016-01-10 02:23:32 -04:00
|
|
|
void Scheduler::register_timer_process(AP_HAL::MemberProc proc)
|
2012-12-12 18:04:27 -04:00
|
|
|
{
|
|
|
|
for (uint8_t i = 0; i < _num_timer_procs; i++) {
|
|
|
|
if (_timer_proc[i] == proc) {
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
if (_num_timer_procs < SITL_SCHEDULER_MAX_TIMER_PROCS) {
|
|
|
|
_timer_proc[_num_timer_procs] = proc;
|
|
|
|
_num_timer_procs++;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
2016-01-10 02:23:32 -04:00
|
|
|
void Scheduler::register_io_process(AP_HAL::MemberProc proc)
|
2013-04-17 08:33:50 -03:00
|
|
|
{
|
|
|
|
for (uint8_t i = 0; i < _num_io_procs; i++) {
|
|
|
|
if (_io_proc[i] == proc) {
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
if (_num_io_procs < SITL_SCHEDULER_MAX_TIMER_PROCS) {
|
|
|
|
_io_proc[_num_io_procs] = proc;
|
|
|
|
_num_io_procs++;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
2016-01-10 02:23:32 -04:00
|
|
|
void Scheduler::register_timer_failsafe(AP_HAL::Proc failsafe, uint32_t period_us)
|
2012-12-12 18:04:27 -04:00
|
|
|
{
|
|
|
|
_failsafe = failsafe;
|
|
|
|
}
|
|
|
|
|
2016-01-10 02:23:32 -04:00
|
|
|
void Scheduler::suspend_timer_procs() {
|
2012-12-12 18:04:27 -04:00
|
|
|
_timer_suspended = true;
|
|
|
|
}
|
|
|
|
|
2016-01-10 02:23:32 -04:00
|
|
|
void Scheduler::resume_timer_procs() {
|
2012-12-12 18:04:27 -04:00
|
|
|
_timer_suspended = false;
|
2013-01-03 21:32:52 -04:00
|
|
|
if (_timer_event_missed) {
|
|
|
|
_timer_event_missed = false;
|
|
|
|
_run_timer_procs(false);
|
2012-12-12 18:04:27 -04:00
|
|
|
}
|
|
|
|
}
|
|
|
|
|
2016-01-10 02:23:32 -04:00
|
|
|
bool Scheduler::in_timerprocess() {
|
2013-04-17 08:33:50 -03:00
|
|
|
return _in_timer_proc || _in_io_proc;
|
2013-01-10 17:50:32 -04:00
|
|
|
}
|
|
|
|
|
2016-01-10 02:23:32 -04:00
|
|
|
void Scheduler::system_initialized() {
|
2013-01-10 17:50:32 -04:00
|
|
|
if (_initialized) {
|
2015-11-11 09:43:18 -04:00
|
|
|
AP_HAL::panic(
|
2015-10-24 18:45:41 -03:00
|
|
|
"PANIC: scheduler system initialized called more than once");
|
2013-01-10 17:50:32 -04:00
|
|
|
}
|
2015-04-27 00:08:50 -03:00
|
|
|
int exceptions = FE_OVERFLOW | FE_DIVBYZERO;
|
|
|
|
#ifndef __i386__
|
|
|
|
// i386 with gcc doesn't work with FE_INVALID
|
|
|
|
exceptions |= FE_INVALID;
|
|
|
|
#endif
|
2016-10-30 02:24:21 -03:00
|
|
|
if (_sitlState->_sitl == nullptr || _sitlState->_sitl->float_exception) {
|
2015-04-27 00:08:50 -03:00
|
|
|
feenableexcept(exceptions);
|
2014-11-15 20:04:55 -04:00
|
|
|
} else {
|
2015-04-27 00:08:50 -03:00
|
|
|
feclearexcept(exceptions);
|
2014-11-15 20:04:55 -04:00
|
|
|
}
|
2013-01-10 17:50:32 -04:00
|
|
|
_initialized = true;
|
|
|
|
}
|
|
|
|
|
2016-01-10 02:23:32 -04:00
|
|
|
void Scheduler::sitl_end_atomic() {
|
2017-01-09 08:33:52 -04:00
|
|
|
if (_nested_atomic_ctr == 0) {
|
2017-01-21 00:54:43 -04:00
|
|
|
hal.uartA->printf("NESTED ATOMIC ERROR\n");
|
2017-01-09 08:33:52 -04:00
|
|
|
} else {
|
2013-01-03 21:32:52 -04:00
|
|
|
_nested_atomic_ctr--;
|
2017-01-09 08:33:52 -04:00
|
|
|
}
|
2015-05-04 21:59:07 -03:00
|
|
|
}
|
2013-01-03 21:32:52 -04:00
|
|
|
|
2016-01-10 02:23:32 -04:00
|
|
|
void Scheduler::reboot(bool hold_in_bootloader)
|
2012-12-12 18:04:27 -04:00
|
|
|
{
|
2017-01-21 00:54:43 -04:00
|
|
|
hal.uartA->printf("REBOOT NOT IMPLEMENTED\r\n\n");
|
2012-12-12 18:04:27 -04:00
|
|
|
}
|
|
|
|
|
2016-01-10 02:23:32 -04:00
|
|
|
void Scheduler::_run_timer_procs(bool called_from_isr)
|
2012-12-13 18:57:01 -04:00
|
|
|
{
|
|
|
|
if (_in_timer_proc) {
|
|
|
|
// the timer calls took longer than the period of the
|
|
|
|
// timer. This is bad, and may indicate a serious
|
|
|
|
// driver failure. We can't just call the drivers
|
|
|
|
// again, as we could run out of stack. So we only
|
|
|
|
// call the _failsafe call. It's job is to detect if
|
|
|
|
// the drivers or the main loop are indeed dead and to
|
|
|
|
// activate whatever failsafe it thinks may help if
|
|
|
|
// need be. We assume the failsafe code can't
|
|
|
|
// block. If it does then we will recurse and die when
|
|
|
|
// we run out of stack
|
2016-10-30 02:24:21 -03:00
|
|
|
if (_failsafe != nullptr) {
|
2013-09-30 07:35:42 -03:00
|
|
|
_failsafe();
|
2012-12-13 18:57:01 -04:00
|
|
|
}
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
_in_timer_proc = true;
|
|
|
|
|
|
|
|
if (!_timer_suspended) {
|
|
|
|
// now call the timer based drivers
|
|
|
|
for (int i = 0; i < _num_timer_procs; i++) {
|
2015-05-24 07:40:10 -03:00
|
|
|
if (_timer_proc[i]) {
|
2013-09-30 07:35:42 -03:00
|
|
|
_timer_proc[i]();
|
2012-12-13 18:57:01 -04:00
|
|
|
}
|
|
|
|
}
|
2013-01-03 21:32:52 -04:00
|
|
|
} else if (called_from_isr) {
|
|
|
|
_timer_event_missed = true;
|
2012-12-13 18:57:01 -04:00
|
|
|
}
|
|
|
|
|
|
|
|
// and the failsafe, if one is setup
|
2016-10-30 02:24:21 -03:00
|
|
|
if (_failsafe != nullptr) {
|
2015-03-24 12:02:47 -03:00
|
|
|
_failsafe();
|
2012-12-13 18:57:01 -04:00
|
|
|
}
|
|
|
|
|
|
|
|
_in_timer_proc = false;
|
|
|
|
}
|
|
|
|
|
2016-01-10 02:23:32 -04:00
|
|
|
void Scheduler::_run_io_procs(bool called_from_isr)
|
2013-04-17 08:33:50 -03:00
|
|
|
{
|
|
|
|
if (_in_io_proc) {
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
_in_io_proc = true;
|
|
|
|
|
|
|
|
if (!_timer_suspended) {
|
|
|
|
// now call the IO based drivers
|
|
|
|
for (int i = 0; i < _num_io_procs; i++) {
|
2015-05-24 07:40:10 -03:00
|
|
|
if (_io_proc[i]) {
|
2013-09-30 07:35:42 -03:00
|
|
|
_io_proc[i]();
|
2013-04-17 08:33:50 -03:00
|
|
|
}
|
|
|
|
}
|
|
|
|
} else if (called_from_isr) {
|
|
|
|
_timer_event_missed = true;
|
|
|
|
}
|
|
|
|
|
|
|
|
_in_io_proc = false;
|
2016-01-10 02:17:32 -04:00
|
|
|
|
2016-01-10 02:23:32 -04:00
|
|
|
UARTDriver::from(hal.uartA)->_timer_tick();
|
|
|
|
UARTDriver::from(hal.uartB)->_timer_tick();
|
|
|
|
UARTDriver::from(hal.uartC)->_timer_tick();
|
|
|
|
UARTDriver::from(hal.uartD)->_timer_tick();
|
|
|
|
UARTDriver::from(hal.uartE)->_timer_tick();
|
2017-06-23 16:45:26 -03:00
|
|
|
UARTDriver::from(hal.uartF)->_timer_tick();
|
2013-04-17 08:33:50 -03:00
|
|
|
}
|
|
|
|
|
2015-03-21 11:27:25 -03:00
|
|
|
/*
|
|
|
|
set simulation timestamp
|
|
|
|
*/
|
2016-01-10 02:23:32 -04:00
|
|
|
void Scheduler::stop_clock(uint64_t time_usec)
|
2015-03-21 11:27:25 -03:00
|
|
|
{
|
2015-11-11 09:43:18 -04:00
|
|
|
_stopped_clock_usec = time_usec;
|
2015-03-21 11:27:25 -03:00
|
|
|
_run_io_procs(false);
|
|
|
|
}
|
|
|
|
|
2012-12-12 18:04:27 -04:00
|
|
|
#endif
|