From 26c2555c3ca67379510e00e1ae7d18358eb4c09c Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 23 May 2020 10:31:03 +1000 Subject: [PATCH] Plane: increased allowed time for mavlink send to 750us this is to allow more time to get streams out at low loop rates --- ArduPlane/ArduPlane.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ArduPlane/ArduPlane.cpp b/ArduPlane/ArduPlane.cpp index 18247e0a75..3302dba700 100644 --- a/ArduPlane/ArduPlane.cpp +++ b/ArduPlane/ArduPlane.cpp @@ -53,7 +53,7 @@ const AP_Scheduler::Task Plane::scheduler_tasks[] = { #endif SCHED_TASK(ekf_check, 10, 75), SCHED_TASK_CLASS(GCS, (GCS*)&plane._gcs, update_receive, 300, 500), - SCHED_TASK_CLASS(GCS, (GCS*)&plane._gcs, update_send, 300, 500), + SCHED_TASK_CLASS(GCS, (GCS*)&plane._gcs, update_send, 300, 750), SCHED_TASK_CLASS(AP_ServoRelayEvents, &plane.ServoRelayEvents, update_events, 50, 150), SCHED_TASK_CLASS(AP_BattMonitor, &plane.battery, read, 10, 300), SCHED_TASK_CLASS(AP_Baro, &plane.barometer, accumulate, 50, 150),