mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-21 23:33:57 -04:00
Plane: increased allowed time for mavlink send to 750us
this is to allow more time to get streams out at low loop rates
This commit is contained in:
parent
5bbb02e03b
commit
26c2555c3c
@ -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),
|
||||
|
Loading…
Reference in New Issue
Block a user