mirror of https://github.com/ArduPilot/ardupilot
Copter: support for a GCS singleton
This commit is contained in:
parent
f49f153da0
commit
029aeeb4fd
|
@ -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
|
||||
|
|
|
@ -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);
|
||||
}
|
||||
|
||||
|
|
|
@ -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;
|
||||
|
|
Loading…
Reference in New Issue