From c6a9130d841af2ce7bb3df359812a3e5f3c37a24 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Mon, 25 Mar 2019 20:25:22 +1100 Subject: [PATCH] Sub: call compass cal routine directly from sched table --- ArduSub/ArduSub.cpp | 2 +- ArduSub/Sub.h | 1 - ArduSub/sensors.cpp | 7 ------- 3 files changed, 1 insertion(+), 9 deletions(-) diff --git a/ArduSub/ArduSub.cpp b/ArduSub/ArduSub.cpp index 06dc00a9d2..5115f4da7e 100644 --- a/ArduSub/ArduSub.cpp +++ b/ArduSub/ArduSub.cpp @@ -55,7 +55,7 @@ const AP_Scheduler::Task Sub::scheduler_tasks[] = { #if RPM_ENABLED == ENABLED SCHED_TASK(rpm_update, 10, 200), #endif - SCHED_TASK(compass_cal_update, 100, 100), + SCHED_TASK_CLASS(Compass, &sub.compass, cal_update, 100, 100), SCHED_TASK(accel_cal_update, 10, 100), SCHED_TASK(terrain_update, 10, 100), #if GRIPPER_ENABLED == ENABLED diff --git a/ArduSub/Sub.h b/ArduSub/Sub.h index 2244bdf409..2d5c73949b 100644 --- a/ArduSub/Sub.h +++ b/ArduSub/Sub.h @@ -455,7 +455,6 @@ private: static const struct LogStructure log_structure[]; void init_compass_location(); - void compass_cal_update(void); void fast_loop(); void fifty_hz_loop(); void update_batt_compass(void); diff --git a/ArduSub/sensors.cpp b/ArduSub/sensors.cpp index 65154e0d7c..54c2987452 100644 --- a/ArduSub/sensors.cpp +++ b/ArduSub/sensors.cpp @@ -104,13 +104,6 @@ void Sub::init_optflow() } #endif // OPTFLOW == ENABLED -void Sub::compass_cal_update() -{ - if (!hal.util->get_soft_armed()) { - compass.compass_cal_update(); - } -} - void Sub::accel_cal_update() { if (hal.util->get_soft_armed()) {