mirror of https://github.com/ArduPilot/ardupilot
Plane: eliminate update_perf_logging scheduler table shim
This commit is contained in:
parent
730adc3f7c
commit
3859e5dfb1
|
@ -70,7 +70,7 @@ const AP_Scheduler::Task Plane::scheduler_tasks[] = {
|
|||
SCHED_TASK(airspeed_ratio_update, 1, 100),
|
||||
SCHED_TASK(update_mount, 50, 100),
|
||||
SCHED_TASK(update_trigger, 50, 100),
|
||||
SCHED_TASK(log_perf_info, 0.2, 100),
|
||||
SCHED_TASK_CLASS(AP_Scheduler, &plane.scheduler, update_logging, 0.2, 100),
|
||||
SCHED_TASK(compass_save, 0.1, 200),
|
||||
SCHED_TASK(Log_Write_Fast, 25, 300),
|
||||
SCHED_TASK(update_logging1, 25, 300),
|
||||
|
@ -333,11 +333,6 @@ void Plane::one_second_loop()
|
|||
update_sensor_status_flags();
|
||||
}
|
||||
|
||||
void Plane::log_perf_info()
|
||||
{
|
||||
scheduler.update_logging();
|
||||
}
|
||||
|
||||
void Plane::compass_save()
|
||||
{
|
||||
if (g.compass_enabled &&
|
||||
|
|
|
@ -975,7 +975,6 @@ private:
|
|||
void airspeed_ratio_update(void);
|
||||
void update_mount(void);
|
||||
void update_trigger(void);
|
||||
void log_perf_info(void);
|
||||
void compass_save(void);
|
||||
void update_logging1(void);
|
||||
void update_logging2(void);
|
||||
|
|
Loading…
Reference in New Issue