Newer
Older
Gus Grubba
committed
/****************************************************************************
*
* (c) 2009-2016 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
*
* QGroundControl is licensed according to the terms in the file
* COPYING.md in the root of the source code directory.
*
****************************************************************************/
#include "TaisyncManager.h"
#include "TaisyncHandler.h"
#include "SettingsManager.h"
#include "QGCApplication.h"
#include "VideoManager.h"
static const char *kRADIO_MODE = "RadioMode";
static const char *kRADIO_CHANNEL = "RadioChannel";
static const char *kVIDEO_OUTPUT = "VideoOutput";
static const char *kVIDEO_MODE = "VideoMode";
static const char *kVIDEO_RATE = "VideoRate";
static const char *kLOCAL_IP = "LocalIP";
static const char *kREMOTE_IP = "RemoteIP";
static const char *kNET_MASK = "NetMask";
static const char *kRTSP_URI = "RTSPURI";
static const char *kRTSP_ACCOUNT = "RTSPAccount";
static const char *kRTSP_PASSWORD = "RTSPPassword";
Gus Grubba
committed
//-----------------------------------------------------------------------------
TaisyncManager::TaisyncManager(QGCApplication* app, QGCToolbox* toolbox)
: QGCTool(app, toolbox)
{
connect(&_workTimer, &QTimer::timeout, this, &TaisyncManager::_checkTaisync);
_workTimer.setSingleShot(true);
QSettings settings;
settings.beginGroup(kTAISYNC_GROUP);
_localIPAddr = settings.value(kLOCAL_IP, QString("192.168.199.33")).toString();
_remoteIPAddr = settings.value(kREMOTE_IP, QString("192.168.199.16")).toString();
_netMask = settings.value(kNET_MASK, QString("255.255.255.0")).toString();
_rtspURI = settings.value(kRTSP_URI, QString("rtsp://192.168.0.2")).toString();
_rtspAccount = settings.value(kRTSP_ACCOUNT, QString("admin")).toString();
_rtspPassword = settings.value(kRTSP_PASSWORD, QString("12345678")).toString();
Gus Grubba
committed
//-----------------------------------------------------------------------------
TaisyncManager::~TaisyncManager()
{
_close();
}
//-----------------------------------------------------------------------------
void
TaisyncManager::_close()
Gus Grubba
committed
{
if(_taiSettings) {
_taiSettings->close();
_taiSettings->deleteLater();
_taiSettings = nullptr;
}
#if defined(__ios__) || defined(__android__)
if (_taiTelemetery) {
_taiTelemetery->close();
_taiTelemetery->deleteLater();
_taiTelemetery = nullptr;
}
if(_telemetrySocket) {
_telemetrySocket->close();
_telemetrySocket->deleteLater();
_telemetrySocket = nullptr;
}
Gus Grubba
committed
if (_taiVideo) {
_taiVideo->close();
_taiVideo->deleteLater();
_taiVideo = nullptr;
}
#endif
}
//-----------------------------------------------------------------------------
void
Gus Grubba
committed
{
Gus Grubba
committed
_taiSettings = new TaisyncSettings(this);
connect(_taiSettings, &TaisyncSettings::updateSettings, this, &TaisyncManager::_updateSettings);
connect(_taiSettings, &TaisyncSettings::connected, this, &TaisyncManager::_connected);
connect(_taiSettings, &TaisyncSettings::disconnected, this, &TaisyncManager::_disconnected);
if(!_appSettings) {
_appSettings = _toolbox->settingsManager()->appSettings();
connect(_appSettings->enableTaisync(), &Fact::rawValueChanged, this, &TaisyncManager::_setEnabled);
connect(_appSettings->enableTaisyncVideo(), &Fact::rawValueChanged, this, &TaisyncManager::_setVideoEnabled);
}
Gus Grubba
committed
_setEnabled();
if(_enabled) {
_setVideoEnabled();
}
}
//-----------------------------------------------------------------------------
FactMetaData*
TaisyncManager::_createMetadata(const char* name, QStringList enums)
{
FactMetaData* metaData = new FactMetaData(FactMetaData::valueTypeUint32, name, this);
QQmlEngine::setObjectOwnership(metaData, QQmlEngine::CppOwnership);
metaData->setShortDescription(name);
metaData->setLongDescription(name);
metaData->setRawDefaultValue(QVariant(0));
metaData->setHasControl(true);
metaData->setReadOnly(false);
for(int i = 0; i < enums.size(); i++) {
metaData->addEnumInfo(enums[i], QVariant(i));
}
metaData->setRawMin(0);
metaData->setRawMin(enums.size() - 1);
return metaData;
}
//-----------------------------------------------------------------------------
void
TaisyncManager::setToolbox(QGCToolbox* toolbox)
{
QGCTool::setToolbox(toolbox);
QStringList enums;
enums.append(tr("Auto"));
enums.append(tr("Manual"));
FactMetaData* metaData = _createMetadata(kRADIO_MODE, enums);
_radioMode = new Fact(kTAISYNC_GROUP, metaData, this);
QQmlEngine::setObjectOwnership(_radioMode, QQmlEngine::CppOwnership);
_radioModeList.append("auto");
_radioModeList.append("manual");
connect(_radioMode, &Fact::_containerRawValueChanged, this, &TaisyncManager::_radioSettingsChanged);
}
{
//-- Radio Channel
FactMetaData* metaData = _createMetadata(kRADIO_CHANNEL, enums);
_radioChannel = new Fact(kTAISYNC_GROUP, metaData, this);
QQmlEngine::setObjectOwnership(_radioChannel, QQmlEngine::CppOwnership);
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
connect(_radioChannel, &Fact::_containerRawValueChanged, this, &TaisyncManager::_radioSettingsChanged);
}
{
//-- Video Output
QStringList enums;
enums.append(tr("Stream"));
enums.append(tr("HDMI Port"));
FactMetaData* metaData = _createMetadata(kVIDEO_OUTPUT, enums);
_videoOutput = new Fact(kTAISYNC_GROUP, metaData, this);
QQmlEngine::setObjectOwnership(_videoOutput, QQmlEngine::CppOwnership);
_videoOutputList.append("phone");
_videoOutputList.append("hdmi");
connect(_videoOutput, &Fact::_containerRawValueChanged, this, &TaisyncManager::_videoSettingsChanged);
}
{
//-- Video Mode
QStringList enums;
enums.append("H264");
enums.append("H265");
FactMetaData* metaData = _createMetadata(kVIDEO_MODE, enums);
_videoMode = new Fact(kTAISYNC_GROUP, metaData, this);
QQmlEngine::setObjectOwnership(_videoMode, QQmlEngine::CppOwnership);
connect(_videoMode, &Fact::_containerRawValueChanged, this, &TaisyncManager::_videoSettingsChanged);
}
{
//-- Video Rate
QStringList enums;
enums.append(tr("Low"));
enums.append(tr("Medium"));
enums.append(tr("High"));
FactMetaData* metaData = _createMetadata(kVIDEO_RATE, enums);
_videoRate = new Fact(kTAISYNC_GROUP, metaData, this);
QQmlEngine::setObjectOwnership(_videoRate, QQmlEngine::CppOwnership);
_videoRateList.append("low");
_videoRateList.append("middle");
_videoRateList.append("high");
connect(_videoRate, &Fact::_containerRawValueChanged, this, &TaisyncManager::_videoSettingsChanged);
//-----------------------------------------------------------------------------
bool
TaisyncManager::setRTSPSettings(QString uri, QString account, QString password)
{
if(_taiSettings) {
if(_taiSettings->setRTSPSettings(uri, account, password)) {
_rtspURI = uri;
_rtspAccount = account;
_rtspPassword = password;
QSettings settings;
settings.beginGroup(kTAISYNC_GROUP);
settings.setValue(kRTSP_URI, _rtspURI);
settings.setValue(kRTSP_ACCOUNT, _rtspAccount);
settings.setValue(kRTSP_PASSWORD, _rtspPassword);
settings.endGroup();
emit rtspURIChanged();
emit rtspAccountChanged();
emit rtspPasswordChanged();
_needReboot = true;
emit needRebootChanged();
return true;
}
}
return false;
}
//-----------------------------------------------------------------------------
bool
TaisyncManager::setIPSettings(QString localIP_, QString remoteIP_, QString netMask_)
bool res = false;
if(_localIPAddr != localIP_ || _remoteIPAddr != remoteIP_ || _netMask != netMask_) {
//-- If we are connected to the Taisync
if(_taiSettings) {
//-- Change IP settings
res = _taiSettings->setIPSettings(localIP_, remoteIP_, netMask_);
if(res) {
_needReboot = true;
emit needRebootChanged();
}
}
} else {
//-- We're not connected. Record the change and restart.
_localIPAddr = localIP_;
_remoteIPAddr = remoteIP_;
_netMask = netMask_;
_reset();
res = true;
}
if(res) {
QSettings settings;
settings.beginGroup(kTAISYNC_GROUP);
settings.setValue(kLOCAL_IP, localIP_);
settings.setValue(kREMOTE_IP, remoteIP_);
settings.setValue(kNET_MASK, netMask_);
settings.endGroup();
}
} else {
//-- Nothing to change
res = true;
Gus Grubba
committed
//-----------------------------------------------------------------------------
void
Gus Grubba
committed
{
_taiSettings->setRadioSettings(
_radioModeList[_radioMode->rawValue().toInt()],
_radioChannel->enumStringValue());
_reqMask |= REQ_RADIO_SETTINGS;
_workTimer.start(3000);
Gus Grubba
committed
}
//-----------------------------------------------------------------------------
void
Gus Grubba
committed
{
_taiSettings->setVideoSettings(
_videoOutputList[_videoOutput->rawValue().toInt()],
_videoMode->enumStringValue(),
_videoRateList[_videoRate->rawValue().toInt()]);
_reqMask |= REQ_VIDEO_SETTINGS;
_workTimer.start(500);
Gus Grubba
committed
}
Gus Grubba
committed
//-----------------------------------------------------------------------------
void
TaisyncManager::_setEnabled()
{
bool enable = _appSettings->enableTaisync()->rawValue().toBool();
if(enable) {
#if defined(__ios__) || defined(__android__)
if(!_taiTelemetery) {
_taiTelemetery = new TaisyncTelemetry(this);
QObject::connect(_taiTelemetery, &TaisyncTelemetry::bytesReady, this, &TaisyncManager::_readTelemBytes);
_telemetrySocket = new QUdpSocket(this);
_telemetrySocket->setSocketOption(QAbstractSocket::SendBufferSizeSocketOption, 64 * 1024);
_telemetrySocket->setSocketOption(QAbstractSocket::ReceiveBufferSizeSocketOption, 64 * 1024);
QObject::connect(_telemetrySocket, &QUdpSocket::readyRead, this, &TaisyncManager::_readUDPBytes);
_telemetrySocket->bind(QHostAddress::LocalHost, 0, QUdpSocket::ShareAddress);
_taiTelemetery->start();
}
Gus Grubba
committed
#endif
Gus Grubba
committed
_workTimer.start(1000);
} else {
Gus Grubba
committed
_workTimer.stop();
Gus Grubba
committed
}
_enabled = enable;
}
//-----------------------------------------------------------------------------
void
TaisyncManager::_setVideoEnabled()
{
bool enable = _appSettings->enableTaisyncVideo()->rawValue().toBool();
if(enable) {
if(!_savedVideoSource.isValid()) {
//-- Hide video selection as we will be fixed to Taisync video and set the way we need it.
VideoSettings* pVSettings = qgcApp()->toolbox()->settingsManager()->videoSettings();
//-- First save current state
_savedVideoSource = pVSettings->videoSource()->rawValue();
_savedVideoUDP = pVSettings->udpPort()->rawValue();
_savedAR = pVSettings->aspectRatio()->rawValue();
_savedVideoState = pVSettings->visible();
//-- Now set it up the way we need it do be
pVSettings->setVisible(false);
pVSettings->udpPort()->setRawValue(5600);
pVSettings->aspectRatio()->setRawValue(1024.0 / 768.0);
pVSettings->videoSource()->setRawValue(QString(VideoSettings::videoSourceUDP));
}
Gus Grubba
committed
#if defined(__ios__) || defined(__android__)
if(!_taiVideo) {
//-- iOS and Android receive raw h.264 and need a different pipeline
qgcApp()->toolbox()->videoManager()->setIsTaisync(true);
_taiVideo = new TaisyncVideoReceiver(this);
_taiVideo->start();
}
Gus Grubba
committed
#endif
} else {
//-- Restore video settings
#if defined(__ios__) || defined(__android__)
qgcApp()->toolbox()->videoManager()->setIsTaisync(false);
if (_taiVideo) {
_taiVideo->close();
_taiVideo->deleteLater();
_taiVideo = nullptr;
}
#endif
if(!_savedVideoSource.isValid()) {
VideoSettings* pVSettings = qgcApp()->toolbox()->settingsManager()->videoSettings();
pVSettings->videoSource()->setRawValue(_savedVideoSource);
pVSettings->udpPort()->setRawValue(_savedVideoUDP);
pVSettings->aspectRatio()->setRawValue(_savedAR);
pVSettings->setVisible(_savedVideoState);
_savedVideoSource.clear();
}
}
_enableVideo = enable;
}
//-----------------------------------------------------------------------------
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
#if defined(__ios__) || defined(__android__)
void
TaisyncManager::_readTelemBytes(QByteArray bytesIn)
{
//-- Send telemetry from vehicle to QGC (using normal UDP)
_telemetrySocket->writeDatagram(bytesIn, QHostAddress::LocalHost, TAISYNC_TELEM_TARGET_PORT);
}
#endif
//-----------------------------------------------------------------------------
#if defined(__ios__) || defined(__android__)
void
TaisyncManager::_readUDPBytes()
{
if (!_telemetrySocket || !_taiTelemetery) {
return;
}
//-- Read UDP data from QGC
while (_telemetrySocket->hasPendingDatagrams()) {
QByteArray datagram;
datagram.resize(static_cast<int>(_telemetrySocket->pendingDatagramSize()));
_telemetrySocket->readDatagram(datagram.data(), datagram.size());
//-- Send it to vehicle
_taiTelemetery->writeBytes(datagram);
}
}
#endif
//-----------------------------------------------------------------------------
Gus Grubba
committed
void
TaisyncManager::_connected()
{
qCDebug(TaisyncLog) << "Taisync Settings Connected";
_isConnected = true;
emit connectedChanged();
Gus Grubba
committed
}
//-----------------------------------------------------------------------------
void
TaisyncManager::_disconnected()
{
qCDebug(TaisyncLog) << "Taisync Settings Disconnected";
_isConnected = false;
emit connectedChanged();
_needReboot = false;
emit needRebootChanged();
_linkConnected = false;
emit linkConnectedChanged();
Gus Grubba
committed
//-----------------------------------------------------------------------------
void
TaisyncManager::_checkTaisync()
{
if(_enabled) {
if(!_isConnected) {
if(!_taiSettings->isServerRunning()) {
_taiSettings->start();
}
Gus Grubba
committed
} else {
while(true) {
if (_reqMask & REQ_LINK_STATUS) {
_taiSettings->requestLinkStatus();
break;
}
if (_reqMask & REQ_DEV_INFO) {
_taiSettings->requestDevInfo();
break;
}
if (_reqMask & REQ_FREQ_SCAN) {
_taiSettings->requestFreqScan();
break;
}
if (_reqMask & REQ_VIDEO_SETTINGS) {
_taiSettings->requestVideoSettings();
break;
}
if (_reqMask & REQ_RADIO_SETTINGS) {
_taiSettings->requestRadioSettings();
break;
}
if (_reqMask & REQ_RTSP_SETTINGS) {
_taiSettings->requestRTSPURISettings();
break;
}
if (_reqMask & REQ_IP_SETTINGS) {
//-- Check link status
if(_timeoutTimer.elapsed() > 3000) {
//-- Give up and restart
_disconnected();
break;
}
//-- If it's been too long since we last heard, ping it.
if(_timeoutTimer.elapsed() > 1000) {
_taiSettings->requestLinkStatus();
break;
}
Gus Grubba
committed
}
}
Gus Grubba
committed
}
}
//-----------------------------------------------------------------------------
void
TaisyncManager::_updateSettings(QByteArray jSonData)
{
Gus Grubba
committed
QJsonParseError jsonParseError;
QJsonDocument doc = QJsonDocument::fromJson(jSonData, &jsonParseError);
if (jsonParseError.error != QJsonParseError::NoError) {
qWarning() << "Unable to parse Taisync response:" << jsonParseError.errorString() << jsonParseError.offset;
return;
}
QJsonObject jObj = doc.object();
//-- Link Status?
if(jSonData.contains("\"flight\":")) {
bool tlinkConnected = jObj["flight"].toString("") == "online";
if(tlinkConnected != _linkConnected) {
_linkConnected = tlinkConnected;
emit linkConnectedChanged();
}
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();
}
Gus Grubba
committed
//-- Device Info?
} else if(jSonData.contains("\"firmwareversion\":")) {
QString tfwVersion = jObj["firmwareversion"].toString(_fwVersion);
QString tserialNumber = jObj["sn"].toString(_serialNumber);
if(tfwVersion != _fwVersion || tserialNumber != _serialNumber) {
_fwVersion = tfwVersion;
_serialNumber = tserialNumber;
emit infoChanged();
}
//-- Radio Settings?
} else if(jSonData.contains("\"freq\":")) {
int idx = _radioModeList.indexOf(jObj["mode"].toString(_radioMode->enumStringValue()));
if(idx >= 0) _radioMode->_containerSetRawValue(idx);
idx = _radioChannel->valueIndex(jObj["freq"].toString(_radioChannel->enumStringValue()));
if(idx < 0) idx = 0;
_radioChannel->_containerSetRawValue(idx);
Gus Grubba
committed
//-- Video Settings?
} else if(jSonData.contains("\"maxbitrate\":")) {
int idx;
idx = _videoMode->valueIndex(jObj["mode"].toString(_videoMode->enumStringValue()));
if(idx < 0) idx = 0;
_videoMode->_containerSetRawValue(idx);
idx = _videoRateList.indexOf(jObj["maxbitrate"].toString(_videoMode->enumStringValue()));
if(idx >= 0) _videoRate->_containerSetRawValue(idx);
idx = _videoOutputList.indexOf(jObj["decode"].toString(_videoOutput->enumStringValue()));
if(idx >= 0) _videoOutput->_containerSetRawValue(idx);
//-- IP Address Settings?
} else if(jSonData.contains("\"usbEthIp\":")) {
QString value;
value = jObj["ipaddr"].toString(_localIPAddr);
if(value != _localIPAddr) {
_localIPAddr = value;
emit localIPAddrChanged();
}
value = jObj["netmask"].toString(_netMask);
if(value != _netMask) {
_netMask = value;
emit netMaskChanged();
}
value = jObj["usbEthIp"].toString(_remoteIPAddr);
if(value != _remoteIPAddr) {
_remoteIPAddr = value;
if(changed) {
QSettings settings;
settings.beginGroup(kTAISYNC_GROUP);
settings.setValue(kLOCAL_IP, _localIPAddr);
settings.setValue(kREMOTE_IP, _remoteIPAddr);
settings.setValue(kNET_MASK, _netMask);
settings.endGroup();
}
//-- RTSP URI Settings?
} else if(jSonData.contains("\"rtspURI\":")) {
QString value;
value = jObj["rtspURI"].toString(_rtspURI);
if(value != _rtspURI) {
_rtspURI = value;
emit rtspURIChanged();
}
value = jObj["account"].toString(_rtspAccount);
if(value != _rtspAccount) {
_rtspAccount = value;
emit rtspAccountChanged();
}
value = jObj["passwd"].toString(_rtspPassword);
if(value != _rtspPassword) {
_rtspPassword = value;
if(changed) {
QSettings settings;
settings.beginGroup(kTAISYNC_GROUP);
settings.setValue(kRTSP_URI, _rtspURI);
settings.setValue(kRTSP_ACCOUNT, _rtspAccount);
settings.setValue(kRTSP_PASSWORD, _rtspPassword);
settings.endGroup();
}