AP_Frsky_Telem: use gcs() to get frame string

This commit is contained in:
Peter Barker 2019-03-01 17:08:03 +11:00 committed by Peter Barker
parent b12d20d86c
commit 680008ba4f
2 changed files with 1 additions and 4 deletions

View File

@ -50,6 +50,7 @@ void AP_Frsky_Telem::init(const uint32_t *ap_valuep)
_protocol = AP_SerialManager::SerialProtocol_FrSky_SPort_Passthrough; // FrSky SPort and SPort Passthrough (OpenTX) protocols (X-receivers)
// make frsky_telemetry available to GCS_MAVLINK (used to queue statustext messages from GCS_MAVLINK)
// add firmware and frame info to message queue
const char* _frame_string = gcs().frame_string();
if (_frame_string == nullptr) {
queue_message(MAV_SEVERITY_INFO, AP::fwversion().fw_string);
} else {

View File

@ -138,16 +138,12 @@ public:
static ObjectArray<mavlink_statustext_t> _statustext_queue;
void set_frame_string(const char *string) { _frame_string = string; }
private:
AP_HAL::UARTDriver *_port; // UART used to send data to FrSky receiver
AP_SerialManager::SerialProtocol _protocol; // protocol used - detected using SerialManager's SERIAL#_PROTOCOL parameter
bool _initialised_uart;
uint16_t _crc;
const char *_frame_string;
struct
{
uint32_t value;