From e948f79db8de7727bbf34697c033a8c829894515 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Sat, 16 Jul 2022 12:02:45 +1000 Subject: [PATCH] AP_Vehicle: move call to compass cal update up to AP_Vehicle --- libraries/AP_Vehicle/AP_Vehicle.cpp | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/libraries/AP_Vehicle/AP_Vehicle.cpp b/libraries/AP_Vehicle/AP_Vehicle.cpp index 7e8aafac1d..05b4296510 100644 --- a/libraries/AP_Vehicle/AP_Vehicle.cpp +++ b/libraries/AP_Vehicle/AP_Vehicle.cpp @@ -324,6 +324,9 @@ const AP_Scheduler::Task AP_Vehicle::scheduler_tasks[] = { #if AP_AIRSPEED_ENABLED SCHED_TASK_CLASS(AP_Airspeed, &vehicle.airspeed, update, 10, 100, 41), // NOTE: the priority number here should be right before Plane's calc_airspeed_errors #endif +#if COMPASS_CAL_ENABLED + SCHED_TASK_CLASS(Compass, &vehicle.compass, cal_update, 100, 200, 75), +#endif #if HAL_RUNCAM_ENABLED SCHED_TASK_CLASS(AP_RunCam, &vehicle.runcam, update, 50, 50, 200), #endif @@ -350,7 +353,7 @@ const AP_Scheduler::Task AP_Vehicle::scheduler_tasks[] = { SCHED_TASK(publish_osd_info, 1, 10, 240), #endif #if HAL_INS_ACCELCAL_ENABLED - SCHED_TASK(accel_cal_update, 10, 100, 245), + SCHED_TASK(accel_cal_update, 10, 100, 245), #endif #if AP_FENCE_ENABLED SCHED_TASK_CLASS(AC_Fence, &vehicle.fence, update, 10, 100, 248),