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/>.
|
2019-10-20 10:31:12 -03:00
|
|
|
*
|
2018-01-05 02:19:51 -04:00
|
|
|
* Code by Andrew Tridgell and Siddharth Bharat Purohit
|
|
|
|
*/
|
|
|
|
#include <AP_HAL/AP_HAL.h>
|
|
|
|
|
|
|
|
#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>
|
2019-05-09 08:15:58 -03:00
|
|
|
#include <AP_InternalError/AP_InternalError.h>
|
2018-01-05 02:19:51 -04:00
|
|
|
|
2018-06-25 06:50:30 -03:00
|
|
|
#if CH_CFG_USE_DYNAMIC == TRUE
|
|
|
|
|
2019-01-18 00:23:42 -04:00
|
|
|
#include <AP_Logger/AP_Logger.h>
|
2018-01-05 02:19:51 -04:00
|
|
|
#include <AP_Scheduler/AP_Scheduler.h>
|
|
|
|
#include <AP_BoardConfig/AP_BoardConfig.h>
|
2018-06-27 05:46:34 -03:00
|
|
|
#include "hwdef/common/stm32_util.h"
|
2019-04-11 08:12:03 -03:00
|
|
|
#include "hwdef/common/watchdog.h"
|
2018-01-28 21:43:55 -04:00
|
|
|
#include "shared_dma.h"
|
2018-05-26 06:00:49 -03:00
|
|
|
#include "sdcard.h"
|
2018-01-05 02:19:51 -04:00
|
|
|
|
2018-10-29 18:51:37 -03:00
|
|
|
#if HAL_WITH_IO_MCU
|
|
|
|
#include <AP_IOMCU/AP_IOMCU.h>
|
|
|
|
extern AP_IOMCU iomcu;
|
|
|
|
#endif
|
|
|
|
|
2018-01-05 02:19:51 -04:00
|
|
|
using namespace ChibiOS;
|
|
|
|
|
|
|
|
extern const AP_HAL::HAL& hal;
|
2018-10-05 21:32:00 -03:00
|
|
|
#ifndef HAL_NO_TIMER_THREAD
|
2018-08-29 10:14:45 -03:00
|
|
|
THD_WORKING_AREA(_timer_thread_wa, TIMER_THD_WA_SIZE);
|
2018-10-05 21:32:00 -03:00
|
|
|
#endif
|
|
|
|
#ifndef HAL_NO_RCIN_THREAD
|
2018-08-29 10:14:45 -03:00
|
|
|
THD_WORKING_AREA(_rcin_thread_wa, RCIN_THD_WA_SIZE);
|
2018-10-05 21:32:00 -03:00
|
|
|
#endif
|
2018-08-29 10:14:45 -03:00
|
|
|
#ifndef HAL_USE_EMPTY_IO
|
|
|
|
THD_WORKING_AREA(_io_thread_wa, IO_THD_WA_SIZE);
|
|
|
|
#endif
|
|
|
|
#ifndef HAL_USE_EMPTY_STORAGE
|
|
|
|
THD_WORKING_AREA(_storage_thread_wa, STORAGE_THD_WA_SIZE);
|
|
|
|
#endif
|
2019-05-09 08:15:58 -03:00
|
|
|
#ifndef HAL_NO_MONITOR_THREAD
|
|
|
|
THD_WORKING_AREA(_monitor_thread_wa, MONITOR_THD_WA_SIZE);
|
|
|
|
#endif
|
|
|
|
|
2018-01-13 00:02:05 -04:00
|
|
|
Scheduler::Scheduler()
|
2018-05-21 20:08:35 -03:00
|
|
|
{
|
|
|
|
}
|
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-05-21 20:08:35 -03:00
|
|
|
chBSemObjectInit(&_timer_semaphore, false);
|
|
|
|
chBSemObjectInit(&_io_semaphore, false);
|
2018-10-05 21:32:00 -03:00
|
|
|
|
2019-05-09 08:15:58 -03:00
|
|
|
#ifndef HAL_NO_MONITOR_THREAD
|
|
|
|
// setup the monitor thread - this is used to detect software lockups
|
|
|
|
_monitor_thread_ctx = chThdCreateStatic(_monitor_thread_wa,
|
|
|
|
sizeof(_monitor_thread_wa),
|
|
|
|
APM_MONITOR_PRIORITY, /* Initial priority. */
|
|
|
|
_monitor_thread, /* Thread function. */
|
|
|
|
this); /* Thread parameter. */
|
|
|
|
#endif
|
|
|
|
|
2018-10-05 21:32:00 -03:00
|
|
|
#ifndef HAL_NO_TIMER_THREAD
|
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-10-05 21:32:00 -03:00
|
|
|
#endif
|
2018-01-05 02:19:51 -04:00
|
|
|
|
2018-10-05 21:32:00 -03:00
|
|
|
#ifndef HAL_NO_RCIN_THREAD
|
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-10-05 21:32:00 -03:00
|
|
|
#endif
|
2018-08-29 10:14:45 -03:00
|
|
|
#ifndef HAL_USE_EMPTY_IO
|
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. */
|
2018-08-29 10:14:45 -03:00
|
|
|
#endif
|
2018-01-05 02:19:51 -04:00
|
|
|
|
2018-08-29 10:14:45 -03:00
|
|
|
#ifndef HAL_USE_EMPTY_STORAGE
|
2018-01-05 02:19:51 -04:00
|
|
|
// 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-08-29 10:14:45 -03:00
|
|
|
#endif
|
|
|
|
|
2018-01-05 02:19:51 -04:00
|
|
|
}
|
|
|
|
|
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;
|
2018-06-02 12:56:42 -03:00
|
|
|
ticks = chTimeUS2I(usec);
|
2018-02-11 19:26:45 -04:00
|
|
|
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-05-04 05:30:25 -03:00
|
|
|
void Scheduler::boost_end(void)
|
2018-01-05 02:19:51 -04:00
|
|
|
{
|
|
|
|
#if APM_MAIN_PRIORITY_BOOST != APM_MAIN_PRIORITY
|
2018-05-04 05:30:25 -03:00
|
|
|
if (in_main_thread() && _priority_boosted) {
|
|
|
|
_priority_boosted = false;
|
|
|
|
hal_chibios_set_priority(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
|
|
|
{
|
2019-07-04 07:19:03 -03:00
|
|
|
if (!_priority_boosted && in_main_thread()) {
|
2018-05-04 05:30:25 -03:00
|
|
|
set_high_priority();
|
|
|
|
_priority_boosted = true;
|
2019-07-04 07:19:03 -03:00
|
|
|
_called_boost = true;
|
2018-05-04 05:30:25 -03:00
|
|
|
}
|
2018-02-09 22:46:55 -04:00
|
|
|
delay_microseconds(usec); //Suspends Thread for desired microseconds
|
|
|
|
}
|
|
|
|
|
|
|
|
/*
|
|
|
|
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
|
|
|
{
|
|
|
|
uint64_t start = AP_HAL::micros64();
|
|
|
|
|
|
|
|
while ((AP_HAL::micros64() - start)/1000 < ms) {
|
|
|
|
delay_microseconds(1000);
|
|
|
|
if (_min_delay_cb_ms <= ms) {
|
2018-07-06 22:51:18 -03:00
|
|
|
if (in_main_thread()) {
|
|
|
|
call_delay_cb();
|
|
|
|
}
|
2018-01-05 02:19:51 -04:00
|
|
|
}
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
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
|
|
|
{
|
2018-05-21 20:08:35 -03:00
|
|
|
chBSemWait(&_timer_semaphore);
|
2018-01-05 02:19:51 -04:00
|
|
|
for (uint8_t i = 0; i < _num_timer_procs; i++) {
|
|
|
|
if (_timer_proc[i] == proc) {
|
2018-05-21 20:08:35 -03:00
|
|
|
chBSemSignal(&_timer_semaphore);
|
2018-01-05 02:19:51 -04:00
|
|
|
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-05-21 20:08:35 -03:00
|
|
|
chBSemSignal(&_timer_semaphore);
|
2018-01-05 02:19:51 -04:00
|
|
|
}
|
|
|
|
|
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
|
|
|
{
|
2018-05-21 20:08:35 -03:00
|
|
|
chBSemWait(&_io_semaphore);
|
2018-01-05 02:19:51 -04:00
|
|
|
for (uint8_t i = 0; i < _num_io_procs; i++) {
|
|
|
|
if (_io_proc[i] == proc) {
|
2018-05-21 20:08:35 -03:00
|
|
|
chBSemSignal(&_io_semaphore);
|
2018-01-05 02:19:51 -04:00
|
|
|
return;
|
|
|
|
}
|
|
|
|
}
|
2019-10-20 10:31:12 -03:00
|
|
|
|
2018-01-05 02:19:51 -04:00
|
|
|
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-05-21 20:08:35 -03:00
|
|
|
chBSemSignal(&_io_semaphore);
|
2018-01-05 02:19:51 -04:00
|
|
|
}
|
|
|
|
|
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::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();
|
|
|
|
|
2018-10-29 18:51:37 -03:00
|
|
|
#if HAL_WITH_IO_MCU
|
|
|
|
if (AP_BoardConfig::io_enabled()) {
|
|
|
|
iomcu.shutdown();
|
|
|
|
}
|
|
|
|
#endif
|
|
|
|
|
2019-05-26 22:45:30 -03:00
|
|
|
#ifndef HAL_NO_LOGGING
|
2018-06-06 17:00:26 -03:00
|
|
|
//stop logging
|
2019-02-11 16:41:09 -04:00
|
|
|
if (AP_Logger::get_singleton()) {
|
|
|
|
AP::logger().StopLogging();
|
|
|
|
}
|
2018-06-06 17:00:26 -03:00
|
|
|
|
2018-05-26 06:00:49 -03:00
|
|
|
// stop sdcard driver, if active
|
|
|
|
sdcard_stop();
|
2018-08-29 10:14:45 -03:00
|
|
|
#endif
|
2018-01-05 02:19:51 -04:00
|
|
|
|
2019-08-12 22:45:51 -03:00
|
|
|
#if !defined(NO_FASTBOOT)
|
2018-06-27 05:46:34 -03:00
|
|
|
// setup RTC for fast reboot
|
|
|
|
set_fast_reboot(hold_in_bootloader?RTC_BOOT_HOLD:RTC_BOOT_FAST);
|
2018-08-29 10:14:45 -03:00
|
|
|
#endif
|
2018-06-27 05:46:34 -03:00
|
|
|
|
2018-06-04 08:43:44 -03:00
|
|
|
// disable all interrupt sources
|
|
|
|
port_disable();
|
2019-10-20 10:31:12 -03:00
|
|
|
|
2018-01-05 02:19:51 -04:00
|
|
|
// reboot
|
|
|
|
NVIC_SystemReset();
|
|
|
|
}
|
|
|
|
|
2018-05-13 19:47:14 -03:00
|
|
|
void Scheduler::_run_timers()
|
2018-01-05 02:19:51 -04:00
|
|
|
{
|
|
|
|
if (_in_timer_proc) {
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
_in_timer_proc = true;
|
|
|
|
|
2018-05-21 20:08:35 -03:00
|
|
|
int num_procs = 0;
|
|
|
|
chBSemWait(&_timer_semaphore);
|
|
|
|
num_procs = _num_timer_procs;
|
|
|
|
chBSemSignal(&_timer_semaphore);
|
2018-05-13 19:47:14 -03:00
|
|
|
// now call the timer based drivers
|
2018-05-21 20:08:35 -03:00
|
|
|
for (int i = 0; i < num_procs; i++) {
|
2018-05-13 19:47:14 -03:00
|
|
|
if (_timer_proc[i]) {
|
|
|
|
_timer_proc[i]();
|
2018-01-05 02:19:51 -04:00
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
// and the failsafe, if one is setup
|
|
|
|
if (_failsafe != nullptr) {
|
|
|
|
_failsafe();
|
|
|
|
}
|
|
|
|
|
2018-10-28 20:24:01 -03:00
|
|
|
#if HAL_USE_ADC == TRUE && !defined(HAL_DISABLE_ADC_DRIVER)
|
2018-01-05 02:19:51 -04:00
|
|
|
// process analog input
|
2018-01-13 00:02:05 -04:00
|
|
|
((AnalogIn *)hal.analogin)->_timer_tick();
|
2018-03-06 18:41:03 -04:00
|
|
|
#endif
|
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-03-06 18:41:03 -04:00
|
|
|
chRegSetThreadName("apm_timer");
|
2018-01-05 02:19:51 -04:00
|
|
|
|
|
|
|
while (!sched->_hal_initialized) {
|
|
|
|
sched->delay_microseconds(1000);
|
|
|
|
}
|
|
|
|
while (true) {
|
|
|
|
sched->delay_microseconds(1000);
|
|
|
|
|
|
|
|
// run registered timers
|
2018-05-13 19:47:14 -03:00
|
|
|
sched->_run_timers();
|
2018-01-05 02:19:51 -04:00
|
|
|
|
|
|
|
// process any pending RC output requests
|
2018-01-17 06:25:02 -04:00
|
|
|
hal.rcout->timer_tick();
|
2019-04-11 08:12:03 -03:00
|
|
|
|
|
|
|
if (sched->expect_delay_start != 0) {
|
|
|
|
uint32_t now = AP_HAL::millis();
|
|
|
|
if (now - sched->expect_delay_start <= sched->expect_delay_length) {
|
2019-05-09 08:15:58 -03:00
|
|
|
sched->watchdog_pat();
|
2019-04-11 08:12:03 -03:00
|
|
|
}
|
|
|
|
}
|
2018-01-18 15:12:38 -04:00
|
|
|
}
|
|
|
|
}
|
2018-01-05 02:19:51 -04:00
|
|
|
|
2019-05-26 22:45:30 -03:00
|
|
|
#ifndef HAL_NO_MONITOR_THREAD
|
2019-05-09 08:15:58 -03:00
|
|
|
void Scheduler::_monitor_thread(void *arg)
|
|
|
|
{
|
|
|
|
Scheduler *sched = (Scheduler *)arg;
|
|
|
|
chRegSetThreadName("apm_monitor");
|
|
|
|
|
|
|
|
while (!sched->_initialized) {
|
|
|
|
sched->delay(100);
|
|
|
|
}
|
|
|
|
bool using_watchdog = AP_BoardConfig::watchdog_enabled();
|
|
|
|
|
|
|
|
while (true) {
|
|
|
|
sched->delay(100);
|
|
|
|
if (using_watchdog) {
|
|
|
|
stm32_watchdog_save((uint32_t *)&hal.util->persistent_data, (sizeof(hal.util->persistent_data)+3)/4);
|
|
|
|
}
|
|
|
|
uint32_t now = AP_HAL::millis();
|
|
|
|
uint32_t loop_delay = now - sched->last_watchdog_pat_ms;
|
|
|
|
if (loop_delay >= 200) {
|
|
|
|
// the main loop has been stuck for at least
|
|
|
|
// 200ms. Starting logging the main loop state
|
2019-05-15 01:12:15 -03:00
|
|
|
const AP_HAL::Util::PersistentData &pd = hal.util->persistent_data;
|
2019-05-16 04:57:35 -03:00
|
|
|
AP::logger().Write("MON", "TimeUS,LDelay,Task,IErr,IErrCnt,MavMsg,MavCmd,SemLine,SPICnt,I2CCnt", "QIbIIHHHII",
|
2019-05-09 08:15:58 -03:00
|
|
|
AP_HAL::micros64(),
|
|
|
|
loop_delay,
|
|
|
|
pd.scheduler_task,
|
|
|
|
pd.internal_errors,
|
2019-05-11 05:19:25 -03:00
|
|
|
pd.internal_error_count,
|
|
|
|
pd.last_mavlink_msgid,
|
|
|
|
pd.last_mavlink_cmd,
|
2019-05-16 04:57:35 -03:00
|
|
|
pd.semaphore_line,
|
|
|
|
pd.spi_count,
|
|
|
|
pd.i2c_count);
|
2019-05-09 08:15:58 -03:00
|
|
|
}
|
|
|
|
if (loop_delay >= 500) {
|
|
|
|
// at 500ms we declare an internal error
|
|
|
|
AP::internalerror().error(AP_InternalError::error_t::main_loop_stuck);
|
|
|
|
}
|
|
|
|
}
|
|
|
|
}
|
2019-05-26 22:45:30 -03:00
|
|
|
#endif // HAL_NO_MONITOR_THREAD
|
2019-05-09 08:15:58 -03:00
|
|
|
|
2018-01-18 15:12:38 -04:00
|
|
|
void Scheduler::_rcin_thread(void *arg)
|
|
|
|
{
|
|
|
|
Scheduler *sched = (Scheduler *)arg;
|
2018-03-06 18:41:03 -04:00
|
|
|
chRegSetThreadName("apm_rcin");
|
2018-01-18 15:12:38 -04:00
|
|
|
while (!sched->_hal_initialized) {
|
|
|
|
sched->delay_microseconds(20000);
|
|
|
|
}
|
|
|
|
while (true) {
|
2019-08-27 04:47:32 -03:00
|
|
|
sched->delay_microseconds(1000);
|
2018-01-13 00:02:05 -04:00
|
|
|
((RCInput *)hal.rcin)->_timer_tick();
|
2018-01-05 02:19:51 -04:00
|
|
|
}
|
|
|
|
}
|
|
|
|
|
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;
|
|
|
|
|
2018-05-21 20:08:35 -03:00
|
|
|
int num_procs = 0;
|
|
|
|
chBSemWait(&_io_semaphore);
|
|
|
|
num_procs = _num_io_procs;
|
|
|
|
chBSemSignal(&_io_semaphore);
|
2018-05-13 19:47:14 -03:00
|
|
|
// now call the IO based drivers
|
2018-05-21 20:08:35 -03:00
|
|
|
for (int i = 0; i < num_procs; i++) {
|
2018-05-13 19:47:14 -03:00
|
|
|
if (_io_proc[i]) {
|
|
|
|
_io_proc[i]();
|
2018-01-05 02:19:51 -04:00
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
_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-03-06 18:41:03 -04:00
|
|
|
chRegSetThreadName("apm_io");
|
2018-01-05 02:19:51 -04:00
|
|
|
while (!sched->_hal_initialized) {
|
|
|
|
sched->delay_microseconds(1000);
|
|
|
|
}
|
2018-12-28 19:50:17 -04:00
|
|
|
uint32_t last_sd_start_ms = AP_HAL::millis();
|
2018-01-05 02:19:51 -04:00
|
|
|
while (true) {
|
|
|
|
sched->delay_microseconds(1000);
|
|
|
|
|
|
|
|
// run registered IO processes
|
|
|
|
sched->_run_io();
|
2018-12-28 19:50:17 -04:00
|
|
|
|
|
|
|
if (!hal.util->get_soft_armed()) {
|
|
|
|
// if sdcard hasn't mounted then retry it every 3s in the IO
|
|
|
|
// thread when disarmed
|
|
|
|
uint32_t now = AP_HAL::millis();
|
|
|
|
if (now - last_sd_start_ms > 3000) {
|
2018-12-30 02:38:53 -04:00
|
|
|
last_sd_start_ms = now;
|
2018-12-28 19:50:17 -04:00
|
|
|
sdcard_retry();
|
|
|
|
}
|
|
|
|
}
|
2018-01-05 02:19:51 -04:00
|
|
|
}
|
|
|
|
}
|
|
|
|
|
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-03-06 18:41:03 -04:00
|
|
|
chRegSetThreadName("apm_storage");
|
2018-01-05 02:19:51 -04:00
|
|
|
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
|
|
|
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-07-06 20:59:10 -03:00
|
|
|
/*
|
|
|
|
trampoline for thread create
|
|
|
|
*/
|
|
|
|
void Scheduler::thread_create_trampoline(void *ctx)
|
|
|
|
{
|
|
|
|
AP_HAL::MemberProc *t = (AP_HAL::MemberProc *)ctx;
|
|
|
|
(*t)();
|
|
|
|
free(t);
|
|
|
|
}
|
|
|
|
|
|
|
|
/*
|
|
|
|
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)
|
|
|
|
{
|
|
|
|
// take a copy of the MemberProc, it is freed after thread exits
|
|
|
|
AP_HAL::MemberProc *tproc = (AP_HAL::MemberProc *)malloc(sizeof(proc));
|
|
|
|
if (!tproc) {
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
*tproc = proc;
|
|
|
|
|
|
|
|
uint8_t thread_priority = APM_IO_PRIORITY;
|
|
|
|
static const struct {
|
|
|
|
priority_base base;
|
|
|
|
uint8_t p;
|
|
|
|
} priority_map[] = {
|
|
|
|
{ PRIORITY_BOOST, APM_MAIN_PRIORITY_BOOST},
|
|
|
|
{ PRIORITY_MAIN, APM_MAIN_PRIORITY},
|
|
|
|
{ PRIORITY_SPI, APM_SPI_PRIORITY},
|
|
|
|
{ PRIORITY_I2C, APM_I2C_PRIORITY},
|
|
|
|
{ PRIORITY_CAN, APM_CAN_PRIORITY},
|
|
|
|
{ PRIORITY_TIMER, APM_TIMER_PRIORITY},
|
|
|
|
{ PRIORITY_RCIN, APM_RCIN_PRIORITY},
|
|
|
|
{ PRIORITY_IO, APM_IO_PRIORITY},
|
|
|
|
{ PRIORITY_UART, APM_UART_PRIORITY},
|
|
|
|
{ PRIORITY_STORAGE, APM_STORAGE_PRIORITY},
|
2018-09-27 20:17:27 -03:00
|
|
|
{ PRIORITY_SCRIPTING, APM_SCRIPTING_PRIORITY},
|
2018-07-06 20:59:10 -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, LOWPRIO, HIGHPRIO);
|
|
|
|
break;
|
|
|
|
}
|
|
|
|
}
|
2019-02-26 20:14:58 -04:00
|
|
|
thread_t *thread_ctx = thread_create_alloc(THD_WORKING_AREA_SIZE(stack_size),
|
2018-07-06 20:59:10 -03:00
|
|
|
name,
|
|
|
|
thread_priority,
|
|
|
|
thread_create_trampoline,
|
|
|
|
tproc);
|
|
|
|
if (thread_ctx == nullptr) {
|
|
|
|
free(tproc);
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
return true;
|
|
|
|
}
|
|
|
|
|
2019-04-11 08:12:03 -03:00
|
|
|
/*
|
|
|
|
inform the scheduler that we are calling an operation from the
|
|
|
|
main thread that may take an extended amount of time. This can
|
|
|
|
be used to prevent watchdog reset during expected long delays
|
|
|
|
A value of zero cancels the previous expected delay
|
|
|
|
*/
|
|
|
|
void Scheduler::expect_delay_ms(uint32_t ms)
|
|
|
|
{
|
|
|
|
if (!in_main_thread()) {
|
|
|
|
// only for main thread
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
if (ms == 0) {
|
2019-05-11 05:20:53 -03:00
|
|
|
if (expect_delay_nesting > 0) {
|
|
|
|
expect_delay_nesting--;
|
|
|
|
}
|
|
|
|
if (expect_delay_nesting == 0) {
|
|
|
|
expect_delay_start = 0;
|
|
|
|
}
|
2019-04-11 08:12:03 -03:00
|
|
|
} else {
|
2019-05-11 05:20:53 -03:00
|
|
|
uint32_t now = AP_HAL::millis();
|
|
|
|
if (expect_delay_start != 0) {
|
|
|
|
// we already have a delay running, possibly extend it
|
|
|
|
uint32_t done = now - expect_delay_start;
|
|
|
|
if (expect_delay_length > done) {
|
|
|
|
ms = MAX(ms, expect_delay_length - done);
|
|
|
|
}
|
|
|
|
}
|
|
|
|
expect_delay_start = now;
|
2019-04-11 08:12:03 -03:00
|
|
|
expect_delay_length = ms;
|
2019-05-11 05:20:53 -03:00
|
|
|
expect_delay_nesting++;
|
2019-05-06 22:58:47 -03:00
|
|
|
|
|
|
|
// also put our priority below timer thread if we are boosted
|
|
|
|
boost_end();
|
2019-04-11 08:12:03 -03:00
|
|
|
}
|
|
|
|
}
|
|
|
|
|
2019-05-09 08:15:58 -03:00
|
|
|
// pat the watchdog
|
|
|
|
void Scheduler::watchdog_pat(void)
|
|
|
|
{
|
|
|
|
stm32_watchdog_pat();
|
|
|
|
last_watchdog_pat_ms = AP_HAL::millis();
|
|
|
|
}
|
|
|
|
|
2018-03-06 18:41:03 -04:00
|
|
|
#endif // CH_CFG_USE_DYNAMIC
|