Copter: rename gcs_check_input to gcs_update

this makes the names consistent with Rover and Plane
This commit is contained in:
Randy Mackay 2018-08-23 14:17:48 +09:00
parent d1f419b530
commit 920300899e
3 changed files with 5 additions and 5 deletions

View File

@ -136,7 +136,7 @@ const AP_Scheduler::Task Copter::scheduler_tasks[] = {
SCHED_TASK(gpsglitch_check, 10, 50),
SCHED_TASK(landinggear_update, 10, 75),
SCHED_TASK(lost_vehicle_check, 10, 50),
SCHED_TASK(gcs_check_input, 400, 180),
SCHED_TASK(gcs_update, 400, 180),
SCHED_TASK(gcs_send_heartbeat, 1, 110),
SCHED_TASK(gcs_send_deferred, 50, 550),
SCHED_TASK(gcs_data_stream_send, 50, 550),
@ -564,7 +564,7 @@ void Copter::read_AHRS(void)
//-----------------------------------------------
#if HIL_MODE != HIL_MODE_DISABLED
// update hil before ahrs update
gcs_check_input();
gcs_update();
#endif
// we tell AHRS to skip INS update as we have already done it in fast_loop()

View File

@ -756,7 +756,7 @@ private:
void send_rpm(mavlink_channel_t chan);
void send_pid_tuning(mavlink_channel_t chan);
void gcs_data_stream_send(void);
void gcs_check_input(void);
void gcs_update(void);
// heli.cpp
void heli_init();

View File

@ -1503,7 +1503,7 @@ void Copter::mavlink_delay_cb()
}
if (tnow - last_50hz > 20) {
last_50hz = tnow;
gcs_check_input();
gcs_update();
gcs_data_stream_send();
gcs_send_deferred();
notify.update();
@ -1527,7 +1527,7 @@ void Copter::gcs_data_stream_send(void)
/*
* look for incoming commands on the GCS links
*/
void Copter::gcs_check_input(void)
void Copter::gcs_update(void)
{
gcs().update();
}