From d060670ba3079dd8046c6fa550e4d0afdfe2498e Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 17 Jun 2016 11:27:47 +1000 Subject: [PATCH] Plane: rename gcs[] to gcs_chan[] Wish to use gcs() to return the gcs singleton --- ArduPlane/GCS_Mavlink.cpp | 26 +++++++++++++------------- ArduPlane/Log.cpp | 2 +- ArduPlane/Parameters.cpp | 8 ++++---- ArduPlane/Plane.h | 2 +- ArduPlane/system.cpp | 16 ++++++++-------- 5 files changed, 27 insertions(+), 27 deletions(-) diff --git a/ArduPlane/GCS_Mavlink.cpp b/ArduPlane/GCS_Mavlink.cpp index 4e6215d252..909e71b9d1 100644 --- a/ArduPlane/GCS_Mavlink.cpp +++ b/ArduPlane/GCS_Mavlink.cpp @@ -91,7 +91,7 @@ void Plane::send_heartbeat(mavlink_channel_t chan) // indicate we have set a custom mode base_mode |= MAV_MODE_FLAG_CUSTOM_MODE_ENABLED; - gcs[chan-MAVLINK_COMM_0].send_heartbeat(MAV_TYPE_FIXED_WING, + gcs_chan[chan-MAVLINK_COMM_0].send_heartbeat(MAV_TYPE_FIXED_WING, base_mode, custom_mode, system_status); @@ -2098,7 +2098,7 @@ void GCS_MAVLINK_Plane::handleMessage(mavlink_message_t* msg) void Plane::mavlink_delay_cb() { static uint32_t last_1hz, last_50hz, last_5s; - if (!gcs[0].initialised || in_mavlink_delay) return; + if (!gcs_chan[0].initialised || in_mavlink_delay) return; in_mavlink_delay = true; @@ -2129,8 +2129,8 @@ void Plane::mavlink_delay_cb() void Plane::gcs_send_message(enum ap_message id) { for (uint8_t i=0; idelay @@ -162,7 +162,7 @@ void Plane::init_ardupilot() // setup telem slots with serial ports for (uint8_t i = 1; i < MAVLINK_COMM_NUM_BUFFERS; i++) { - gcs[i].setup_uart(serial_manager, AP_SerialManager::SerialProtocol_MAVLink, i); + gcs_chan[i].setup_uart(serial_manager, AP_SerialManager::SerialProtocol_MAVLink, i); } // setup frsky @@ -232,11 +232,11 @@ void Plane::init_ardupilot() if (g.cli_enabled == 1) { const char *msg = "\nPress ENTER 3 times to start interactive setup\n"; cliSerial->printf("%s\n", msg); - if (gcs[1].initialised && (gcs[1].get_uart() != nullptr)) { - gcs[1].get_uart()->printf("%s\n", msg); + if (gcs_chan[1].initialised && (gcs_chan[1].get_uart() != nullptr)) { + gcs_chan[1].get_uart()->printf("%s\n", msg); } - if (num_gcs > 2 && gcs[2].initialised && (gcs[2].get_uart() != nullptr)) { - gcs[2].get_uart()->printf("%s\n", msg); + if (num_gcs > 2 && gcs_chan[2].initialised && (gcs_chan[2].get_uart() != nullptr)) { + gcs_chan[2].get_uart()->printf("%s\n", msg); } } #endif // CLI_ENABLED @@ -571,8 +571,8 @@ void Plane::check_long_failsafe() (tnow - failsafe.last_heartbeat_ms) > g.long_fs_timeout*1000) { failsafe_long_on_event(FAILSAFE_GCS, MODE_REASON_GCS_FAILSAFE); } else if (g.gcs_heartbeat_fs_enabled == GCS_FAILSAFE_HB_RSSI && - gcs[0].last_radio_status_remrssi_ms != 0 && - (tnow - gcs[0].last_radio_status_remrssi_ms) > g.long_fs_timeout*1000) { + gcs_chan[0].last_radio_status_remrssi_ms != 0 && + (tnow - gcs_chan[0].last_radio_status_remrssi_ms) > g.long_fs_timeout*1000) { failsafe_long_on_event(FAILSAFE_GCS, MODE_REASON_GCS_FAILSAFE); } } else {