From 029aeeb4fd8bb7dbc025ca46e2a350df82631a2c Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Mon, 30 May 2016 20:05:06 +1000 Subject: [PATCH] Copter: support for a GCS singleton --- ArduCopter/Copter.h | 2 ++ ArduCopter/GCS_Mavlink.cpp | 6 +++--- ArduCopter/system.cpp | 2 +- 3 files changed, 6 insertions(+), 4 deletions(-) diff --git a/ArduCopter/Copter.h b/ArduCopter/Copter.h index 243ea64463..82fd880f73 100644 --- a/ArduCopter/Copter.h +++ b/ArduCopter/Copter.h @@ -239,6 +239,8 @@ private: static const uint8_t num_gcs = MAVLINK_COMM_NUM_BUFFERS; GCS_MAVLINK_Copter gcs_chan[MAVLINK_COMM_NUM_BUFFERS]; + GCS _gcs; // avoid using this; use gcs() + GCS &gcs() { return _gcs; } // User variables #ifdef USERHOOK_VARIABLES diff --git a/ArduCopter/GCS_Mavlink.cpp b/ArduCopter/GCS_Mavlink.cpp index 31a5e70871..5f9046ce7a 100644 --- a/ArduCopter/GCS_Mavlink.cpp +++ b/ArduCopter/GCS_Mavlink.cpp @@ -11,7 +11,7 @@ void Copter::gcs_send_heartbeat(void) void Copter::gcs_send_deferred(void) { gcs_send_message(MSG_RETRY_DEFERRED); - GCS_MAVLINK::service_statustext(); + gcs().service_statustext(); } /* @@ -2075,7 +2075,7 @@ void Copter::gcs_check_input(void) void Copter::gcs_send_text(MAV_SEVERITY severity, const char *str) { - GCS_MAVLINK::send_statustext(severity, 0xFF, str); + gcs().send_statustext(severity, 0xFF, str); notify.send_text(str); } @@ -2091,7 +2091,7 @@ void Copter::gcs_send_text_fmt(MAV_SEVERITY severity, const char *fmt, ...) va_start(arg_list, fmt); va_end(arg_list); hal.util->vsnprintf((char *)str, sizeof(str), fmt, arg_list); - GCS_MAVLINK::send_statustext(severity, 0xFF, str); + gcs().send_statustext(severity, 0xFF, str); notify.send_text(str); } diff --git a/ArduCopter/system.cpp b/ArduCopter/system.cpp index a871d3a640..1c218d3faf 100644 --- a/ArduCopter/system.cpp +++ b/ArduCopter/system.cpp @@ -111,7 +111,7 @@ void Copter::init_ardupilot() // initialise stats module g2.stats.init(); - GCS_MAVLINK::set_dataflash(&DataFlash); + gcs().set_dataflash(&DataFlash); // identify ourselves correctly with the ground station mavlink_system.sysid = g.sysid_this_mav;