diff --git a/ArduPlane/ArduPlane.cpp b/ArduPlane/ArduPlane.cpp index 6ecd5089a9..bc3e255cde 100644 --- a/ArduPlane/ArduPlane.cpp +++ b/ArduPlane/ArduPlane.cpp @@ -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 && diff --git a/ArduPlane/Plane.h b/ArduPlane/Plane.h index c3cbf45826..c17b44f423 100644 --- a/ArduPlane/Plane.h +++ b/ArduPlane/Plane.h @@ -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);