AP_Scheduler: add static create method
This commit is contained in:
parent
8094482f21
commit
d3e12eb899
@ -51,9 +51,14 @@
|
|||||||
class AP_Scheduler
|
class AP_Scheduler
|
||||||
{
|
{
|
||||||
public:
|
public:
|
||||||
// constructor
|
static AP_Scheduler create() { return AP_Scheduler{}; }
|
||||||
AP_Scheduler(void);
|
|
||||||
|
constexpr AP_Scheduler(AP_Scheduler &&other) = default;
|
||||||
|
|
||||||
|
/* Do not allow copies */
|
||||||
|
AP_Scheduler(const AP_Scheduler &other) = delete;
|
||||||
|
AP_Scheduler &operator=(const AP_Scheduler&) = delete;
|
||||||
|
|
||||||
FUNCTOR_TYPEDEF(task_fn_t, void);
|
FUNCTOR_TYPEDEF(task_fn_t, void);
|
||||||
|
|
||||||
struct Task {
|
struct Task {
|
||||||
@ -100,12 +105,14 @@ public:
|
|||||||
static int8_t current_task;
|
static int8_t current_task;
|
||||||
|
|
||||||
private:
|
private:
|
||||||
|
AP_Scheduler();
|
||||||
|
|
||||||
// used to enable scheduler debugging
|
// used to enable scheduler debugging
|
||||||
AP_Int8 _debug;
|
AP_Int8 _debug;
|
||||||
|
|
||||||
// overall scheduling rate in Hz
|
// overall scheduling rate in Hz
|
||||||
AP_Int16 _loop_rate_hz; // The value of this variable can be changed with the non-initialization. (Ex. Tuning by GDB)
|
AP_Int16 _loop_rate_hz; // The value of this variable can be changed with the non-initialization. (Ex. Tuning by GDB)
|
||||||
|
|
||||||
// progmem list of tasks to run
|
// progmem list of tasks to run
|
||||||
const struct Task *_tasks;
|
const struct Task *_tasks;
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user