Browse Source

AP_Frsky_Telem: make frsky_telemetry available to GCS_MAVLINK

master
floaledm 8 years ago committed by Andrew Tridgell
parent
commit
60c59bea4d
  1. 4
      libraries/AP_Frsky_Telem/AP_Frsky_Telem.cpp

4
libraries/AP_Frsky_Telem/AP_Frsky_Telem.cpp

@ -20,6 +20,8 @@ @@ -20,6 +20,8 @@
FRSKY Telemetry library
*/
#include "AP_Frsky_Telem.h"
#include <GCS_MAVLink/GCS.h>
extern const AP_HAL::HAL& hal;
ObjectArray<mavlink_statustext_t> AP_Frsky_Telem::_statustext_queue(FRSKY_TELEM_PAYLOAD_STATUS_CAPACITY);
@ -43,6 +45,8 @@ void AP_Frsky_Telem::init(const AP_SerialManager &serial_manager, const char *fi @@ -43,6 +45,8 @@ void AP_Frsky_Telem::init(const AP_SerialManager &serial_manager, const char *fi
_protocol = AP_SerialManager::SerialProtocol_FrSky_SPort; // FrSky SPort protocol (X-receivers)
} 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)
// make frsky_telemetry available to GCS_MAVLINK (used to queue statustext messages from GCS_MAVLINK)
GCS_MAVLINK::register_frsky_telemetry_callback(this);
// add firmware and frame info to message queue
queue_message(MAV_SEVERITY_INFO, firmware_str);
// save main parameters locally

Loading…
Cancel
Save