2016-02-17 21:25:25 -04:00
|
|
|
#pragma once
|
2012-08-23 15:36:13 -03:00
|
|
|
|
2012-09-05 20:54:21 -03:00
|
|
|
#include <stdint.h>
|
2015-10-22 12:03:11 -03:00
|
|
|
|
2015-10-22 14:22:16 -03:00
|
|
|
#include <AP_Common/AP_Common.h>
|
2012-09-05 20:54:21 -03:00
|
|
|
|
2015-10-22 12:03:11 -03:00
|
|
|
#include "AP_HAL_Boards.h"
|
|
|
|
#include "AP_HAL_Namespace.h"
|
|
|
|
|
|
|
|
|
2012-08-23 15:36:13 -03:00
|
|
|
class AP_HAL::Scheduler {
|
|
|
|
public:
|
2012-09-06 15:20:12 -03:00
|
|
|
Scheduler() {}
|
2015-12-02 11:37:22 -04:00
|
|
|
virtual void init() = 0;
|
2012-12-19 22:16:10 -04:00
|
|
|
virtual void delay(uint16_t ms) = 0;
|
2015-02-15 20:52:37 -04:00
|
|
|
|
|
|
|
/*
|
|
|
|
delay for the given number of microseconds. This needs to be as
|
|
|
|
accurate as possible - preferably within 100 microseconds.
|
|
|
|
*/
|
2012-09-05 20:54:21 -03:00
|
|
|
virtual void delay_microseconds(uint16_t us) = 0;
|
2015-02-15 20:52:37 -04:00
|
|
|
|
|
|
|
/*
|
|
|
|
delay for the given number of microseconds. On supported
|
|
|
|
platforms this boosts the priority of the main thread for a
|
|
|
|
short time when the time completes. The aim is to ensure the
|
|
|
|
main thread runs at a higher priority than drivers for the start
|
|
|
|
of each loop
|
|
|
|
*/
|
|
|
|
virtual void delay_microseconds_boost(uint16_t us) { delay_microseconds(us); }
|
|
|
|
|
2019-04-11 08:11:10 -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
|
|
|
|
*/
|
|
|
|
virtual void expect_delay_ms(uint32_t ms) { }
|
2020-03-10 22:20:04 -03:00
|
|
|
|
|
|
|
/*
|
|
|
|
return true if we are in a period of expected delay. This can be
|
|
|
|
used to suppress error messages
|
|
|
|
*/
|
|
|
|
virtual bool in_expected_delay(void) const { return false; }
|
|
|
|
|
2018-05-04 05:29:27 -03:00
|
|
|
/*
|
|
|
|
end the priority boost from delay_microseconds_boost()
|
|
|
|
*/
|
|
|
|
virtual void boost_end(void) {}
|
2018-05-08 02:47:08 -03:00
|
|
|
|
|
|
|
// register a function to be called by the scheduler if it needs
|
|
|
|
// to sleep for more than min_time_ms
|
2012-10-26 22:02:52 -03:00
|
|
|
virtual void register_delay_callback(AP_HAL::Proc,
|
2018-05-08 02:47:08 -03:00
|
|
|
uint16_t min_time_ms);
|
|
|
|
// returns true if the Scheduler has called the delay callback
|
|
|
|
// function. If you are on the main thread that means your call
|
|
|
|
// stack has the scheduler on it somewhere.
|
|
|
|
virtual bool in_delay_callback() const { return _in_delay_callback; }
|
2013-01-03 21:31:43 -04:00
|
|
|
|
2013-04-17 08:33:50 -03:00
|
|
|
// register a high priority timer task
|
2013-09-30 04:00:26 -03:00
|
|
|
virtual void register_timer_process(AP_HAL::MemberProc) = 0;
|
2013-04-17 08:33:50 -03:00
|
|
|
|
|
|
|
// register a low priority IO task
|
2013-09-30 04:00:26 -03:00
|
|
|
virtual void register_io_process(AP_HAL::MemberProc) = 0;
|
2013-04-17 08:33:50 -03:00
|
|
|
|
2013-09-30 04:00:26 -03:00
|
|
|
virtual void register_timer_failsafe(AP_HAL::Proc,
|
2013-09-28 03:23:34 -03:00
|
|
|
uint32_t period_us) = 0;
|
2012-12-04 19:52:27 -04:00
|
|
|
|
2020-12-23 07:22:46 -04:00
|
|
|
// check and set the startup state
|
|
|
|
virtual void set_system_initialized() = 0;
|
|
|
|
virtual bool is_system_initialized() = 0;
|
2013-01-10 17:50:11 -04:00
|
|
|
|
2013-09-03 22:58:13 -03:00
|
|
|
virtual void reboot(bool hold_in_bootloader) = 0;
|
2013-10-12 04:22:57 -03:00
|
|
|
|
2013-12-29 18:31:18 -04:00
|
|
|
/**
|
2014-02-26 04:33:39 -04:00
|
|
|
optional function to stop clock at a given time, used by log replay
|
2013-12-29 18:31:18 -04:00
|
|
|
*/
|
2014-02-26 04:33:39 -04:00
|
|
|
virtual void stop_clock(uint64_t time_usec) {}
|
2017-04-02 11:54:31 -03:00
|
|
|
|
2017-09-17 22:01:43 -03:00
|
|
|
virtual bool in_main_thread() const = 0;
|
|
|
|
|
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
|
|
|
|
|
|
|
|
Warning: may not be implemented on all HALs
|
|
|
|
*/
|
|
|
|
virtual void *disable_interrupts_save(void) { return nullptr; }
|
|
|
|
|
|
|
|
/*
|
|
|
|
restore interrupt state from disable_interrupts_save()
|
|
|
|
*/
|
|
|
|
virtual void restore_interrupts(void *) {}
|
2018-05-08 02:47:08 -03:00
|
|
|
|
|
|
|
// called by subclasses when they need to delay for some time
|
|
|
|
virtual void call_delay_cb();
|
|
|
|
uint16_t _min_delay_cb_ms;
|
|
|
|
|
2018-07-06 20:30:13 -03:00
|
|
|
/*
|
|
|
|
priority_base is used to select what the priority for a new
|
|
|
|
thread is relative to
|
|
|
|
*/
|
|
|
|
enum priority_base {
|
|
|
|
PRIORITY_BOOST,
|
|
|
|
PRIORITY_MAIN,
|
|
|
|
PRIORITY_SPI,
|
|
|
|
PRIORITY_I2C,
|
|
|
|
PRIORITY_CAN,
|
|
|
|
PRIORITY_TIMER,
|
2020-12-05 15:16:05 -04:00
|
|
|
PRIORITY_RCOUT,
|
2023-02-23 08:35:05 -04:00
|
|
|
PRIORITY_LED,
|
2018-07-06 20:30:13 -03:00
|
|
|
PRIORITY_RCIN,
|
|
|
|
PRIORITY_IO,
|
|
|
|
PRIORITY_UART,
|
2018-09-27 20:03:35 -03:00
|
|
|
PRIORITY_STORAGE,
|
|
|
|
PRIORITY_SCRIPTING,
|
2018-07-06 20:30:13 -03:00
|
|
|
};
|
|
|
|
|
|
|
|
/*
|
|
|
|
create a new thread
|
|
|
|
*/
|
|
|
|
virtual bool thread_create(AP_HAL::MemberProc proc, const char *name,
|
|
|
|
uint32_t stack_size, priority_base base, int8_t priority) {
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
|
2018-05-08 02:47:08 -03:00
|
|
|
private:
|
|
|
|
|
|
|
|
AP_HAL::Proc _delay_cb;
|
|
|
|
bool _in_delay_callback : 1;
|
|
|
|
|
2012-08-23 15:36:13 -03:00
|
|
|
};
|
2019-05-11 05:16:51 -03:00
|
|
|
|
|
|
|
/*
|
|
|
|
helper macro and class to make using expect_delay_ms() safer and easier
|
|
|
|
*/
|
|
|
|
class ExpectDelay {
|
|
|
|
public:
|
2019-05-15 01:09:13 -03:00
|
|
|
ExpectDelay(uint32_t ms);
|
2019-05-11 05:16:51 -03:00
|
|
|
~ExpectDelay();
|
|
|
|
};
|
|
|
|
|
2019-05-15 01:09:13 -03:00
|
|
|
#define EXPECT_DELAY_MS(ms) DELAY_JOIN( ms, __COUNTER__ )
|
|
|
|
#define DELAY_JOIN( ms, counter) _DO_DELAY_JOIN( ms, counter )
|
|
|
|
#define _DO_DELAY_JOIN( ms, counter ) ExpectDelay _getdelay ## counter(ms)
|
2022-12-03 18:48:07 -04:00
|
|
|
|
|
|
|
|
|
|
|
/*
|
|
|
|
TIME_CHECK() can be used to unexpected detect long delays. Scatter
|
|
|
|
them in likely places and any long delays will be printed
|
|
|
|
*/
|
|
|
|
|
|
|
|
class TimeCheck {
|
|
|
|
public:
|
|
|
|
TimeCheck(uint32_t limit_ms, const char *file, uint32_t line);
|
|
|
|
~TimeCheck();
|
|
|
|
private:
|
|
|
|
const uint32_t limit_ms;
|
|
|
|
const uint32_t line;
|
|
|
|
const char *file;
|
|
|
|
uint32_t start_ms;
|
|
|
|
};
|
|
|
|
|
|
|
|
#define TIME_CHECK(limit_ms) JOIN_TC(limit_ms, __FILE__, __LINE__, __COUNTER__ )
|
|
|
|
#define JOIN_TC(limit_ms, file, line, counter ) _DO_JOIN_TC( limit_ms, file, line, counter )
|
|
|
|
#define _DO_JOIN_TC(limit_ms, file, line, counter ) TimeCheck _gettc ## counter(limit_ms, file, line)
|