From d39fcfd03829caf4cd1452f7c446ee740bc56917 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Sat, 16 Jul 2022 12:02:45 +1000 Subject: [PATCH] ArduCopter: move call to compass cal update up to AP_Vehicle --- ArduCopter/Copter.cpp | 1 - ArduCopter/Copter.h | 1 - 2 files changed, 2 deletions(-) diff --git a/ArduCopter/Copter.cpp b/ArduCopter/Copter.cpp index ff0fa5ae54..c9dd33c3dd 100644 --- a/ArduCopter/Copter.cpp +++ b/ArduCopter/Copter.cpp @@ -213,7 +213,6 @@ const AP_Scheduler::Task Copter::scheduler_tasks[] = { #if RPM_ENABLED == ENABLED SCHED_TASK_CLASS(AP_RPM, &copter.rpm_sensor, update, 40, 200, 129), #endif - SCHED_TASK_CLASS(Compass, &copter.compass, cal_update, 100, 100, 132), SCHED_TASK_CLASS(AP_TempCalibration, &copter.g2.temp_calibration, update, 10, 100, 135), #if HAL_ADSB_ENABLED SCHED_TASK(avoidance_adsb_update, 10, 100, 138), diff --git a/ArduCopter/Copter.h b/ArduCopter/Copter.h index e0fd9033b4..0f04e230bc 100644 --- a/ArduCopter/Copter.h +++ b/ArduCopter/Copter.h @@ -880,7 +880,6 @@ private: bool rangefinder_alt_ok() const; bool rangefinder_up_ok() const; void update_optical_flow(void); - void compass_cal_update(void); // RC_Channel.cpp void save_trim();