mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_FrSky_Telem: allow for external library to send SPort data
this provides the API needed for AP_RCProtocol_FPort to send passthrough data over FPORT
This commit is contained in:
parent
e9dded98ce
commit
49f81fbd18
@ -37,25 +37,24 @@
|
||||
|
||||
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)
|
||||
{
|
||||
singleton = this;
|
||||
}
|
||||
|
||||
AP_Frsky_Telem::~AP_Frsky_Telem(void)
|
||||
{
|
||||
singleton = nullptr;
|
||||
}
|
||||
|
||||
/*
|
||||
* init - perform required initialisation
|
||||
setup ready for passthrough telem
|
||||
*/
|
||||
bool AP_Frsky_Telem::init()
|
||||
void AP_Frsky_Telem::setup_passthrough(void)
|
||||
{
|
||||
const AP_SerialManager &serial_manager = AP::serialmanager();
|
||||
|
||||
// check for protocol configured for a serial port - only the first serial port with one of these protocols will then run (cannot have FrSky on multiple serial ports)
|
||||
if ((_port = serial_manager.find_serial(AP_SerialManager::SerialProtocol_FrSky_D, 0))) {
|
||||
_protocol = AP_SerialManager::SerialProtocol_FrSky_D; // FrSky D protocol (D-receivers)
|
||||
} else if ((_port = serial_manager.find_serial(AP_SerialManager::SerialProtocol_FrSky_SPort, 0))) {
|
||||
_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)
|
||||
// add firmware and frame info to message queue
|
||||
const char* _frame_string = gcs().frame_string();
|
||||
@ -83,6 +82,34 @@ bool AP_Frsky_Telem::init()
|
||||
_passthrough.packet_weight[10] = 1700; // 0x5007 parameters
|
||||
}
|
||||
|
||||
/*
|
||||
* init - perform required initialisation
|
||||
*/
|
||||
bool AP_Frsky_Telem::init()
|
||||
{
|
||||
const AP_SerialManager &serial_manager = AP::serialmanager();
|
||||
|
||||
// check for protocol configured for a serial port - only the first serial port with one of these protocols will then run (cannot have FrSky on multiple serial ports)
|
||||
if ((_port = serial_manager.find_serial(AP_SerialManager::SerialProtocol_FrSky_D, 0))) {
|
||||
_protocol = AP_SerialManager::SerialProtocol_FrSky_D; // FrSky D protocol (D-receivers)
|
||||
} else if ((_port = serial_manager.find_serial(AP_SerialManager::SerialProtocol_FrSky_SPort, 0))) {
|
||||
_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)
|
||||
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) {
|
||||
if (!hal.scheduler->thread_create(FUNCTOR_BIND_MEMBER(&AP_Frsky_Telem::loop, void),
|
||||
"FrSky",
|
||||
@ -499,6 +526,13 @@ void AP_Frsky_Telem::send_byte(uint8_t byte)
|
||||
*/
|
||||
void AP_Frsky_Telem::send_uint32(uint8_t frame, uint16_t id, uint32_t data)
|
||||
{
|
||||
if (use_external_data) {
|
||||
external_data.frame = frame;
|
||||
external_data.appid = id;
|
||||
external_data.data = data;
|
||||
external_data.pending = true;
|
||||
return;
|
||||
}
|
||||
send_byte(frame); // frame type
|
||||
uint8_t *bytes = (uint8_t*)&id;
|
||||
send_byte(bytes[0]); // LSB
|
||||
@ -1063,3 +1097,29 @@ uint32_t AP_Frsky_Telem::sensor_status_flags() const
|
||||
|
||||
return ~health & enabled & present;
|
||||
}
|
||||
|
||||
/*
|
||||
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 (!use_external_data) {
|
||||
// not initialised for external data
|
||||
return false;
|
||||
}
|
||||
passthrough_wfq_adaptive_scheduler(0);
|
||||
if (!external_data.pending) {
|
||||
return false;
|
||||
}
|
||||
frame = external_data.frame;
|
||||
appid = external_data.appid;
|
||||
data = external_data.data;
|
||||
external_data.pending = false;
|
||||
return true;
|
||||
}
|
||||
|
||||
namespace AP {
|
||||
AP_Frsky_Telem *frsky_telem() {
|
||||
return AP_Frsky_Telem::get_singleton();
|
||||
}
|
||||
};
|
||||
|
@ -114,6 +114,8 @@ class AP_Frsky_Telem {
|
||||
public:
|
||||
AP_Frsky_Telem();
|
||||
|
||||
~AP_Frsky_Telem();
|
||||
|
||||
/* Do not allow copies */
|
||||
AP_Frsky_Telem(const AP_Frsky_Telem &other) = delete;
|
||||
AP_Frsky_Telem &operator=(const AP_Frsky_Telem&) = delete;
|
||||
@ -130,6 +132,13 @@ public:
|
||||
// functioning correctly
|
||||
uint32_t sensor_status_flags() const;
|
||||
|
||||
static AP_Frsky_Telem *get_singleton(void) {
|
||||
return singleton;
|
||||
}
|
||||
|
||||
// get next telemetry data for external consumers of SPort data
|
||||
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
|
||||
AP_SerialManager::SerialProtocol _protocol; // protocol used - detected using SerialManager's SERIAL#_PROTOCOL parameter
|
||||
@ -244,4 +253,23 @@ private:
|
||||
void calc_nav_alt(void);
|
||||
float format_gps(float dec);
|
||||
void calc_gps_position(void);
|
||||
|
||||
// setup ready for passthrough operation
|
||||
void setup_passthrough(void);
|
||||
|
||||
static AP_Frsky_Telem *singleton;
|
||||
|
||||
// use_external_data is set when this library will
|
||||
// be providing data to another transport, such as FPort
|
||||
bool use_external_data;
|
||||
struct {
|
||||
uint8_t frame;
|
||||
uint16_t appid;
|
||||
uint32_t data;
|
||||
bool pending;
|
||||
} external_data;
|
||||
};
|
||||
|
||||
namespace AP {
|
||||
AP_Frsky_Telem *frsky_telem();
|
||||
};
|
||||
|
Loading…
Reference in New Issue
Block a user