mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-27 02:04:00 -04:00
AP_Scheduler: removed delegate ptr handling
no longer needed
This commit is contained in:
parent
edc21cfa38
commit
7db9da6545
@ -39,14 +39,13 @@ const AP_Param::GroupInfo AP_Scheduler::var_info[] PROGMEM = {
|
|||||||
};
|
};
|
||||||
|
|
||||||
// initialise the scheduler
|
// initialise the scheduler
|
||||||
void AP_Scheduler::init(const AP_Scheduler::Task *tasks, uint8_t num_tasks, void *classptr)
|
void AP_Scheduler::init(const AP_Scheduler::Task *tasks, uint8_t num_tasks)
|
||||||
{
|
{
|
||||||
_tasks = tasks;
|
_tasks = tasks;
|
||||||
_num_tasks = num_tasks;
|
_num_tasks = num_tasks;
|
||||||
_last_run = new uint16_t[_num_tasks];
|
_last_run = new uint16_t[_num_tasks];
|
||||||
memset(_last_run, 0, sizeof(_last_run[0]) * _num_tasks);
|
memset(_last_run, 0, sizeof(_last_run[0]) * _num_tasks);
|
||||||
_tick_counter = 0;
|
_tick_counter = 0;
|
||||||
_classptr = classptr;
|
|
||||||
}
|
}
|
||||||
|
|
||||||
// one tick has passed
|
// one tick has passed
|
||||||
@ -90,8 +89,6 @@ void AP_Scheduler::run(uint16_t time_available)
|
|||||||
current_task = i;
|
current_task = i;
|
||||||
#if APM_BUILD_FUNCTOR
|
#if APM_BUILD_FUNCTOR
|
||||||
func();
|
func();
|
||||||
#elif AP_SCHEDULER_USE_DELEGATE_PTR
|
|
||||||
func(_classptr);
|
|
||||||
#else
|
#else
|
||||||
func();
|
func();
|
||||||
#endif
|
#endif
|
||||||
|
@ -38,19 +38,11 @@
|
|||||||
#include <AP_HAL.h>
|
#include <AP_HAL.h>
|
||||||
#include <AP_Vehicle.h>
|
#include <AP_Vehicle.h>
|
||||||
|
|
||||||
#if APM_BUILD_DELEGATES && defined(__AVR__)
|
|
||||||
#define AP_SCHEDULER_USE_DELEGATE_PTR 1
|
|
||||||
#else
|
|
||||||
#define AP_SCHEDULER_USE_DELEGATE_PTR 0
|
|
||||||
#endif
|
|
||||||
|
|
||||||
class AP_Scheduler
|
class AP_Scheduler
|
||||||
{
|
{
|
||||||
public:
|
public:
|
||||||
#if APM_BUILD_FUNCTOR
|
#if APM_BUILD_FUNCTOR
|
||||||
FUNCTOR_TYPEDEF(task_fn_t, void);
|
FUNCTOR_TYPEDEF(task_fn_t, void);
|
||||||
#elif APM_BUILD_DELEGATES
|
|
||||||
DELEGATE_FUNCTION_VOID_TYPEDEF(task_fn_t);
|
|
||||||
#else
|
#else
|
||||||
typedef void (*task_fn_t)(void);
|
typedef void (*task_fn_t)(void);
|
||||||
#endif
|
#endif
|
||||||
@ -62,7 +54,7 @@ public:
|
|||||||
};
|
};
|
||||||
|
|
||||||
// initialise scheduler
|
// initialise scheduler
|
||||||
void init(const Task *tasks, uint8_t num_tasks, void *classptr);
|
void init(const Task *tasks, uint8_t num_tasks);
|
||||||
|
|
||||||
// call when one tick has passed
|
// call when one tick has passed
|
||||||
void tick(void);
|
void tick(void);
|
||||||
@ -116,9 +108,6 @@ private:
|
|||||||
|
|
||||||
// number of ticks that _spare_micros is counted over
|
// number of ticks that _spare_micros is counted over
|
||||||
uint8_t _spare_ticks;
|
uint8_t _spare_ticks;
|
||||||
|
|
||||||
// class pointer for use on AVR
|
|
||||||
void *_classptr;
|
|
||||||
};
|
};
|
||||||
|
|
||||||
#endif // AP_SCHEDULER_H
|
#endif // AP_SCHEDULER_H
|
||||||
|
Loading…
Reference in New Issue
Block a user