diff --git a/APMrover2/APMrover2.cpp b/APMrover2/APMrover2.cpp index 5a4e1e09cc..86a493fc8d 100644 --- a/APMrover2/APMrover2.cpp +++ b/APMrover2/APMrover2.cpp @@ -85,7 +85,7 @@ const AP_Scheduler::Task Rover::scheduler_tasks[] = { SCHED_TASK_CLASS(AP_Notify, &rover.notify, update, 50, 300), SCHED_TASK(one_second_loop, 1, 1500), SCHED_TASK_CLASS(AC_Sprayer, &rover.g2.sprayer, update, 3, 90), - SCHED_TASK(compass_cal_update, 50, 200), + SCHED_TASK_CLASS(Compass, &rover.compass, cal_update, 50, 200), SCHED_TASK(compass_save, 0.1, 200), SCHED_TASK(accel_cal_update, 10, 200), #if LOGGING_ENABLED == ENABLED diff --git a/APMrover2/Rover.h b/APMrover2/Rover.h index 4bc54b17d7..780ad2f18a 100644 --- a/APMrover2/Rover.h +++ b/APMrover2/Rover.h @@ -463,7 +463,6 @@ private: // sensors.cpp void init_compass_location(void); void update_compass(void); - void compass_cal_update(void); void compass_save(void); void init_beacon(); void init_visual_odom(); diff --git a/APMrover2/sensors.cpp b/APMrover2/sensors.cpp index fce932460f..200b3b7f24 100644 --- a/APMrover2/sensors.cpp +++ b/APMrover2/sensors.cpp @@ -30,13 +30,6 @@ void Rover::update_compass(void) } } -// Calibrate compass -void Rover::compass_cal_update() { - if (!hal.util->get_soft_armed()) { - compass.compass_cal_update(); - } -} - // Save compass offsets void Rover::compass_save() { if (AP::compass().enabled() &&