mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 15:53:56 -04:00
Copter: adjust for new update entry points into GCS
This commit is contained in:
parent
7f5c0db949
commit
05f2e51b4d
@ -135,10 +135,9 @@ const AP_Scheduler::Task Copter::scheduler_tasks[] = {
|
|||||||
SCHED_TASK(gpsglitch_check, 10, 50),
|
SCHED_TASK(gpsglitch_check, 10, 50),
|
||||||
SCHED_TASK(landinggear_update, 10, 75),
|
SCHED_TASK(landinggear_update, 10, 75),
|
||||||
SCHED_TASK(lost_vehicle_check, 10, 50),
|
SCHED_TASK(lost_vehicle_check, 10, 50),
|
||||||
SCHED_TASK_CLASS(GCS, (GCS*)&copter._gcs, update, 400, 180),
|
SCHED_TASK_CLASS(GCS, (GCS*)&copter._gcs, update_receive, 400, 180),
|
||||||
SCHED_TASK(gcs_send_heartbeat, 1, 110),
|
SCHED_TASK(gcs_send_heartbeat, 1, 110),
|
||||||
SCHED_TASK_CLASS(GCS, (GCS*)&copter._gcs, retry_deferred, 400, 550),
|
SCHED_TASK_CLASS(GCS, (GCS*)&copter._gcs, update_send, 400, 550),
|
||||||
SCHED_TASK_CLASS(GCS, (GCS*)&copter._gcs, data_stream_send, 400, 550),
|
|
||||||
#if MOUNT == ENABLED
|
#if MOUNT == ENABLED
|
||||||
SCHED_TASK_CLASS(AP_Mount, &copter.camera_mount, update, 50, 75),
|
SCHED_TASK_CLASS(AP_Mount, &copter.camera_mount, update, 50, 75),
|
||||||
#endif
|
#endif
|
||||||
|
@ -1437,9 +1437,8 @@ void Copter::mavlink_delay_cb()
|
|||||||
}
|
}
|
||||||
if (tnow - last_50hz > 20) {
|
if (tnow - last_50hz > 20) {
|
||||||
last_50hz = tnow;
|
last_50hz = tnow;
|
||||||
gcs().update();
|
gcs().update_receive();
|
||||||
gcs().data_stream_send();
|
gcs().update_send();
|
||||||
gcs().retry_deferred();
|
|
||||||
notify.update();
|
notify.update();
|
||||||
}
|
}
|
||||||
if (tnow - last_5s > 5000) {
|
if (tnow - last_5s > 5000) {
|
||||||
|
Loading…
Reference in New Issue
Block a user