mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-11 17:13:56 -03:00
AP_Scheduler: support member functions for rover
This commit is contained in:
parent
12cbf7888f
commit
1237772479
@ -39,13 +39,14 @@ const AP_Param::GroupInfo AP_Scheduler::var_info[] PROGMEM = {
|
||||
};
|
||||
|
||||
// initialise the scheduler
|
||||
void AP_Scheduler::init(const AP_Scheduler::Task *tasks, uint8_t num_tasks)
|
||||
void AP_Scheduler::init(const AP_Scheduler::Task *tasks, uint8_t num_tasks, void *classptr)
|
||||
{
|
||||
_tasks = tasks;
|
||||
_num_tasks = num_tasks;
|
||||
_last_run = new uint16_t[_num_tasks];
|
||||
memset(_last_run, 0, sizeof(_last_run[0]) * _num_tasks);
|
||||
_tick_counter = 0;
|
||||
_classptr = classptr;
|
||||
}
|
||||
|
||||
// one tick has passed
|
||||
@ -84,9 +85,14 @@ void AP_Scheduler::run(uint16_t time_available)
|
||||
if (_task_time_allowed <= time_available) {
|
||||
// run it
|
||||
_task_time_started = now;
|
||||
task_fn_t func = (task_fn_t)pgm_read_pointer(&_tasks[i].function);
|
||||
task_fn_t func;
|
||||
pgm_read_block(&_tasks[i].function, &func, sizeof(func));
|
||||
current_task = i;
|
||||
#if AP_SCHEDULER_USE_DELEGATE_PTR
|
||||
func(_classptr);
|
||||
#else
|
||||
func();
|
||||
#endif
|
||||
current_task = -1;
|
||||
|
||||
// record the tick counter when we ran. This drives
|
||||
|
@ -35,10 +35,23 @@
|
||||
the scheduler is allowed to use before it must return
|
||||
*/
|
||||
|
||||
#include <AP_HAL.h>
|
||||
#include <AP_Vehicle.h>
|
||||
|
||||
#if APM_BUILD_TYPE(APM_BUILD_APMrover2) && defined(__AVR__)
|
||||
#define AP_SCHEDULER_USE_DELEGATE_PTR 1
|
||||
#else
|
||||
#define AP_SCHEDULER_USE_DELEGATE_PTR 0
|
||||
#endif
|
||||
|
||||
class AP_Scheduler
|
||||
{
|
||||
public:
|
||||
typedef void (*task_fn_t)(void);
|
||||
#if APM_BUILD_TYPE(APM_BUILD_APMrover2)
|
||||
DELEGATE_FUNCTION_VOID_TYPEDEF(task_fn_t);
|
||||
#else
|
||||
typedef void (*task_fn_t)(void);
|
||||
#endif
|
||||
|
||||
struct Task {
|
||||
task_fn_t function;
|
||||
@ -47,7 +60,7 @@ public:
|
||||
};
|
||||
|
||||
// initialise scheduler
|
||||
void init(const Task *tasks, uint8_t num_tasks);
|
||||
void init(const Task *tasks, uint8_t num_tasks, void *classptr);
|
||||
|
||||
// call when one tick has passed
|
||||
void tick(void);
|
||||
@ -101,6 +114,9 @@ private:
|
||||
|
||||
// number of ticks that _spare_micros is counted over
|
||||
uint8_t _spare_ticks;
|
||||
|
||||
// class pointer for use on AVR
|
||||
void *_classptr;
|
||||
};
|
||||
|
||||
#endif // AP_SCHEDULER_H
|
||||
|
@ -70,7 +70,7 @@ void setup(void)
|
||||
AP_InertialSensor::RATE_50HZ);
|
||||
|
||||
// initialise the scheduler
|
||||
scheduler.init(&scheduler_tasks[0], sizeof(scheduler_tasks)/sizeof(scheduler_tasks[0]));
|
||||
scheduler.init(&scheduler_tasks[0], sizeof(scheduler_tasks)/sizeof(scheduler_tasks[0]), NULL);
|
||||
}
|
||||
|
||||
void loop(void)
|
||||
|
Loading…
Reference in New Issue
Block a user