mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-03 12:14:10 -04:00
AP_Scheduler: use designated initializers for tasks structs
Makes code less prone to break build and semantics (e.g., when a new field is added).
This commit is contained in:
parent
b0258d902c
commit
2e6074c108
@ -62,7 +62,10 @@ private:
|
|||||||
|
|
||||||
static SchedTest schedtest;
|
static SchedTest schedtest;
|
||||||
|
|
||||||
#define SCHED_TASK(func) FUNCTOR_BIND(&schedtest, &SchedTest::func, void)
|
#define SCHED_TASK(func, _interval_ticks, _max_time_micros) {\
|
||||||
|
.function = FUNCTOR_BIND(&schedtest, &SchedTest::func, void),\
|
||||||
|
.interval_ticks = _interval_ticks,\
|
||||||
|
.max_time_micros = _max_time_micros}
|
||||||
|
|
||||||
/*
|
/*
|
||||||
scheduler table - all regular tasks are listed here, along with how
|
scheduler table - all regular tasks are listed here, along with how
|
||||||
@ -70,9 +73,9 @@ static SchedTest schedtest;
|
|||||||
they are expected to take (in microseconds)
|
they are expected to take (in microseconds)
|
||||||
*/
|
*/
|
||||||
const AP_Scheduler::Task SchedTest::scheduler_tasks[] PROGMEM = {
|
const AP_Scheduler::Task SchedTest::scheduler_tasks[] PROGMEM = {
|
||||||
{ SCHED_TASK(ins_update), 1, 1000 },
|
SCHED_TASK(ins_update, 1, 1000),
|
||||||
{ SCHED_TASK(one_hz_print), 50, 1000 },
|
SCHED_TASK(one_hz_print, 50, 1000),
|
||||||
{ SCHED_TASK(five_second_call), 250, 1800 },
|
SCHED_TASK(five_second_call, 250, 1800),
|
||||||
};
|
};
|
||||||
|
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user