Commit 58fd244a authored by Gus Grubba's avatar Gus Grubba

iOS fully functional.

parent 339da87a
...@@ -29,15 +29,22 @@ TaisyncHandler::~TaisyncHandler() ...@@ -29,15 +29,22 @@ TaisyncHandler::~TaisyncHandler()
} }
//----------------------------------------------------------------------------- //-----------------------------------------------------------------------------
void bool TaisyncHandler::close()
TaisyncHandler::close()
{ {
bool res = (_tcpSocket || _tcpServer);
if(_tcpSocket) { if(_tcpSocket) {
qCDebug(TaisyncLog) << "Close Taisync TCP"; qCDebug(TaisyncLog) << "Close Taisync TCP socket on port" << _tcpSocket->localPort();
_tcpSocket->close(); _tcpSocket->close();
_tcpSocket->deleteLater(); _tcpSocket->deleteLater();
_tcpSocket = nullptr; _tcpSocket = nullptr;
} }
if(_tcpServer) {
qCDebug(TaisyncLog) << "Close Taisync TCP server on port" << _tcpServer->serverPort();;
_tcpServer->close();
_tcpServer->deleteLater();
_tcpServer = nullptr;
}
return res;
} }
//----------------------------------------------------------------------------- //-----------------------------------------------------------------------------
...@@ -47,10 +54,12 @@ TaisyncHandler::_start(uint16_t port, QHostAddress addr) ...@@ -47,10 +54,12 @@ TaisyncHandler::_start(uint16_t port, QHostAddress addr)
close(); close();
_serverMode = addr == QHostAddress::AnyIPv4; _serverMode = addr == QHostAddress::AnyIPv4;
if(_serverMode) { if(_serverMode) {
qCDebug(TaisyncLog) << "Listen for Taisync TCP on port" << port; if(!_tcpServer) {
_tcpServer = new QTcpServer(this); qCDebug(TaisyncLog) << "Listen for Taisync TCP on port" << port;
QObject::connect(_tcpServer, &QTcpServer::newConnection, this, &TaisyncHandler::_newConnection); _tcpServer = new QTcpServer(this);
_tcpServer->listen(QHostAddress::AnyIPv4, port); QObject::connect(_tcpServer, &QTcpServer::newConnection, this, &TaisyncHandler::_newConnection);
_tcpServer->listen(QHostAddress::AnyIPv4, port);
}
} else { } else {
_tcpSocket = new QTcpSocket(); _tcpSocket = new QTcpSocket();
QObject::connect(_tcpSocket, &QIODevice::readyRead, this, &TaisyncHandler::_readBytes); QObject::connect(_tcpSocket, &QIODevice::readyRead, this, &TaisyncHandler::_readBytes);
...@@ -69,24 +78,30 @@ TaisyncHandler::_start(uint16_t port, QHostAddress addr) ...@@ -69,24 +78,30 @@ TaisyncHandler::_start(uint16_t port, QHostAddress addr)
void void
TaisyncHandler::_newConnection() TaisyncHandler::_newConnection()
{ {
qCDebug(TaisyncLog) << "New Taisync TCP Connection"; qCDebug(TaisyncLog) << "New Taisync TCP Connection on port" << _tcpServer->serverPort();
if(_tcpSocket) { if(_tcpSocket) {
_tcpSocket->close(); _tcpSocket->close();
_tcpSocket->deleteLater(); _tcpSocket->deleteLater();
} }
_tcpSocket = _tcpServer->nextPendingConnection(); _tcpSocket = _tcpServer->nextPendingConnection();
QObject::connect(_tcpSocket, &QIODevice::readyRead, this, &TaisyncHandler::_readBytes); if(_tcpSocket) {
emit connected(); QObject::connect(_tcpSocket, &QIODevice::readyRead, this, &TaisyncHandler::_readBytes);
QObject::connect(_tcpSocket, &QAbstractSocket::disconnected, this, &TaisyncHandler::_socketDisconnected);
emit connected();
} else {
qCWarning(TaisyncLog) << "New Taisync TCP Connection provided no socket";
}
} }
//----------------------------------------------------------------------------- //-----------------------------------------------------------------------------
void void
TaisyncHandler::_socketDisconnected() TaisyncHandler::_socketDisconnected()
{ {
qCDebug(TaisyncLog) << "Taisync Telemetry Connection Closed"; qCDebug(TaisyncLog) << "Taisync TCP Connection Closed on port" << _tcpSocket->localPort();
if(_tcpSocket) { if(_tcpSocket) {
_tcpSocket->close(); _tcpSocket->close();
_tcpSocket->deleteLater(); _tcpSocket->deleteLater();
_tcpSocket = nullptr; _tcpSocket = nullptr;
} }
emit disconnected();
} }
...@@ -36,7 +36,8 @@ public: ...@@ -36,7 +36,8 @@ public:
explicit TaisyncHandler (QObject* parent = nullptr); explicit TaisyncHandler (QObject* parent = nullptr);
~TaisyncHandler (); ~TaisyncHandler ();
virtual bool start () = 0; virtual bool start () = 0;
virtual void close (); virtual bool close ();
virtual bool isServerRunning () { return (_serverMode && _tcpServer); }
protected: protected:
virtual bool _start (uint16_t port, QHostAddress addr = QHostAddress::AnyIPv4); virtual bool _start (uint16_t port, QHostAddress addr = QHostAddress::AnyIPv4);
...@@ -48,6 +49,7 @@ protected slots: ...@@ -48,6 +49,7 @@ protected slots:
signals: signals:
void connected (); void connected ();
void disconnected ();
protected: protected:
bool _serverMode = true; bool _serverMode = true;
......
...@@ -28,6 +28,13 @@ TaisyncManager::TaisyncManager(QGCApplication* app, QGCToolbox* toolbox) ...@@ -28,6 +28,13 @@ TaisyncManager::TaisyncManager(QGCApplication* app, QGCToolbox* toolbox)
//----------------------------------------------------------------------------- //-----------------------------------------------------------------------------
TaisyncManager::~TaisyncManager() TaisyncManager::~TaisyncManager()
{
_close();
}
//-----------------------------------------------------------------------------
void
TaisyncManager::_close()
{ {
if(_taiSettings) { if(_taiSettings) {
_taiSettings->close(); _taiSettings->close();
...@@ -55,21 +62,32 @@ TaisyncManager::~TaisyncManager() ...@@ -55,21 +62,32 @@ TaisyncManager::~TaisyncManager()
//----------------------------------------------------------------------------- //-----------------------------------------------------------------------------
void void
TaisyncManager::setToolbox(QGCToolbox* toolbox) TaisyncManager::_reset()
{ {
QGCTool::setToolbox(toolbox); _close();
_taiSettings = new TaisyncSettings(this); _taiSettings = new TaisyncSettings(this);
connect(_taiSettings, &TaisyncSettings::updateSettings, this, &TaisyncManager::_updateSettings); connect(_taiSettings, &TaisyncSettings::updateSettings, this, &TaisyncManager::_updateSettings);
connect(_taiSettings, &TaisyncSettings::connected, this, &TaisyncManager::_connected); connect(_taiSettings, &TaisyncSettings::connected, this, &TaisyncManager::_connected);
_appSettings = toolbox->settingsManager()->appSettings(); connect(_taiSettings, &TaisyncSettings::disconnected, this, &TaisyncManager::_disconnected);
connect(_appSettings->enableTaisync(), &Fact::rawValueChanged, this, &TaisyncManager::_setEnabled); if(!_appSettings) {
connect(_appSettings->enableTaisyncVideo(), &Fact::rawValueChanged, this, &TaisyncManager::_setVideoEnabled); _appSettings = _toolbox->settingsManager()->appSettings();
connect(_appSettings->enableTaisync(), &Fact::rawValueChanged, this, &TaisyncManager::_setEnabled);
connect(_appSettings->enableTaisyncVideo(), &Fact::rawValueChanged, this, &TaisyncManager::_setVideoEnabled);
}
_setEnabled(); _setEnabled();
if(_enabled) { if(_enabled) {
_setVideoEnabled(); _setVideoEnabled();
} }
} }
//-----------------------------------------------------------------------------
void
TaisyncManager::setToolbox(QGCToolbox* toolbox)
{
QGCTool::setToolbox(toolbox);
_reset();
}
//----------------------------------------------------------------------------- //-----------------------------------------------------------------------------
void void
TaisyncManager::setDecodeIndex(int idx) TaisyncManager::setDecodeIndex(int idx)
...@@ -91,24 +109,22 @@ TaisyncManager::_setEnabled() ...@@ -91,24 +109,22 @@ TaisyncManager::_setEnabled()
bool enable = _appSettings->enableTaisync()->rawValue().toBool(); bool enable = _appSettings->enableTaisync()->rawValue().toBool();
if(enable) { if(enable) {
#if defined(__ios__) || defined(__android__) #if defined(__ios__) || defined(__android__)
_taiTelemetery = new TaisyncTelemetry(this); if(!_taiTelemetery) {
QObject::connect(_taiTelemetery, &TaisyncTelemetry::bytesReady, this, &TaisyncManager::_readTelemBytes); _taiTelemetery = new TaisyncTelemetry(this);
_telemetrySocket = new QUdpSocket(this); QObject::connect(_taiTelemetery, &TaisyncTelemetry::bytesReady, this, &TaisyncManager::_readTelemBytes);
_telemetrySocket->setSocketOption(QAbstractSocket::SendBufferSizeSocketOption, 64 * 1024); _telemetrySocket = new QUdpSocket(this);
_telemetrySocket->setSocketOption(QAbstractSocket::ReceiveBufferSizeSocketOption, 64 * 1024); _telemetrySocket->setSocketOption(QAbstractSocket::SendBufferSizeSocketOption, 64 * 1024);
QObject::connect(_telemetrySocket, &QUdpSocket::readyRead, this, &TaisyncManager::_readUDPBytes); _telemetrySocket->setSocketOption(QAbstractSocket::ReceiveBufferSizeSocketOption, 64 * 1024);
_telemetrySocket->bind(QHostAddress::LocalHost, 0, QUdpSocket::ShareAddress); QObject::connect(_telemetrySocket, &QUdpSocket::readyRead, this, &TaisyncManager::_readUDPBytes);
_telemetrySocket->bind(QHostAddress::LocalHost, 0, QUdpSocket::ShareAddress);
_taiTelemetery->start();
}
#endif #endif
_workTimer.start(1000); _workTimer.start(1000);
} else { } else {
#if defined(__ios__) || defined(__android__) //-- Stop everything
if (_taiTelemetery) {
_taiTelemetery->close();
_taiTelemetery->deleteLater();
_taiTelemetery = nullptr;
}
#endif
_workTimer.stop(); _workTimer.stop();
_close();
} }
_enabled = enable; _enabled = enable;
} }
...@@ -119,23 +135,27 @@ TaisyncManager::_setVideoEnabled() ...@@ -119,23 +135,27 @@ TaisyncManager::_setVideoEnabled()
{ {
bool enable = _appSettings->enableTaisyncVideo()->rawValue().toBool(); bool enable = _appSettings->enableTaisyncVideo()->rawValue().toBool();
if(enable) { if(enable) {
//-- Hide video selection as we will be fixed to Taisync video and set the way we need it. if(!_savedVideoSource.isValid()) {
VideoSettings* pVSettings = qgcApp()->toolbox()->settingsManager()->videoSettings(); //-- Hide video selection as we will be fixed to Taisync video and set the way we need it.
//-- First save current state VideoSettings* pVSettings = qgcApp()->toolbox()->settingsManager()->videoSettings();
_savedVideoSource = pVSettings->videoSource()->rawValue(); //-- First save current state
_savedVideoUDP = pVSettings->udpPort()->rawValue(); _savedVideoSource = pVSettings->videoSource()->rawValue();
_savedAR = pVSettings->aspectRatio()->rawValue(); _savedVideoUDP = pVSettings->udpPort()->rawValue();
_savedVideoState = pVSettings->visible(); _savedAR = pVSettings->aspectRatio()->rawValue();
//-- Now set it up the way we need it do be _savedVideoState = pVSettings->visible();
pVSettings->setVisible(false); //-- Now set it up the way we need it do be
pVSettings->udpPort()->setRawValue(5600); pVSettings->setVisible(false);
pVSettings->aspectRatio()->setRawValue(1024.0 / 768.0); pVSettings->udpPort()->setRawValue(5600);
pVSettings->videoSource()->setRawValue(QString(VideoSettings::videoSourceUDP)); pVSettings->aspectRatio()->setRawValue(1024.0 / 768.0);
pVSettings->videoSource()->setRawValue(QString(VideoSettings::videoSourceUDP));
}
#if defined(__ios__) || defined(__android__) #if defined(__ios__) || defined(__android__)
//-- iOS and Android receive raw h.264 and need a different pipeline if(!_taiVideo) {
qgcApp()->toolbox()->videoManager()->setIsTaisync(true); //-- iOS and Android receive raw h.264 and need a different pipeline
_taiVideo = new TaisyncVideoReceiver(this); qgcApp()->toolbox()->videoManager()->setIsTaisync(true);
_taiVideo->start(); _taiVideo = new TaisyncVideoReceiver(this);
_taiVideo->start();
}
#endif #endif
} else { } else {
//-- Restore video settings //-- Restore video settings
...@@ -197,13 +217,25 @@ TaisyncManager::_connected() ...@@ -197,13 +217,25 @@ TaisyncManager::_connected()
emit connectedChanged(); emit connectedChanged();
} }
//-----------------------------------------------------------------------------
void
TaisyncManager::_disconnected()
{
qCDebug(TaisyncLog) << "Taisync Settings Disconnected";
_isConnected = false;
emit connectedChanged();
_reset();
}
//----------------------------------------------------------------------------- //-----------------------------------------------------------------------------
void void
TaisyncManager::_checkTaisync() TaisyncManager::_checkTaisync()
{ {
if(_enabled) { if(_enabled) {
if(!_isConnected) { if(!_isConnected) {
_taiSettings->start(); if(!_taiSettings->isServerRunning()) {
_taiSettings->start();
}
} else { } else {
if(++_currReq >= REQ_LAST) { if(++_currReq >= REQ_LAST) {
_currReq = REQ_LINK_STATUS; _currReq = REQ_LINK_STATUS;
...@@ -221,9 +253,12 @@ TaisyncManager::_checkTaisync() ...@@ -221,9 +253,12 @@ TaisyncManager::_checkTaisync()
case REQ_VIDEO_SETTINGS: case REQ_VIDEO_SETTINGS:
_taiSettings->requestVideoSettings(); _taiSettings->requestVideoSettings();
break; break;
case REQ_RADIO_SETTINGS:
_taiSettings->requestRadioSettings();
break;
} }
} }
_workTimer.start(1000); _workTimer.start(_isConnected ? 500 : 5000);
} }
} }
...@@ -241,18 +276,37 @@ TaisyncManager::_updateSettings(QByteArray jSonData) ...@@ -241,18 +276,37 @@ TaisyncManager::_updateSettings(QByteArray jSonData)
QJsonObject jObj = doc.object(); QJsonObject jObj = doc.object();
//-- Link Status? //-- Link Status?
if(jSonData.contains("\"flight\":")) { if(jSonData.contains("\"flight\":")) {
_linkConnected = jObj["flight"].toString("") == "online"; bool tlinkConnected = jObj["flight"].toString("") == "online";
_linkVidFormat = jObj["videoformat"].toString(_linkVidFormat); if(tlinkConnected != _linkConnected) {
_downlinkRSSI = jObj["radiorssi"].toInt(_downlinkRSSI); _linkConnected = tlinkConnected;
_uplinkRSSI = jObj["hdrssi"].toInt(_uplinkRSSI); emit linkConnectedChanged();
emit linkChanged(); }
QString tlinkVidFormat = jObj["videoformat"].toString(_linkVidFormat);
int tdownlinkRSSI = jObj["radiorssi"].toInt(_downlinkRSSI);
int tuplinkRSSI = jObj["hdrssi"].toInt(_uplinkRSSI);
if(_linkVidFormat != tlinkVidFormat || _downlinkRSSI != tdownlinkRSSI || _uplinkRSSI != tuplinkRSSI) {
_linkVidFormat = tlinkVidFormat;
_downlinkRSSI = tdownlinkRSSI;
_uplinkRSSI = tuplinkRSSI;
emit linkChanged();
}
//-- Device Info? //-- Device Info?
} else if(jSonData.contains("\"firmwareversion\":")) { } else if(jSonData.contains("\"firmwareversion\":")) {
_fwVersion = jObj["firmwareversion"].toString(_fwVersion); QString tfwVersion = jObj["firmwareversion"].toString(_fwVersion);
_serialNumber = jObj["sn"].toString(_serialNumber); QString tserialNumber = jObj["sn"].toString(_serialNumber);
if(tfwVersion != _fwVersion || tserialNumber != _serialNumber) {
_fwVersion = tfwVersion;
_serialNumber = tserialNumber;
emit infoChanged();
}
//-- Radio Settings?
} else if(jSonData.contains("\"freq\":")) {
// {\"mode\":\"auto\",\"freq\":\"ch12\"}
//-- Video Settings? //-- Video Settings?
} else if(jSonData.contains("\"maxbitrate\":")) { } else if(jSonData.contains("\"maxbitrate\":")) {
//{\"decode\":\"phone\",\"mode\":\"h264\",\"maxbitrate\":\"high\"}
} }
......
...@@ -29,12 +29,12 @@ class TaisyncManager : public QGCTool ...@@ -29,12 +29,12 @@ class TaisyncManager : public QGCTool
public: public:
Q_PROPERTY(bool connected READ connected NOTIFY connectedChanged) Q_PROPERTY(bool connected READ connected NOTIFY connectedChanged)
Q_PROPERTY(bool linkConnected READ linkConnected NOTIFY linkChanged) Q_PROPERTY(bool linkConnected READ linkConnected NOTIFY linkConnectedChanged)
Q_PROPERTY(QString linkVidFormat READ linkVidFormat NOTIFY linkChanged) Q_PROPERTY(QString linkVidFormat READ linkVidFormat NOTIFY linkChanged)
Q_PROPERTY(int uplinkRSSI READ uplinkRSSI NOTIFY linkChanged) Q_PROPERTY(int uplinkRSSI READ uplinkRSSI NOTIFY linkChanged)
Q_PROPERTY(int downlinkRSSI READ downlinkRSSI NOTIFY linkChanged) Q_PROPERTY(int downlinkRSSI READ downlinkRSSI NOTIFY linkChanged)
Q_PROPERTY(QString serialNumber READ serialNumber NOTIFY linkChanged) Q_PROPERTY(QString serialNumber READ serialNumber NOTIFY infoChanged)
Q_PROPERTY(QString fwVersion READ fwVersion NOTIFY linkChanged) Q_PROPERTY(QString fwVersion READ fwVersion NOTIFY infoChanged)
Q_PROPERTY(QStringList decodeList READ decodeList NOTIFY decodeIndexChanged) Q_PROPERTY(QStringList decodeList READ decodeList NOTIFY decodeIndexChanged)
Q_PROPERTY(int decodeIndex READ decodeIndex WRITE setDecodeIndex NOTIFY decodeIndexChanged) Q_PROPERTY(int decodeIndex READ decodeIndex WRITE setDecodeIndex NOTIFY decodeIndexChanged)
Q_PROPERTY(QStringList rateList READ rateList NOTIFY rateIndexChanged) Q_PROPERTY(QStringList rateList READ rateList NOTIFY rateIndexChanged)
...@@ -61,12 +61,15 @@ public: ...@@ -61,12 +61,15 @@ public:
signals: signals:
void linkChanged (); void linkChanged ();
void linkConnectedChanged ();
void infoChanged ();
void connectedChanged (); void connectedChanged ();
void decodeIndexChanged (); void decodeIndexChanged ();
void rateIndexChanged (); void rateIndexChanged ();
private slots: private slots:
void _connected (); void _connected ();
void _disconnected ();
void _checkTaisync (); void _checkTaisync ();
void _updateSettings (QByteArray jSonData); void _updateSettings (QByteArray jSonData);
void _setEnabled (); void _setEnabled ();
...@@ -76,6 +79,10 @@ private slots: ...@@ -76,6 +79,10 @@ private slots:
void _readTelemBytes (QByteArray bytesIn); void _readTelemBytes (QByteArray bytesIn);
#endif #endif
private:
void _close ();
void _reset ();
private: private:
enum { enum {
...@@ -83,6 +90,7 @@ private: ...@@ -83,6 +90,7 @@ private:
REQ_DEV_INFO, REQ_DEV_INFO,
REQ_FREQ_SCAN, REQ_FREQ_SCAN,
REQ_VIDEO_SETTINGS, REQ_VIDEO_SETTINGS,
REQ_RADIO_SETTINGS,
REQ_LAST REQ_LAST
}; };
......
...@@ -44,47 +44,43 @@ bool TaisyncSettings::start() ...@@ -44,47 +44,43 @@ bool TaisyncSettings::start()
bool bool
TaisyncSettings::requestLinkStatus() TaisyncSettings::requestLinkStatus()
{ {
if(_tcpSocket) { return _request("/v1/baseband.json");
QString req = QString(kGetReq).arg("/v1/baseband.json");
//qCDebug(TaisyncVerbose) << "Request" << req;
_tcpSocket->write(req.toUtf8());
return true;
}
return false;
} }
//----------------------------------------------------------------------------- //-----------------------------------------------------------------------------
bool bool
TaisyncSettings::requestDevInfo() TaisyncSettings::requestDevInfo()
{ {
if(_tcpSocket) { return _request("/v1/device.json");
QString req = QString(kGetReq).arg("/v1/device.json");
//qCDebug(TaisyncVerbose) << "Request" << req;
_tcpSocket->write(req.toUtf8());
return true;
}
return false;
} }
//----------------------------------------------------------------------------- //-----------------------------------------------------------------------------
bool bool
TaisyncSettings::requestFreqScan() TaisyncSettings::requestFreqScan()
{ {
if(_tcpSocket) { return _request("/v1/freqscan.json");
QString req = QString(kGetReq).arg("/v1/freqscan.json");
//qCDebug(TaisyncVerbose) << "Request" << req;
_tcpSocket->write(req.toUtf8());
return true;
}
return false;
} }
//----------------------------------------------------------------------------- //-----------------------------------------------------------------------------
bool bool
TaisyncSettings::requestVideoSettings() TaisyncSettings::requestVideoSettings()
{
return _request("/v1/video.json");
}
//-----------------------------------------------------------------------------
bool
TaisyncSettings::requestRadioSettings()
{
return _request("/v1/radio.json");
}
//-----------------------------------------------------------------------------
bool
TaisyncSettings::_request(const QString& request)
{ {
if(_tcpSocket) { if(_tcpSocket) {
QString req = QString(kGetReq).arg("/v1/video.json"); QString req = QString(kGetReq).arg(request);
//qCDebug(TaisyncVerbose) << "Request" << req; //qCDebug(TaisyncVerbose) << "Request" << req;
_tcpSocket->write(req.toUtf8()); _tcpSocket->write(req.toUtf8());
return true; return true;
......
...@@ -21,6 +21,7 @@ public: ...@@ -21,6 +21,7 @@ public:
bool requestDevInfo (); bool requestDevInfo ();
bool requestFreqScan (); bool requestFreqScan ();
bool requestVideoSettings (); bool requestVideoSettings ();
bool requestRadioSettings ();
signals: signals:
void updateSettings (QByteArray jSonData); void updateSettings (QByteArray jSonData);
...@@ -28,4 +29,6 @@ signals: ...@@ -28,4 +29,6 @@ signals:
protected slots: protected slots:
void _readBytes () override; void _readBytes () override;
private:
bool _request (const QString& request);
}; };
...@@ -39,7 +39,7 @@ QGCView { ...@@ -39,7 +39,7 @@ QGCView {
property real _panelWidth: _qgcView.width * _internalWidthRatio property real _panelWidth: _qgcView.width * _internalWidthRatio
property Fact _taisyncEnabledFact: QGroundControl.settingsManager.appSettings.enableTaisync property Fact _taisyncEnabledFact: QGroundControl.settingsManager.appSettings.enableTaisync
property Fact _taisyncVideoEnabledFact: QGroundControl.settingsManager.appSettings.enableTaisyncVideo property Fact _taisyncVideoEnabledFact: QGroundControl.settingsManager.appSettings.enableTaisyncVideo
property bool _taisyncEnabled: _taisyncVideoEnabledFact.rawValue property bool _taisyncEnabled: _taisyncEnabledFact.rawValue
readonly property real _internalWidthRatio: 0.8 readonly property real _internalWidthRatio: 0.8
......
...@@ -12,9 +12,6 @@ ...@@ -12,9 +12,6 @@
#include "QGCApplication.h" #include "QGCApplication.h"
#include "VideoManager.h" #include "VideoManager.h"
QGC_LOGGING_CATEGORY(TaisyncTelemetryLog, "TaisyncTelemetryLog")
//----------------------------------------------------------------------------- //-----------------------------------------------------------------------------
TaisyncTelemetry::TaisyncTelemetry(QObject* parent) TaisyncTelemetry::TaisyncTelemetry(QObject* parent)
: TaisyncHandler(parent) : TaisyncHandler(parent)
...@@ -22,18 +19,33 @@ TaisyncTelemetry::TaisyncTelemetry(QObject* parent) ...@@ -22,18 +19,33 @@ TaisyncTelemetry::TaisyncTelemetry(QObject* parent)
} }
//----------------------------------------------------------------------------- //-----------------------------------------------------------------------------
void bool
TaisyncTelemetry::close() TaisyncTelemetry::close()
{ {
TaisyncHandler::close(); if(_mavlinkChannel >= 0) {
qCDebug(TaisyncTelemetryLog) << "Close Taisync Telemetry"; qgcApp()->toolbox()->linkManager()->_freeMavlinkChannel(_mavlinkChannel);
_mavlinkChannel = -1;
}
if(TaisyncHandler::close()) {
qCDebug(TaisyncLog) << "Close Taisync Telemetry";
return true;
}
return false;
} }
//----------------------------------------------------------------------------- //-----------------------------------------------------------------------------
bool TaisyncTelemetry::start() bool TaisyncTelemetry::start()
{ {
qCDebug(TaisyncTelemetryLog) << "Start Taisync Telemetry"; qCDebug(TaisyncLog) << "Start Taisync Telemetry";
return _start(TAISYNC_TELEM_PORT); if(_start(TAISYNC_TELEM_PORT)) {
_mavlinkChannel = qgcApp()->toolbox()->linkManager()->_reserveMavlinkChannel();
_heartbeatTimer.setInterval(1000);
_heartbeatTimer.setSingleShot(false);
connect(&_heartbeatTimer, &QTimer::timeout, this, &TaisyncTelemetry::_sendGCSHeartbeat);
_heartbeatTimer.start();
return true;
}
return false;
} }
//----------------------------------------------------------------------------- //-----------------------------------------------------------------------------
...@@ -50,15 +62,43 @@ void ...@@ -50,15 +62,43 @@ void
TaisyncTelemetry::_newConnection() TaisyncTelemetry::_newConnection()
{ {
TaisyncHandler::_newConnection(); TaisyncHandler::_newConnection();
qCDebug(TaisyncTelemetryLog) << "New Taisync Temeletry Connection"; qCDebug(TaisyncLog) << "New Taisync Temeletry Connection";
} }
//----------------------------------------------------------------------------- //-----------------------------------------------------------------------------
void void
TaisyncTelemetry::_readBytes() TaisyncTelemetry::_readBytes()
{ {
_heartbeatTimer.stop();
while(_tcpSocket->bytesAvailable()) { while(_tcpSocket->bytesAvailable()) {
QByteArray bytesIn = _tcpSocket->read(_tcpSocket->bytesAvailable()); QByteArray bytesIn = _tcpSocket->read(_tcpSocket->bytesAvailable());
emit bytesReady(bytesIn); emit bytesReady(bytesIn);
} }
} }
//-----------------------------------------------------------------------------
void
TaisyncTelemetry::_sendGCSHeartbeat()
{
//-- TODO: This is temporary. We should not have to send out heartbeats for a link to start.
if(_tcpSocket) {
MAVLinkProtocol* pMavlinkProtocol = qgcApp()->toolbox()->mavlinkProtocol();
if(pMavlinkProtocol && _mavlinkChannel >= 0) {
qCDebug(TaisyncLog) << "Taisync heartbeat out";
mavlink_message_t message;
mavlink_msg_heartbeat_pack_chan(
static_cast<uint8_t>(pMavlinkProtocol->getSystemId()),
static_cast<uint8_t>(pMavlinkProtocol->getComponentId()),
static_cast<uint8_t>(_mavlinkChannel),
&message,
MAV_TYPE_GCS, // MAV_TYPE
MAV_AUTOPILOT_INVALID, // MAV_AUTOPILOT
MAV_MODE_MANUAL_ARMED, // MAV_MODE
0, // custom mode
MAV_STATE_ACTIVE); // MAV_STATE
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
int len = mavlink_msg_to_send_buffer(buffer, &message);
_tcpSocket->write(reinterpret_cast<const char*>(buffer), len);
}
}
}
...@@ -13,15 +13,13 @@ ...@@ -13,15 +13,13 @@
#include <QUdpSocket> #include <QUdpSocket>
#include <QTimer> #include <QTimer>
Q_DECLARE_LOGGING_CATEGORY(TaisyncTelemetryLog)
class TaisyncTelemetry : public TaisyncHandler class TaisyncTelemetry : public TaisyncHandler
{ {
Q_OBJECT Q_OBJECT
public: public:
explicit TaisyncTelemetry (QObject* parent = nullptr); explicit TaisyncTelemetry (QObject* parent = nullptr);
void close () override; bool close () override;
bool start () override; bool start () override;
void writeBytes (QByteArray bytes); void writeBytes (QByteArray bytes);
...@@ -31,5 +29,10 @@ signals: ...@@ -31,5 +29,10 @@ signals:
private slots: private slots:
void _newConnection () override; void _newConnection () override;
void _readBytes () override; void _readBytes () override;
void _sendGCSHeartbeat ();
private:
int _mavlinkChannel = -1;
QTimer _heartbeatTimer;
}; };
...@@ -12,9 +12,6 @@ ...@@ -12,9 +12,6 @@
#include "QGCApplication.h" #include "QGCApplication.h"
#include "VideoManager.h" #include "VideoManager.h"
QGC_LOGGING_CATEGORY(TaisyncVideoReceiverLog, "TaisyncVideoReceiverLog")
//----------------------------------------------------------------------------- //-----------------------------------------------------------------------------
TaisyncVideoReceiver::TaisyncVideoReceiver(QObject* parent) TaisyncVideoReceiver::TaisyncVideoReceiver(QObject* parent)
: TaisyncHandler(parent) : TaisyncHandler(parent)
...@@ -22,31 +19,39 @@ TaisyncVideoReceiver::TaisyncVideoReceiver(QObject* parent) ...@@ -22,31 +19,39 @@ TaisyncVideoReceiver::TaisyncVideoReceiver(QObject* parent)
} }
//----------------------------------------------------------------------------- //-----------------------------------------------------------------------------
void bool
TaisyncVideoReceiver::close() TaisyncVideoReceiver::close()
{ {
TaisyncHandler::close(); if(TaisyncHandler::close() || _udpVideoSocket) {
qCDebug(TaisyncVideoReceiverLog) << "Close Taisync Video Receiver"; qCDebug(TaisyncLog) << "Close Taisync Video Receiver";
if(_udpVideoSocket) { if(_udpVideoSocket) {
_udpVideoSocket->close(); _udpVideoSocket->close();
_udpVideoSocket->deleteLater(); _udpVideoSocket->deleteLater();
_udpVideoSocket = nullptr; _udpVideoSocket = nullptr;
}
return true;
} }
return false;
} }
//----------------------------------------------------------------------------- //-----------------------------------------------------------------------------
bool bool
TaisyncVideoReceiver::start() TaisyncVideoReceiver::start()
{ {
qCDebug(TaisyncVideoReceiverLog) << "Start Taisync Video Receiver"; qCDebug(TaisyncLog) << "Start Taisync Video Receiver";
_udpVideoSocket = new QUdpSocket(this); if(_start(TAISYNC_VIDEO_TCP_PORT)) {
return _start(TAISYNC_VIDEO_TCP_PORT); _udpVideoSocket = new QUdpSocket(this);
return true;
}
return false;
} }
//----------------------------------------------------------------------------- //-----------------------------------------------------------------------------
void void
TaisyncVideoReceiver::_readBytes() TaisyncVideoReceiver::_readBytes()
{ {
QByteArray bytesIn = _tcpSocket->read(_tcpSocket->bytesAvailable()); if(_udpVideoSocket) {
_udpVideoSocket->writeDatagram(bytesIn, QHostAddress::LocalHost, TAISYNC_VIDEO_UDP_PORT); QByteArray bytesIn = _tcpSocket->read(_tcpSocket->bytesAvailable());
_udpVideoSocket->writeDatagram(bytesIn, QHostAddress::LocalHost, TAISYNC_VIDEO_UDP_PORT);
}
} }
...@@ -12,8 +12,6 @@ ...@@ -12,8 +12,6 @@
#include "TaisyncHandler.h" #include "TaisyncHandler.h"
#include <QUdpSocket> #include <QUdpSocket>
Q_DECLARE_LOGGING_CATEGORY(TaisyncVideoReceiverLog)
class TaisyncVideoReceiver : public TaisyncHandler class TaisyncVideoReceiver : public TaisyncHandler
{ {
Q_OBJECT Q_OBJECT
...@@ -21,7 +19,7 @@ public: ...@@ -21,7 +19,7 @@ public:
explicit TaisyncVideoReceiver (QObject* parent = nullptr); explicit TaisyncVideoReceiver (QObject* parent = nullptr);
bool start () override; bool start () override;
void close () override; bool close () override;
private slots: private slots:
void _readBytes () override; void _readBytes () override;
......
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment