diff --git a/AntennaTracker/AntennaTracker.cpp b/AntennaTracker/AntennaTracker.cpp index 7b1477c950..3f99c89f30 100644 --- a/AntennaTracker/AntennaTracker.cpp +++ b/AntennaTracker/AntennaTracker.cpp @@ -49,7 +49,7 @@ const AP_Scheduler::Task Tracker::scheduler_tasks[] = { SCHED_TASK_CLASS(AP_InertialSensor, &tracker.ins, periodic, 50, 50), SCHED_TASK_CLASS(AP_Notify, &tracker.notify, update, 50, 100), SCHED_TASK(one_second_loop, 1, 3900), - SCHED_TASK(compass_cal_update, 50, 100), + SCHED_TASK_CLASS(Compass, &tracker.compass, cal_update, 50, 100), SCHED_TASK(accel_cal_update, 10, 100) }; diff --git a/AntennaTracker/Tracker.h b/AntennaTracker/Tracker.h index 14dc9be341..de86802056 100644 --- a/AntennaTracker/Tracker.h +++ b/AntennaTracker/Tracker.h @@ -247,7 +247,6 @@ private: void compass_save(); void init_compass_location(); void update_compass(void); - void compass_cal_update(); void accel_cal_update(void); void update_GPS(void); void handle_battery_failsafe(const char* type_str, const int8_t action); diff --git a/AntennaTracker/sensors.cpp b/AntennaTracker/sensors.cpp index 1da7b72b80..0e915be2ac 100644 --- a/AntennaTracker/sensors.cpp +++ b/AntennaTracker/sensors.cpp @@ -36,15 +36,6 @@ void Tracker::update_compass(void) } } -/* - calibrate compass -*/ -void Tracker::compass_cal_update() { - if (!hal.util->get_soft_armed()) { - compass.compass_cal_update(); - } -} - // Save compass offsets void Tracker::compass_save() { if (AP::compass().enabled() &&