diff --git a/AntennaTracker/AntennaTracker.cpp b/AntennaTracker/AntennaTracker.cpp index 6c5ac40453..140c5461ac 100644 --- a/AntennaTracker/AntennaTracker.cpp +++ b/AntennaTracker/AntennaTracker.cpp @@ -41,7 +41,6 @@ const AP_Scheduler::Task Tracker::scheduler_tasks[] = { SCHED_TASK_CLASS(AP_Baro, &tracker.barometer, update, 10, 1500), SCHED_TASK(gcs_update, 50, 1700), SCHED_TASK(gcs_data_stream_send, 50, 3000), - SCHED_TASK(compass_accumulate, 50, 1500), SCHED_TASK_CLASS(AP_Baro, &tracker.barometer, accumulate, 50, 900), SCHED_TASK(ten_hz_logging_loop, 10, 300), #if LOGGING_ENABLED == ENABLED diff --git a/AntennaTracker/Tracker.h b/AntennaTracker/Tracker.h index f738d7e544..64283c6ab4 100644 --- a/AntennaTracker/Tracker.h +++ b/AntennaTracker/Tracker.h @@ -213,7 +213,6 @@ private: void read_radio(); void update_ahrs(); void update_compass(void); - void compass_accumulate(void); void accel_cal_update(void); void update_GPS(void); void init_servos(); diff --git a/AntennaTracker/sensors.cpp b/AntennaTracker/sensors.cpp index ad29b72585..c1ad696d26 100644 --- a/AntennaTracker/sensors.cpp +++ b/AntennaTracker/sensors.cpp @@ -22,16 +22,6 @@ void Tracker::update_compass(void) } } -/* - if the compass is enabled then try to accumulate a reading - */ -void Tracker::compass_accumulate(void) -{ - if (g.compass_enabled) { - compass.accumulate(); - } -} - /* calibrate compass */