From 55195278742f9ff88276b60a3f222011dc29bca4 Mon Sep 17 00:00:00 2001 From: Tom Pittenger Date: Thu, 25 Apr 2019 16:32:15 -0700 Subject: [PATCH] Sub: move heartbeat sending to gcs instead of by vehicles --- ArduSub/ArduSub.cpp | 1 - 1 file changed, 1 deletion(-) diff --git a/ArduSub/ArduSub.cpp b/ArduSub/ArduSub.cpp index 092ca68cd9..6cf098de28 100644 --- a/ArduSub/ArduSub.cpp +++ b/ArduSub/ArduSub.cpp @@ -39,7 +39,6 @@ const AP_Scheduler::Task Sub::scheduler_tasks[] = { SCHED_TASK_CLASS(AP_Notify, &sub.notify, update, 50, 90), SCHED_TASK(one_hz_loop, 1, 100), SCHED_TASK_CLASS(GCS, (GCS*)&sub._gcs, update_receive, 400, 180), - SCHED_TASK(gcs_send_heartbeat, 1, 110), SCHED_TASK_CLASS(GCS, (GCS*)&sub._gcs, update_send, 400, 550), #if MOUNT == ENABLED SCHED_TASK_CLASS(AP_Mount, &sub.camera_mount, update, 50, 75),