diff --git a/ArduPlane/ArduPlane.cpp b/ArduPlane/ArduPlane.cpp index a98b07fcf3..527b884417 100644 --- a/ArduPlane/ArduPlane.cpp +++ b/ArduPlane/ArduPlane.cpp @@ -48,8 +48,8 @@ const AP_Scheduler::Task Plane::scheduler_tasks[] = { SCHED_TASK(update_alt, 10, 200), SCHED_TASK(adjust_altitude_target, 10, 200), SCHED_TASK(afs_fs_check, 10, 100), - SCHED_TASK_CLASS(GCS, (GCS*)&plane._gcs, update_receive, 50, 500), - SCHED_TASK_CLASS(GCS, (GCS*)&plane._gcs, update_send, 50, 500), + 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(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),