Browse Source

AP_Frsky_Telem: move FrSky handling to it's own thread

we are getting timing issues sharing with the other users of the IO
thread. The FrSky protocols are quite timing sensitive, so this should
help
master
Andrew Tridgell 6 years ago
parent
commit
7afd51d03e
  1. 43
      libraries/AP_Frsky_Telem/AP_Frsky_Telem.cpp
  2. 3
      libraries/AP_Frsky_Telem/AP_Frsky_Telem.h

43
libraries/AP_Frsky_Telem/AP_Frsky_Telem.cpp

@ -65,10 +65,13 @@ bool AP_Frsky_Telem::init() @@ -65,10 +65,13 @@ bool AP_Frsky_Telem::init()
}
if (_port != nullptr) {
hal.scheduler->register_io_process(FUNCTOR_BIND_MEMBER(&AP_Frsky_Telem::tick, void));
if (!hal.scheduler->thread_create(FUNCTOR_BIND_MEMBER(&AP_Frsky_Telem::loop, void),
"FrSky",
1024, AP_HAL::Scheduler::PRIORITY_RCIN, 1)) {
return false;
}
// we don't want flow control for either protocol
_port->set_flow_control(AP_HAL::UARTDriver::FLOW_CONTROL_DISABLE);
return true;
}
@ -342,27 +345,27 @@ void AP_Frsky_Telem::send_D(void) @@ -342,27 +345,27 @@ void AP_Frsky_Telem::send_D(void)
}
/*
* tick - main call to send data to the receiver (called by scheduler at 1kHz)
thread to loop handling bytes
*/
void AP_Frsky_Telem::tick(void)
void AP_Frsky_Telem::loop(void)
{
// check UART has been initialised
if (!_initialised_uart) {
// initialise uart (this must be called from within tick b/c the UART begin must be called from the same thread as it is used from)
if (_protocol == AP_SerialManager::SerialProtocol_FrSky_D) { // FrSky D protocol (D-receivers)
_port->begin(AP_SERIALMANAGER_FRSKY_D_BAUD, AP_SERIALMANAGER_FRSKY_BUFSIZE_RX, AP_SERIALMANAGER_FRSKY_BUFSIZE_TX);
} else { // FrSky SPort and SPort Passthrough (OpenTX) protocols (X-receivers)
_port->begin(AP_SERIALMANAGER_FRSKY_SPORT_BAUD, AP_SERIALMANAGER_FRSKY_BUFSIZE_RX, AP_SERIALMANAGER_FRSKY_BUFSIZE_TX);
}
_initialised_uart = true;// true when we have detected the protocol and UART has been initialised
// initialise uart (this must be called from within tick b/c the UART begin must be called from the same thread as it is used from)
if (_protocol == AP_SerialManager::SerialProtocol_FrSky_D) { // FrSky D protocol (D-receivers)
_port->begin(AP_SERIALMANAGER_FRSKY_D_BAUD, AP_SERIALMANAGER_FRSKY_BUFSIZE_RX, AP_SERIALMANAGER_FRSKY_BUFSIZE_TX);
} else { // FrSky SPort and SPort Passthrough (OpenTX) protocols (X-receivers)
_port->begin(AP_SERIALMANAGER_FRSKY_SPORT_BAUD, AP_SERIALMANAGER_FRSKY_BUFSIZE_RX, AP_SERIALMANAGER_FRSKY_BUFSIZE_TX);
}
if (_protocol == AP_SerialManager::SerialProtocol_FrSky_D) { // FrSky D protocol (D-receivers)
send_D();
} else if (_protocol == AP_SerialManager::SerialProtocol_FrSky_SPort) { // FrSky SPort protocol (X-receivers)
send_SPort();
} else if (_protocol == AP_SerialManager::SerialProtocol_FrSky_SPort_Passthrough) { // FrSky SPort Passthrough (OpenTX) protocol (X-receivers)
send_SPort_Passthrough();
_port->set_unbuffered_writes(true);
while (true) {
hal.scheduler->delay(1);
if (_protocol == AP_SerialManager::SerialProtocol_FrSky_D) { // FrSky D protocol (D-receivers)
send_D();
} else if (_protocol == AP_SerialManager::SerialProtocol_FrSky_SPort) { // FrSky SPort protocol (X-receivers)
send_SPort();
} else if (_protocol == AP_SerialManager::SerialProtocol_FrSky_SPort_Passthrough) { // FrSky SPort Passthrough (OpenTX) protocol (X-receivers)
send_SPort_Passthrough();
}
}
}

3
libraries/AP_Frsky_Telem/AP_Frsky_Telem.h

@ -133,7 +133,6 @@ public: @@ -133,7 +133,6 @@ public:
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;
uint32_t check_sensor_status_timer;
@ -203,7 +202,7 @@ private: @@ -203,7 +202,7 @@ private:
// main transmission function when protocol is FrSky D
void send_D(void);
// tick - main call to send updates to transmitter (called by scheduler at 1kHz)
void tick(void);
void loop(void);
// methods related to the nuts-and-bolts of sending data
void calc_crc(uint8_t byte);

Loading…
Cancel
Save