mirror of https://github.com/ArduPilot/ardupilot
Plane: Support for a GCS singleton
This commit is contained in:
parent
d060670ba3
commit
49bf336539
|
@ -2178,7 +2178,7 @@ void Plane::gcs_update(void)
|
|||
|
||||
void Plane::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);
|
||||
}
|
||||
|
||||
|
@ -2194,7 +2194,7 @@ void Plane::gcs_send_text_fmt(MAV_SEVERITY severity, const char *fmt, ...)
|
|||
va_start(arg_list, fmt);
|
||||
hal.util->vsnprintf((char *)str, sizeof(str), fmt, arg_list);
|
||||
va_end(arg_list);
|
||||
GCS_MAVLINK::send_statustext(severity, 0xFF, str);
|
||||
gcs().send_statustext(severity, 0xFF, str);
|
||||
notify.send_text(str);
|
||||
}
|
||||
|
||||
|
@ -2218,7 +2218,7 @@ void Plane::gcs_send_airspeed_calibration(const Vector3f &vg)
|
|||
void Plane::gcs_retry_deferred(void)
|
||||
{
|
||||
gcs_send_message(MSG_RETRY_DEFERRED);
|
||||
GCS_MAVLINK::service_statustext();
|
||||
gcs().service_statustext();
|
||||
}
|
||||
|
||||
/*
|
||||
|
|
|
@ -252,6 +252,8 @@ private:
|
|||
AP_SerialManager serial_manager;
|
||||
const uint8_t num_gcs = MAVLINK_COMM_NUM_BUFFERS;
|
||||
GCS_MAVLINK_Plane gcs_chan[MAVLINK_COMM_NUM_BUFFERS];
|
||||
GCS _gcs; // avoid using this; use gcs()
|
||||
GCS &gcs() { return _gcs; }
|
||||
|
||||
// selected navigation controller
|
||||
AP_Navigation *nav_controller = &L1_controller;
|
||||
|
|
|
@ -116,7 +116,7 @@ void Plane::init_ardupilot()
|
|||
}
|
||||
#endif
|
||||
|
||||
GCS_MAVLINK::set_dataflash(&DataFlash);
|
||||
gcs().set_dataflash(&DataFlash);
|
||||
|
||||
mavlink_system.sysid = g.sysid_this_mav;
|
||||
|
||||
|
|
Loading…
Reference in New Issue