mirror of https://github.com/ArduPilot/ardupilot
Sub: rename gcs_check_input to gcs_update
This commit is contained in:
parent
920300899e
commit
012dd57246
|
@ -38,7 +38,7 @@ const AP_Scheduler::Task Sub::scheduler_tasks[] = {
|
||||||
SCHED_TASK_CLASS(AP_Baro, &sub.barometer, accumulate, 50, 90),
|
SCHED_TASK_CLASS(AP_Baro, &sub.barometer, accumulate, 50, 90),
|
||||||
SCHED_TASK_CLASS(AP_Notify, &sub.notify, update, 50, 90),
|
SCHED_TASK_CLASS(AP_Notify, &sub.notify, update, 50, 90),
|
||||||
SCHED_TASK(one_hz_loop, 1, 100),
|
SCHED_TASK(one_hz_loop, 1, 100),
|
||||||
SCHED_TASK(gcs_check_input, 400, 180),
|
SCHED_TASK(gcs_update, 400, 180),
|
||||||
SCHED_TASK(gcs_send_heartbeat, 1, 110),
|
SCHED_TASK(gcs_send_heartbeat, 1, 110),
|
||||||
SCHED_TASK(gcs_send_deferred, 50, 550),
|
SCHED_TASK(gcs_send_deferred, 50, 550),
|
||||||
SCHED_TASK(gcs_data_stream_send, 50, 550),
|
SCHED_TASK(gcs_data_stream_send, 50, 550),
|
||||||
|
|
|
@ -1225,7 +1225,7 @@ void Sub::mavlink_delay_cb()
|
||||||
}
|
}
|
||||||
if (tnow - last_50hz > 20) {
|
if (tnow - last_50hz > 20) {
|
||||||
last_50hz = tnow;
|
last_50hz = tnow;
|
||||||
gcs_check_input();
|
gcs_update();
|
||||||
gcs_data_stream_send();
|
gcs_data_stream_send();
|
||||||
gcs_send_deferred();
|
gcs_send_deferred();
|
||||||
notify.update();
|
notify.update();
|
||||||
|
@ -1249,7 +1249,7 @@ void Sub::gcs_data_stream_send()
|
||||||
/*
|
/*
|
||||||
* look for incoming commands on the GCS links
|
* look for incoming commands on the GCS links
|
||||||
*/
|
*/
|
||||||
void Sub::gcs_check_input()
|
void Sub::gcs_update()
|
||||||
{
|
{
|
||||||
gcs().update();
|
gcs().update();
|
||||||
}
|
}
|
||||||
|
|
|
@ -490,7 +490,7 @@ private:
|
||||||
#endif
|
#endif
|
||||||
void send_pid_tuning(mavlink_channel_t chan);
|
void send_pid_tuning(mavlink_channel_t chan);
|
||||||
void gcs_data_stream_send(void);
|
void gcs_data_stream_send(void);
|
||||||
void gcs_check_input(void);
|
void gcs_update(void);
|
||||||
void do_erase_logs(void);
|
void do_erase_logs(void);
|
||||||
void Log_Write_Optflow();
|
void Log_Write_Optflow();
|
||||||
void Log_Write_Control_Tuning();
|
void Log_Write_Control_Tuning();
|
||||||
|
|
Loading…
Reference in New Issue