mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
Rover: reduce scheduler estimated time for gcs tasks
This commit is contained in:
parent
012dd57246
commit
473e8d18a1
@ -59,9 +59,9 @@ const AP_Scheduler::Task Rover::scheduler_tasks[] = {
|
||||
SCHED_TASK(update_mission, 50, 200),
|
||||
SCHED_TASK(update_logging1, 10, 200),
|
||||
SCHED_TASK(update_logging2, 10, 200),
|
||||
SCHED_TASK(gcs_retry_deferred, 50, 1000),
|
||||
SCHED_TASK(gcs_update, 50, 1000),
|
||||
SCHED_TASK(gcs_data_stream_send, 50, 3000),
|
||||
SCHED_TASK(gcs_retry_deferred, 50, 500),
|
||||
SCHED_TASK(gcs_update, 50, 500),
|
||||
SCHED_TASK(gcs_data_stream_send, 50, 1000),
|
||||
SCHED_TASK(read_mode_switch, 7, 200),
|
||||
SCHED_TASK(read_aux_all, 10, 200),
|
||||
SCHED_TASK_CLASS(AP_BattMonitor, &rover.battery, read, 10, 300),
|
||||
|
Loading…
Reference in New Issue
Block a user