mirror of https://github.com/ArduPilot/ardupilot
Rover: call GCS update functions at much higher rate to support lower intervals
This commit is contained in:
parent
2e58eb1d46
commit
f2dc8f9282
|
@ -60,8 +60,8 @@ 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_CLASS(GCS, (GCS*)&rover._gcs, update_receive, 50, 500),
|
||||
SCHED_TASK_CLASS(GCS, (GCS*)&rover._gcs, update_send, 50, 1000),
|
||||
SCHED_TASK_CLASS(GCS, (GCS*)&rover._gcs, update_receive, 400, 500),
|
||||
SCHED_TASK_CLASS(GCS, (GCS*)&rover._gcs, update_send, 400, 1000),
|
||||
SCHED_TASK_CLASS(RC_Channels, (RC_Channels*)&rover.g2.rc_channels, read_mode_switch, 7, 200),
|
||||
SCHED_TASK_CLASS(RC_Channels, (RC_Channels*)&rover.g2.rc_channels, read_aux_all, 10, 200),
|
||||
SCHED_TASK_CLASS(AP_BattMonitor, &rover.battery, read, 10, 300),
|
||||
|
|
Loading…
Reference in New Issue