mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-09 17:38:32 -04:00
AP_Scheduler: stop using Progmem.h
This commit is contained in:
parent
25c289b74c
commit
3375b6b01c
@ -23,7 +23,6 @@
|
|||||||
|
|
||||||
#include <AP_HAL/AP_HAL.h>
|
#include <AP_HAL/AP_HAL.h>
|
||||||
#include <AP_Param/AP_Param.h>
|
#include <AP_Param/AP_Param.h>
|
||||||
#include <AP_Progmem/AP_Progmem.h>
|
|
||||||
#include <AP_Vehicle/AP_Vehicle.h>
|
#include <AP_Vehicle/AP_Vehicle.h>
|
||||||
|
|
||||||
#if APM_BUILD_TYPE(APM_BUILD_ArduCopter)
|
#if APM_BUILD_TYPE(APM_BUILD_ArduCopter)
|
||||||
@ -111,7 +110,7 @@ void AP_Scheduler::run(uint16_t time_available)
|
|||||||
}
|
}
|
||||||
if (dt >= interval_ticks) {
|
if (dt >= interval_ticks) {
|
||||||
// this task is due to run. Do we have enough time to run it?
|
// this task is due to run. Do we have enough time to run it?
|
||||||
_task_time_allowed = pgm_read_word(&_tasks[i].max_time_micros);
|
_task_time_allowed = _tasks[i].max_time_micros;
|
||||||
|
|
||||||
if (dt >= interval_ticks*2) {
|
if (dt >= interval_ticks*2) {
|
||||||
// we've slipped a whole run of this task!
|
// we've slipped a whole run of this task!
|
||||||
@ -128,10 +127,8 @@ void AP_Scheduler::run(uint16_t time_available)
|
|||||||
if (_task_time_allowed <= time_available) {
|
if (_task_time_allowed <= time_available) {
|
||||||
// run it
|
// run it
|
||||||
_task_time_started = now;
|
_task_time_started = now;
|
||||||
task_fn_t func;
|
|
||||||
pgm_read_block(&_tasks[i].function, &func, sizeof(func));
|
|
||||||
current_task = i;
|
current_task = i;
|
||||||
func();
|
_tasks[i].function();
|
||||||
current_task = -1;
|
current_task = -1;
|
||||||
|
|
||||||
// record the tick counter when we ran. This drives
|
// record the tick counter when we ran. This drives
|
||||||
|
Loading…
Reference in New Issue
Block a user