diff --git a/ArduPlane/ArduPlane.cpp b/ArduPlane/ArduPlane.cpp index 30d3b8b0e7..c76093160c 100644 --- a/ArduPlane/ArduPlane.cpp +++ b/ArduPlane/ArduPlane.cpp @@ -59,7 +59,7 @@ const AP_Scheduler::Task Plane::scheduler_tasks[] = { SCHED_TASK_CLASS(AP_Notify, &plane.notify, update, 50, 300), SCHED_TASK(read_rangefinder, 50, 100), SCHED_TASK_CLASS(AP_ICEngine, &plane.g2.ice_control, update, 10, 100), - SCHED_TASK(compass_cal_update, 50, 50), + SCHED_TASK_CLASS(Compass, &plane.compass, cal_update, 50, 50), SCHED_TASK(accel_cal_update, 10, 50), #if OPTFLOW == ENABLED SCHED_TASK_CLASS(OpticalFlow, &plane.optflow, update, 50, 50), diff --git a/ArduPlane/Plane.h b/ArduPlane/Plane.h index cc65bf7684..9a397cba1a 100644 --- a/ArduPlane/Plane.h +++ b/ArduPlane/Plane.h @@ -966,7 +966,6 @@ private: #if ADVANCED_FAILSAFE == ENABLED void afs_fs_check(void); #endif - void compass_cal_update(); void update_optical_flow(void); void one_second_loop(void); void airspeed_ratio_update(void); diff --git a/ArduPlane/sensors.cpp b/ArduPlane/sensors.cpp index 9b199d7d3d..c125891fbc 100644 --- a/ArduPlane/sensors.cpp +++ b/ArduPlane/sensors.cpp @@ -38,15 +38,6 @@ void Plane::read_rangefinder(void) rangefinder_height_update(); } -/* - calibrate compass -*/ -void Plane::compass_cal_update() { - if (!hal.util->get_soft_armed()) { - compass.compass_cal_update(); - } -} - /* Accel calibration */