mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-01 13:38:38 -04:00
Plane: call GCS update functions at quadcopter main loop rate
This commit is contained in:
parent
b6ac20ce32
commit
153228bef5
@ -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),
|
||||
|
Loading…
Reference in New Issue
Block a user