Copter: move heartbeat sending to gcs instead of by vehicles
This commit is contained in:
parent
fb0c9c7813
commit
3f359886cd
@ -136,7 +136,6 @@ const AP_Scheduler::Task Copter::scheduler_tasks[] = {
|
||||
SCHED_TASK(landinggear_update, 10, 75),
|
||||
SCHED_TASK(lost_vehicle_check, 10, 50),
|
||||
SCHED_TASK_CLASS(GCS, (GCS*)&copter._gcs, update_receive, 400, 180),
|
||||
SCHED_TASK(gcs_send_heartbeat, 1, 110),
|
||||
SCHED_TASK_CLASS(GCS, (GCS*)&copter._gcs, update_send, 400, 550),
|
||||
#if MOUNT == ENABLED
|
||||
SCHED_TASK_CLASS(AP_Mount, &copter.camera_mount, update, 50, 75),
|
||||
|
Loading…
Reference in New Issue
Block a user