From 76a2d89b51f4e44749cdc82736f5acf61eebbc53 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Tue, 25 Feb 2020 14:19:28 +1100 Subject: [PATCH] ArduSub: move call of notify.update up to AP_Vehicle --- ArduSub/ArduSub.cpp | 1 - 1 file changed, 1 deletion(-) diff --git a/ArduSub/ArduSub.cpp b/ArduSub/ArduSub.cpp index 918a189eb3..4ccc431fa3 100644 --- a/ArduSub/ArduSub.cpp +++ b/ArduSub/ArduSub.cpp @@ -80,7 +80,6 @@ const AP_Scheduler::Task Sub::scheduler_tasks[] = { SCHED_TASK(three_hz_loop, 3, 75, 21), SCHED_TASK(update_turn_counter, 10, 50, 24), SCHED_TASK_CLASS(AP_Baro, &sub.barometer, accumulate, 50, 90, 27), - SCHED_TASK_CLASS(AP_Notify, &sub.notify, update, 50, 90, 30), SCHED_TASK(one_hz_loop, 1, 100, 33), SCHED_TASK_CLASS(GCS, (GCS*)&sub._gcs, update_receive, 400, 180, 36), SCHED_TASK_CLASS(GCS, (GCS*)&sub._gcs, update_send, 400, 550, 39),