Plane: adjust for new update entry points into GCS

This commit is contained in:
Peter Barker 2018-11-22 14:04:44 +11:00 committed by Randy Mackay
parent 9665d8d2e9
commit 7f5c0db949
2 changed files with 5 additions and 6 deletions

View File

@ -40,7 +40,6 @@ const AP_Scheduler::Task Plane::scheduler_tasks[] = {
SCHED_TASK(stabilize, 400, 100),
SCHED_TASK(set_servos, 400, 100),
SCHED_TASK(read_control_switch, 7, 100),
SCHED_TASK_CLASS(GCS, (GCS*)&plane._gcs, retry_deferred, 50, 500),
SCHED_TASK(update_GPS_50Hz, 50, 300),
SCHED_TASK(update_GPS_10Hz, 10, 400),
SCHED_TASK(navigate, 10, 150),
@ -49,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, 50, 500),
SCHED_TASK_CLASS(GCS, (GCS*)&plane._gcs, data_stream_send, 50, 500),
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(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),
@ -142,7 +141,7 @@ void Plane::ahrs_update()
#if HIL_SUPPORT
if (g.hil_mode == 1) {
// update hil before AHRS update
gcs().update();
gcs().update_receive();
}
#endif

View File

@ -1471,8 +1471,8 @@ void Plane::mavlink_delay_cb()
}
if (tnow - last_50hz > 20) {
last_50hz = tnow;
gcs().update();
gcs().data_stream_send();
gcs().update_receive();
gcs().update_send();
notify.update();
}
if (tnow - last_5s > 5000) {