2018-01-05 02:19:51 -04:00
|
|
|
/*
|
|
|
|
* 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/>.
|
|
|
|
*
|
|
|
|
* Code by Andrew Tridgell and Siddharth Bharat Purohit
|
|
|
|
*/
|
|
|
|
#include <AP_HAL/AP_HAL.h>
|
|
|
|
#if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
|
|
|
|
|
|
|
|
#include "AP_HAL_ChibiOS.h"
|
|
|
|
#include "Scheduler.h"
|
2018-01-28 14:31:21 -04:00
|
|
|
#include "Util.h"
|
2018-01-05 02:19:51 -04:00
|
|
|
|
|
|
|
#include <AP_HAL_ChibiOS/UARTDriver.h>
|
|
|
|
#include <AP_HAL_ChibiOS/AnalogIn.h>
|
|
|
|
#include <AP_HAL_ChibiOS/Storage.h>
|
|
|
|
#include <AP_HAL_ChibiOS/RCOutput.h>
|
|
|
|
#include <AP_HAL_ChibiOS/RCInput.h>
|
2018-02-01 15:21:18 -04:00
|
|
|
#include <AP_HAL_ChibiOS/CAN.h>
|
2018-01-05 02:19:51 -04:00
|
|
|
|
|
|
|
#include <AP_Scheduler/AP_Scheduler.h>
|
|
|
|
#include <AP_BoardConfig/AP_BoardConfig.h>
|
2018-01-28 21:43:55 -04:00
|
|
|
#include "shared_dma.h"
|
2018-01-05 02:19:51 -04:00
|
|
|
|
|
|
|
using namespace ChibiOS;
|
|
|
|
|
|
|
|
extern const AP_HAL::HAL& hal;
|
|
|
|
THD_WORKING_AREA(_timer_thread_wa, 2048);
|
2018-01-18 15:12:38 -04:00
|
|
|
THD_WORKING_AREA(_rcin_thread_wa, 512);
|
2018-02-11 23:53:41 -04:00
|
|
|
#ifdef HAL_PWM_ALARM
|
2018-02-01 11:25:03 -04:00
|
|
|
THD_WORKING_AREA(_toneAlarm_thread_wa, 512);
|
2018-02-11 23:53:41 -04:00
|
|
|
#endif
|
2018-01-05 02:19:51 -04:00
|
|
|
THD_WORKING_AREA(_io_thread_wa, 2048);
|
|
|
|
THD_WORKING_AREA(_storage_thread_wa, 2048);
|
2018-02-02 06:17:58 -04:00
|
|
|
#if HAL_WITH_UAVCAN
|
2018-02-01 15:53:29 -04:00
|
|
|
THD_WORKING_AREA(_uavcan_thread_wa, 4096);
|
2018-02-01 15:21:18 -04:00
|
|
|
#endif
|
2018-01-05 02:19:51 -04:00
|
|
|
|
2018-01-13 00:02:05 -04:00
|
|
|
Scheduler::Scheduler()
|
2018-01-05 02:19:51 -04:00
|
|
|
{}
|
|
|
|
|
2018-01-13 00:02:05 -04:00
|
|
|
void Scheduler::init()
|
2018-01-05 02:19:51 -04:00
|
|
|
{
|
2018-04-02 23:25:42 -03:00
|
|
|
chVTObjectInit(&_boost_timer);
|
|
|
|
|
2018-01-05 02:19:51 -04:00
|
|
|
// setup the timer thread - this will call tasks at 1kHz
|
|
|
|
_timer_thread_ctx = chThdCreateStatic(_timer_thread_wa,
|
|
|
|
sizeof(_timer_thread_wa),
|
|
|
|
APM_TIMER_PRIORITY, /* Initial priority. */
|
|
|
|
_timer_thread, /* Thread function. */
|
|
|
|
this); /* Thread parameter. */
|
|
|
|
|
2018-02-09 23:55:22 -04:00
|
|
|
// setup the uavcan thread - this will call tasks at 1kHz
|
2018-02-02 06:17:58 -04:00
|
|
|
#if HAL_WITH_UAVCAN
|
2018-02-01 15:21:18 -04:00
|
|
|
_uavcan_thread_ctx = chThdCreateStatic(_uavcan_thread_wa,
|
|
|
|
sizeof(_uavcan_thread_wa),
|
|
|
|
APM_UAVCAN_PRIORITY, /* Initial priority. */
|
|
|
|
_uavcan_thread, /* Thread function. */
|
|
|
|
this); /* Thread parameter. */
|
|
|
|
#endif
|
2018-01-18 15:12:38 -04:00
|
|
|
// setup the RCIN thread - this will call tasks at 1kHz
|
|
|
|
_rcin_thread_ctx = chThdCreateStatic(_rcin_thread_wa,
|
|
|
|
sizeof(_rcin_thread_wa),
|
|
|
|
APM_RCIN_PRIORITY, /* Initial priority. */
|
|
|
|
_rcin_thread, /* Thread function. */
|
|
|
|
this); /* Thread parameter. */
|
|
|
|
|
2018-01-28 14:31:21 -04:00
|
|
|
// the toneAlarm thread runs at a medium priority
|
2018-02-09 23:55:22 -04:00
|
|
|
#ifdef HAL_PWM_ALARM
|
2018-01-28 14:31:21 -04:00
|
|
|
_toneAlarm_thread_ctx = chThdCreateStatic(_toneAlarm_thread_wa,
|
|
|
|
sizeof(_toneAlarm_thread_wa),
|
|
|
|
APM_TONEALARM_PRIORITY, /* Initial priority. */
|
|
|
|
_toneAlarm_thread, /* Thread function. */
|
|
|
|
this); /* Thread parameter. */
|
2018-02-09 23:55:22 -04:00
|
|
|
#endif
|
2018-01-05 02:19:51 -04:00
|
|
|
// the IO thread runs at lower priority
|
|
|
|
_io_thread_ctx = chThdCreateStatic(_io_thread_wa,
|
|
|
|
sizeof(_io_thread_wa),
|
|
|
|
APM_IO_PRIORITY, /* Initial priority. */
|
|
|
|
_io_thread, /* Thread function. */
|
|
|
|
this); /* Thread parameter. */
|
|
|
|
|
|
|
|
// the storage thread runs at just above IO priority
|
|
|
|
_storage_thread_ctx = chThdCreateStatic(_storage_thread_wa,
|
|
|
|
sizeof(_storage_thread_wa),
|
|
|
|
APM_STORAGE_PRIORITY, /* Initial priority. */
|
|
|
|
_storage_thread, /* Thread function. */
|
|
|
|
this); /* Thread parameter. */
|
|
|
|
}
|
|
|
|
|
2018-02-11 19:26:45 -04:00
|
|
|
|
2018-01-13 00:02:05 -04:00
|
|
|
void Scheduler::delay_microseconds(uint16_t usec)
|
2018-01-05 02:19:51 -04:00
|
|
|
{
|
|
|
|
if (usec == 0) { //chibios faults with 0us sleep
|
|
|
|
return;
|
|
|
|
}
|
2018-02-11 19:26:45 -04:00
|
|
|
uint32_t ticks;
|
|
|
|
if (usec >= 4096) {
|
|
|
|
// we need to use 64 bit calculations for tick conversions
|
|
|
|
ticks = US2ST64(usec);
|
|
|
|
} else {
|
|
|
|
ticks = US2ST(usec);
|
|
|
|
}
|
|
|
|
if (ticks == 0) {
|
|
|
|
// calling with ticks == 0 causes a hard fault on ChibiOS
|
|
|
|
ticks = 1;
|
|
|
|
}
|
|
|
|
chThdSleep(ticks); //Suspends Thread for desired microseconds
|
2018-01-05 02:19:51 -04:00
|
|
|
}
|
|
|
|
|
|
|
|
/*
|
|
|
|
wrapper around sem_post that boosts main thread priority
|
|
|
|
*/
|
|
|
|
static void set_high_priority()
|
|
|
|
{
|
|
|
|
#if APM_MAIN_PRIORITY_BOOST != APM_MAIN_PRIORITY
|
|
|
|
hal_chibios_set_priority(APM_MAIN_PRIORITY_BOOST);
|
|
|
|
#endif
|
|
|
|
}
|
|
|
|
|
|
|
|
/*
|
|
|
|
return the main thread to normal priority
|
|
|
|
*/
|
2018-04-02 23:25:42 -03:00
|
|
|
static void set_normal_priority(void *ctx)
|
2018-01-05 02:19:51 -04:00
|
|
|
{
|
|
|
|
#if APM_MAIN_PRIORITY_BOOST != APM_MAIN_PRIORITY
|
2018-04-02 23:25:42 -03:00
|
|
|
thread_t *task = (thread_t *)ctx;
|
|
|
|
// we don't need a reschedule as that happens automatically on ISR exit
|
|
|
|
task->realprio = APM_MAIN_PRIORITY;
|
2018-01-05 02:19:51 -04:00
|
|
|
#endif
|
|
|
|
}
|
|
|
|
|
|
|
|
/*
|
|
|
|
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-04-02 23:25:42 -03:00
|
|
|
the regularity of timing of the main loop
|
2018-01-05 02:19:51 -04:00
|
|
|
*/
|
2018-01-13 00:02:05 -04:00
|
|
|
void Scheduler::delay_microseconds_boost(uint16_t usec)
|
2018-01-05 02:19:51 -04:00
|
|
|
{
|
|
|
|
set_high_priority();
|
2018-02-09 22:46:55 -04:00
|
|
|
delay_microseconds(usec); //Suspends Thread for desired microseconds
|
2018-04-02 23:25:42 -03:00
|
|
|
chVTSet(&_boost_timer, US2ST(200), set_normal_priority, chThdGetSelfX());
|
2018-02-09 22:46:55 -04:00
|
|
|
_called_boost = true;
|
|
|
|
}
|
|
|
|
|
|
|
|
/*
|
|
|
|
return true if delay_microseconds_boost() has been called since last check
|
|
|
|
*/
|
|
|
|
bool Scheduler::check_called_boost(void)
|
|
|
|
{
|
|
|
|
if (!_called_boost) {
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
_called_boost = false;
|
|
|
|
return true;
|
2018-01-05 02:19:51 -04:00
|
|
|
}
|
|
|
|
|
2018-01-13 00:02:05 -04:00
|
|
|
void Scheduler::delay(uint16_t ms)
|
2018-01-05 02:19:51 -04:00
|
|
|
{
|
|
|
|
if (!in_main_thread()) {
|
|
|
|
//chprintf("ERROR: delay() from timer process\n");
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
uint64_t start = AP_HAL::micros64();
|
|
|
|
|
|
|
|
while ((AP_HAL::micros64() - start)/1000 < ms) {
|
|
|
|
delay_microseconds(1000);
|
|
|
|
if (_min_delay_cb_ms <= ms) {
|
|
|
|
if (_delay_cb) {
|
|
|
|
_delay_cb();
|
|
|
|
}
|
|
|
|
}
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
2018-01-13 00:02:05 -04:00
|
|
|
void Scheduler::register_delay_callback(AP_HAL::Proc proc,
|
2018-01-05 02:19:51 -04:00
|
|
|
uint16_t min_time_ms)
|
|
|
|
{
|
|
|
|
_delay_cb = proc;
|
|
|
|
_min_delay_cb_ms = min_time_ms;
|
|
|
|
}
|
|
|
|
|
2018-01-13 00:02:05 -04:00
|
|
|
void Scheduler::register_timer_process(AP_HAL::MemberProc proc)
|
2018-01-05 02:19:51 -04:00
|
|
|
{
|
|
|
|
for (uint8_t i = 0; i < _num_timer_procs; i++) {
|
|
|
|
if (_timer_proc[i] == proc) {
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
if (_num_timer_procs < CHIBIOS_SCHEDULER_MAX_TIMER_PROCS) {
|
|
|
|
_timer_proc[_num_timer_procs] = proc;
|
|
|
|
_num_timer_procs++;
|
|
|
|
} else {
|
|
|
|
hal.console->printf("Out of timer processes\n");
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
2018-01-13 00:02:05 -04:00
|
|
|
void Scheduler::register_io_process(AP_HAL::MemberProc proc)
|
2018-01-05 02:19:51 -04:00
|
|
|
{
|
|
|
|
for (uint8_t i = 0; i < _num_io_procs; i++) {
|
|
|
|
if (_io_proc[i] == proc) {
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
if (_num_io_procs < CHIBIOS_SCHEDULER_MAX_TIMER_PROCS) {
|
|
|
|
_io_proc[_num_io_procs] = proc;
|
|
|
|
_num_io_procs++;
|
|
|
|
} else {
|
|
|
|
hal.console->printf("Out of IO processes\n");
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
2018-01-13 00:02:05 -04:00
|
|
|
void Scheduler::register_timer_failsafe(AP_HAL::Proc failsafe, uint32_t period_us)
|
2018-01-05 02:19:51 -04:00
|
|
|
{
|
|
|
|
_failsafe = failsafe;
|
|
|
|
}
|
|
|
|
|
2018-01-13 00:02:05 -04:00
|
|
|
void Scheduler::suspend_timer_procs()
|
2018-01-05 02:19:51 -04:00
|
|
|
{
|
|
|
|
_timer_suspended = true;
|
|
|
|
}
|
|
|
|
|
2018-01-13 00:02:05 -04:00
|
|
|
void Scheduler::resume_timer_procs()
|
2018-01-05 02:19:51 -04:00
|
|
|
{
|
|
|
|
_timer_suspended = false;
|
|
|
|
if (_timer_event_missed == true) {
|
|
|
|
_run_timers(false);
|
|
|
|
_timer_event_missed = false;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
extern void Reset_Handler();
|
2018-01-13 00:02:05 -04:00
|
|
|
void Scheduler::reboot(bool hold_in_bootloader)
|
2018-01-05 02:19:51 -04:00
|
|
|
{
|
|
|
|
// disarm motors to ensure they are off during a bootloader upload
|
|
|
|
hal.rcout->force_safety_on();
|
|
|
|
hal.rcout->force_safety_no_wait();
|
|
|
|
|
2018-01-28 21:43:55 -04:00
|
|
|
// lock all shared DMA channels. This has the effect of waiting
|
|
|
|
// till the sensor buses are idle
|
|
|
|
Shared_DMA::lock_all();
|
|
|
|
|
2018-01-05 02:19:51 -04:00
|
|
|
// delay to ensure the async force_saftey operation completes
|
|
|
|
delay(500);
|
|
|
|
|
|
|
|
// disable interrupts during reboot
|
|
|
|
chSysDisable();
|
|
|
|
|
|
|
|
// reboot
|
|
|
|
NVIC_SystemReset();
|
|
|
|
}
|
|
|
|
|
2018-01-13 00:02:05 -04:00
|
|
|
void Scheduler::_run_timers(bool called_from_timer_thread)
|
2018-01-05 02:19:51 -04:00
|
|
|
{
|
|
|
|
if (_in_timer_proc) {
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
_in_timer_proc = true;
|
|
|
|
|
|
|
|
if (!_timer_suspended) {
|
|
|
|
// now call the timer based drivers
|
|
|
|
for (int i = 0; i < _num_timer_procs; i++) {
|
|
|
|
if (_timer_proc[i]) {
|
|
|
|
_timer_proc[i]();
|
|
|
|
}
|
|
|
|
}
|
|
|
|
} else if (called_from_timer_thread) {
|
|
|
|
_timer_event_missed = true;
|
|
|
|
}
|
|
|
|
|
|
|
|
// and the failsafe, if one is setup
|
|
|
|
if (_failsafe != nullptr) {
|
|
|
|
_failsafe();
|
|
|
|
}
|
|
|
|
|
|
|
|
// process analog input
|
2018-01-13 00:02:05 -04:00
|
|
|
((AnalogIn *)hal.analogin)->_timer_tick();
|
2018-01-05 02:19:51 -04:00
|
|
|
|
|
|
|
_in_timer_proc = false;
|
|
|
|
}
|
|
|
|
|
2018-01-13 00:02:05 -04:00
|
|
|
void Scheduler::_timer_thread(void *arg)
|
2018-01-05 02:19:51 -04:00
|
|
|
{
|
2018-01-13 00:02:05 -04:00
|
|
|
Scheduler *sched = (Scheduler *)arg;
|
2018-01-05 02:19:51 -04:00
|
|
|
sched->_timer_thread_ctx->name = "apm_timer";
|
|
|
|
|
|
|
|
while (!sched->_hal_initialized) {
|
|
|
|
sched->delay_microseconds(1000);
|
|
|
|
}
|
|
|
|
while (true) {
|
|
|
|
sched->delay_microseconds(1000);
|
|
|
|
|
|
|
|
// run registered timers
|
|
|
|
sched->_run_timers(true);
|
|
|
|
|
|
|
|
// process any pending RC output requests
|
2018-01-17 06:25:02 -04:00
|
|
|
hal.rcout->timer_tick();
|
2018-01-18 15:12:38 -04:00
|
|
|
}
|
|
|
|
}
|
2018-02-01 15:21:18 -04:00
|
|
|
#if HAL_WITH_UAVCAN
|
|
|
|
void Scheduler::_uavcan_thread(void *arg)
|
|
|
|
{
|
|
|
|
Scheduler *sched = (Scheduler *)arg;
|
2018-02-27 20:04:10 -04:00
|
|
|
sched->_uavcan_thread_ctx->name = "apm_uavcan";
|
2018-02-01 15:21:18 -04:00
|
|
|
while (!sched->_hal_initialized) {
|
|
|
|
sched->delay_microseconds(20000);
|
|
|
|
}
|
|
|
|
while (true) {
|
|
|
|
sched->delay_microseconds(1000);
|
|
|
|
for (int i = 0; i < MAX_NUMBER_OF_CAN_INTERFACES; i++) {
|
|
|
|
if(hal.can_mgr[i] != nullptr) {
|
|
|
|
CANManager::from(hal.can_mgr[i])->_timer_tick();
|
|
|
|
}
|
|
|
|
}
|
|
|
|
}
|
|
|
|
}
|
|
|
|
#endif
|
2018-01-05 02:19:51 -04:00
|
|
|
|
2018-01-18 15:12:38 -04:00
|
|
|
void Scheduler::_rcin_thread(void *arg)
|
|
|
|
{
|
|
|
|
Scheduler *sched = (Scheduler *)arg;
|
|
|
|
sched->_rcin_thread_ctx->name = "apm_rcin";
|
|
|
|
while (!sched->_hal_initialized) {
|
|
|
|
sched->delay_microseconds(20000);
|
|
|
|
}
|
|
|
|
while (true) {
|
|
|
|
sched->delay_microseconds(2500);
|
2018-01-13 00:02:05 -04:00
|
|
|
((RCInput *)hal.rcin)->_timer_tick();
|
2018-01-05 02:19:51 -04:00
|
|
|
}
|
|
|
|
}
|
2018-02-09 23:55:22 -04:00
|
|
|
#ifdef HAL_PWM_ALARM
|
2018-01-05 02:19:51 -04:00
|
|
|
|
2018-01-28 14:31:21 -04:00
|
|
|
void Scheduler::_toneAlarm_thread(void *arg)
|
|
|
|
{
|
|
|
|
Scheduler *sched = (Scheduler *)arg;
|
|
|
|
sched->_toneAlarm_thread_ctx->name = "toneAlarm";
|
|
|
|
while (!sched->_hal_initialized) {
|
2018-02-01 11:25:03 -04:00
|
|
|
sched->delay_microseconds(20000);
|
2018-01-28 14:31:21 -04:00
|
|
|
}
|
|
|
|
while (true) {
|
2018-02-01 11:25:03 -04:00
|
|
|
sched->delay_microseconds(20000);
|
2018-01-28 14:31:21 -04:00
|
|
|
|
|
|
|
// process tone command
|
|
|
|
Util::from(hal.util)->_toneAlarm_timer_tick();
|
|
|
|
}
|
|
|
|
}
|
2018-02-09 23:55:22 -04:00
|
|
|
#endif
|
2018-01-13 00:02:05 -04:00
|
|
|
void Scheduler::_run_io(void)
|
2018-01-05 02:19:51 -04: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++) {
|
|
|
|
if (_io_proc[i]) {
|
|
|
|
_io_proc[i]();
|
|
|
|
}
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
_in_io_proc = false;
|
|
|
|
}
|
|
|
|
|
2018-01-13 00:02:05 -04:00
|
|
|
void Scheduler::_io_thread(void* arg)
|
2018-01-05 02:19:51 -04:00
|
|
|
{
|
2018-01-13 00:02:05 -04:00
|
|
|
Scheduler *sched = (Scheduler *)arg;
|
2018-01-05 02:19:51 -04:00
|
|
|
sched->_io_thread_ctx->name = "apm_io";
|
|
|
|
while (!sched->_hal_initialized) {
|
|
|
|
sched->delay_microseconds(1000);
|
|
|
|
}
|
|
|
|
while (true) {
|
|
|
|
sched->delay_microseconds(1000);
|
|
|
|
|
|
|
|
// run registered IO processes
|
|
|
|
sched->_run_io();
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
2018-01-13 00:02:05 -04:00
|
|
|
void Scheduler::_storage_thread(void* arg)
|
2018-01-05 02:19:51 -04:00
|
|
|
{
|
2018-01-13 00:02:05 -04:00
|
|
|
Scheduler *sched = (Scheduler *)arg;
|
2018-01-05 02:19:51 -04:00
|
|
|
sched->_storage_thread_ctx->name = "apm_storage";
|
|
|
|
while (!sched->_hal_initialized) {
|
|
|
|
sched->delay_microseconds(10000);
|
|
|
|
}
|
|
|
|
while (true) {
|
|
|
|
sched->delay_microseconds(10000);
|
|
|
|
|
|
|
|
// process any pending storage writes
|
2018-01-26 22:32:58 -04:00
|
|
|
hal.storage->_timer_tick();
|
2018-01-05 02:19:51 -04:00
|
|
|
}
|
|
|
|
}
|
|
|
|
|
2018-01-13 00:02:05 -04:00
|
|
|
bool Scheduler::in_main_thread() const
|
2018-01-05 02:19:51 -04:00
|
|
|
{
|
|
|
|
return get_main_thread() == chThdGetSelfX();
|
|
|
|
}
|
|
|
|
|
2018-01-13 00:02:05 -04:00
|
|
|
void Scheduler::system_initialized()
|
2018-01-05 02:19:51 -04:00
|
|
|
{
|
|
|
|
if (_initialized) {
|
|
|
|
AP_HAL::panic("PANIC: scheduler::system_initialized called"
|
|
|
|
"more than once");
|
|
|
|
}
|
|
|
|
_initialized = true;
|
|
|
|
}
|
|
|
|
|
2018-03-28 05:49:51 -03:00
|
|
|
/*
|
|
|
|
disable interrupts and return a context that can be used to
|
|
|
|
restore the interrupt state. This can be used to protect
|
|
|
|
critical regions
|
|
|
|
*/
|
|
|
|
void *Scheduler::disable_interrupts_save(void)
|
|
|
|
{
|
|
|
|
return (void *)(uintptr_t)chSysGetStatusAndLockX();
|
|
|
|
}
|
|
|
|
|
|
|
|
/*
|
|
|
|
restore interrupt state from disable_interrupts_save()
|
|
|
|
*/
|
|
|
|
void Scheduler::restore_interrupts(void *state)
|
|
|
|
{
|
|
|
|
chSysRestoreStatusX((syssts_t)(uintptr_t)state);
|
|
|
|
}
|
|
|
|
|
2018-01-05 02:19:51 -04:00
|
|
|
#endif
|