Sub: support for a GCS singleton

This commit is contained in:
Peter Barker 2017-02-14 16:51:38 +11:00 committed by Andrew Tridgell
parent 6fb2a6814f
commit ee07a06fa2
4 changed files with 10 additions and 8 deletions

View File

@ -43,15 +43,15 @@ void Sub::set_simple_mode(uint8_t b)
if (ap.simple_mode != b) { if (ap.simple_mode != b) {
if (b == 0) { if (b == 0) {
Log_Write_Event(DATA_SET_SIMPLE_OFF); Log_Write_Event(DATA_SET_SIMPLE_OFF);
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_INFO, "SIMPLE mode off"); gcs().send_statustext(MAV_SEVERITY_INFO, 0XFF, "SIMPLE mode off");
} else if (b == 1) { } else if (b == 1) {
Log_Write_Event(DATA_SET_SIMPLE_ON); Log_Write_Event(DATA_SET_SIMPLE_ON);
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_INFO, "SIMPLE mode on"); gcs().send_statustext(MAV_SEVERITY_INFO, 0XFF, "SIMPLE mode on");
} else { } else {
// initialise super simple heading // initialise super simple heading
update_super_simple_bearing(true); update_super_simple_bearing(true);
Log_Write_Event(DATA_SET_SUPERSIMPLE_ON); Log_Write_Event(DATA_SET_SUPERSIMPLE_ON);
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_INFO, "SUPERSIMPLE mode on"); gcs().send_statustext(MAV_SEVERITY_INFO, 0XFF, "SUPERSIMPLE mode on");
} }
ap.simple_mode = b; ap.simple_mode = b;
} }

View File

@ -14,7 +14,7 @@ void Sub::gcs_send_heartbeat(void)
void Sub::gcs_send_deferred(void) void Sub::gcs_send_deferred(void)
{ {
gcs_send_message(MSG_RETRY_DEFERRED); gcs_send_message(MSG_RETRY_DEFERRED);
GCS_MAVLINK::service_statustext(); gcs().service_statustext();
} }
/* /*
@ -627,7 +627,7 @@ bool GCS_MAVLINK_Sub::try_send_message(enum ap_message id)
break; break;
case MSG_STATUSTEXT: case MSG_STATUSTEXT:
// depreciated, use GCS_MAVLINK::send_statustext* // deprecated, use gcs().send_statustext*
return false; return false;
case MSG_LIMITS_STATUS: case MSG_LIMITS_STATUS:
@ -2052,7 +2052,7 @@ void Sub::gcs_check_input(void)
void Sub::gcs_send_text(MAV_SEVERITY severity, const char *str) void Sub::gcs_send_text(MAV_SEVERITY severity, const char *str)
{ {
GCS_MAVLINK::send_statustext(severity, 0xFF, str); gcs().send_statustext(severity, 0xFF, str);
} }
/* /*
@ -2067,5 +2067,5 @@ void Sub::gcs_send_text_fmt(MAV_SEVERITY severity, const char *fmt, ...)
va_start(arg_list, fmt); va_start(arg_list, fmt);
va_end(arg_list); va_end(arg_list);
hal.util->vsnprintf((char *)str, sizeof(str), fmt, 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);
} }

View File

@ -220,6 +220,8 @@ private:
static const uint8_t num_gcs = MAVLINK_COMM_NUM_BUFFERS; static const uint8_t num_gcs = MAVLINK_COMM_NUM_BUFFERS;
GCS_MAVLINK_Sub gcs_chan[MAVLINK_COMM_NUM_BUFFERS]; GCS_MAVLINK_Sub gcs_chan[MAVLINK_COMM_NUM_BUFFERS];
GCS _gcs; // avoid using this; use gcs()
GCS &gcs() { return _gcs; }
// User variables // User variables
#ifdef USERHOOK_VARIABLES #ifdef USERHOOK_VARIABLES

View File

@ -147,7 +147,7 @@ void Sub::init_ardupilot()
log_init(); log_init();
#endif #endif
GCS_MAVLINK::set_dataflash(&DataFlash); gcs().set_dataflash(&DataFlash);
// update motor interlock state // update motor interlock state
update_using_interlock(); update_using_interlock();