diff --git a/AntennaTracker/Tracker.cpp b/AntennaTracker/Tracker.cpp index 2465b7cbcf..c5a72a5c93 100644 --- a/AntennaTracker/Tracker.cpp +++ b/AntennaTracker/Tracker.cpp @@ -52,7 +52,6 @@ const AP_Scheduler::Task Tracker::scheduler_tasks[] = { SCHED_TASK(one_second_loop, 1, 3900), SCHED_TASK_CLASS(Compass, &tracker.compass, cal_update, 50, 100), SCHED_TASK(stats_update, 1, 200), - SCHED_TASK(accel_cal_update, 10, 100) }; void Tracker::get_scheduler_tasks(const AP_Scheduler::Task *&tasks, diff --git a/AntennaTracker/Tracker.h b/AntennaTracker/Tracker.h index 835081b433..5a31bf89b4 100644 --- a/AntennaTracker/Tracker.h +++ b/AntennaTracker/Tracker.h @@ -194,7 +194,6 @@ private: void update_ahrs(); void compass_save(); void update_compass(void); - 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 e20cab3d14..1a63346aa0 100644 --- a/AntennaTracker/sensors.cpp +++ b/AntennaTracker/sensors.cpp @@ -25,20 +25,6 @@ void Tracker::compass_save() { } } -/* - Accel calibration -*/ -void Tracker::accel_cal_update() { - if (hal.util->get_soft_armed()) { - return; - } - ins.acal_update(); - float trim_roll, trim_pitch; - if (ins.get_new_trim(trim_roll, trim_pitch)) { - ahrs.set_trim(Vector3f(trim_roll, trim_pitch, 0)); - } -} - /* read the GPS */