From 9579e64a03e49b894ba79309ee16e8ef92dec3f0 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Wed, 1 Jan 2020 17:32:04 +1100 Subject: [PATCH] AP_Frsky_Telem: make get_telem_data() static auto-create the object when it is needed for FPort --- libraries/AP_Frsky_Telem/AP_Frsky_Telem.cpp | 38 +++++++++++---------- libraries/AP_Frsky_Telem/AP_Frsky_Telem.h | 7 ++-- 2 files changed, 25 insertions(+), 20 deletions(-) diff --git a/libraries/AP_Frsky_Telem/AP_Frsky_Telem.cpp b/libraries/AP_Frsky_Telem/AP_Frsky_Telem.cpp index f9b18179c9..28f8a97d4b 100644 --- a/libraries/AP_Frsky_Telem/AP_Frsky_Telem.cpp +++ b/libraries/AP_Frsky_Telem/AP_Frsky_Telem.cpp @@ -39,8 +39,9 @@ extern const AP_HAL::HAL& hal; AP_Frsky_Telem *AP_Frsky_Telem::singleton; -AP_Frsky_Telem::AP_Frsky_Telem(void) : - _statustext_queue(FRSKY_TELEM_PAYLOAD_STATUS_CAPACITY) +AP_Frsky_Telem::AP_Frsky_Telem(bool _external_data) : + _statustext_queue(FRSKY_TELEM_PAYLOAD_STATUS_CAPACITY), + use_external_data(_external_data) { singleton = this; } @@ -97,17 +98,6 @@ bool AP_Frsky_Telem::init() } else if ((_port = serial_manager.find_serial(AP_SerialManager::SerialProtocol_FrSky_SPort_Passthrough, 0))) { _protocol = AP_SerialManager::SerialProtocol_FrSky_SPort_Passthrough; // FrSky SPort and SPort Passthrough (OpenTX) protocols (X-receivers) setup_passthrough(); - } else if ((_port = serial_manager.find_serial(AP_SerialManager::SerialProtocol_RCIN, 0))) { - _protocol = AP_SerialManager::SerialProtocol_RCIN; // FrSky SPort over FPort - setup_passthrough(); - } - - if (_protocol == AP_SerialManager::SerialProtocol_RCIN) { - use_external_data = true; - setup_passthrough(); - // we don't setup the thread, as output is driven by the AP_RCProtocol library - // calling get_telem_data(); - return true; } if (_port != nullptr) { @@ -1101,12 +1091,8 @@ uint32_t AP_Frsky_Telem::sensor_status_flags() const /* fetch Sport data for an external transport, such as FPort */ -bool AP_Frsky_Telem::get_telem_data(uint8_t &frame, uint16_t &appid, uint32_t &data) +bool AP_Frsky_Telem::_get_telem_data(uint8_t &frame, uint16_t &appid, uint32_t &data) { - if (!use_external_data) { - // not initialised for external data - return false; - } passthrough_wfq_adaptive_scheduler(0); if (!external_data.pending) { return false; @@ -1118,6 +1104,22 @@ bool AP_Frsky_Telem::get_telem_data(uint8_t &frame, uint16_t &appid, uint32_t &d return true; } +/* + fetch Sport data for an external transport, such as FPort + */ +bool AP_Frsky_Telem::get_telem_data(uint8_t &frame, uint16_t &appid, uint32_t &data) +{ + if (!singleton && !hal.util->get_soft_armed()) { + // if telem data is requested when we are disarmed and don't + // yet have a AP_Frsky_Telem object then try to allocate one + new AP_Frsky_Telem(true); + } + if (!singleton) { + return false; + } + return singleton->_get_telem_data(frame, appid, data); +} + namespace AP { AP_Frsky_Telem *frsky_telem() { return AP_Frsky_Telem::get_singleton(); diff --git a/libraries/AP_Frsky_Telem/AP_Frsky_Telem.h b/libraries/AP_Frsky_Telem/AP_Frsky_Telem.h index e1cbb60855..0ffcb6918a 100644 --- a/libraries/AP_Frsky_Telem/AP_Frsky_Telem.h +++ b/libraries/AP_Frsky_Telem/AP_Frsky_Telem.h @@ -112,7 +112,7 @@ for FrSky SPort Passthrough class AP_Frsky_Telem { public: - AP_Frsky_Telem(); + AP_Frsky_Telem(bool external_data=false); ~AP_Frsky_Telem(); @@ -137,7 +137,7 @@ public: } // get next telemetry data for external consumers of SPort data - bool get_telem_data(uint8_t &frame, uint16_t &appid, uint32_t &data); + static bool get_telem_data(uint8_t &frame, uint16_t &appid, uint32_t &data); private: AP_HAL::UARTDriver *_port; // UART used to send data to FrSky receiver @@ -257,6 +257,9 @@ private: // setup ready for passthrough operation void setup_passthrough(void); + // get next telemetry data for external consumers of SPort data (internal function) + bool _get_telem_data(uint8_t &frame, uint16_t &appid, uint32_t &data); + static AP_Frsky_Telem *singleton; // use_external_data is set when this library will