Unverified Commit afe560b4 authored by Gus Grubba's avatar Gus Grubba Committed by GitHub

Merge pull request #7291 from MatejFranceskin/pr-microhard-modems

PR Configuration for microhard pMDDL modems
parents 90e5110a f2f3bc35
......@@ -22,6 +22,7 @@ linux {
CONFIG += LinuxBuild
DEFINES += __STDC_LIMIT_MACROS
DEFINES += QGC_GST_TAISYNC_ENABLED
DEFINES += QGC_GST_MICROHARD_ENABLED
linux-clang {
message("Linux clang")
QMAKE_CXXFLAGS += -Qunused-arguments -fcolor-diagnostics
......@@ -31,12 +32,14 @@ linux {
CONFIG += LinuxBuild
DEFINES += __STDC_LIMIT_MACROS __rasp_pi2__
DEFINES += QGC_GST_TAISYNC_ENABLED
DEFINES += QGC_GST_MICROHARD_ENABLED
} else : android-g++ | android-clang {
CONFIG += AndroidBuild MobileBuild
DEFINES += __android__
DEFINES += __STDC_LIMIT_MACROS
DEFINES += QGC_ENABLE_BLUETOOTH
DEFINES += QGC_GST_TAISYNC_ENABLED
DEFINES += QGC_GST_MICROHARD_ENABLED
target.path = $$DESTDIR
equals(ANDROID_TARGET_ARCH, x86) {
CONFIG += Androidx86Build
......@@ -54,6 +57,7 @@ linux {
CONFIG += WindowsBuild
DEFINES += __STDC_LIMIT_MACROS
DEFINES += QGC_GST_TAISYNC_ENABLED
DEFINES += QGC_GST_MICROHARD_ENABLED
} else {
error("Unsupported Windows toolchain, only Visual Studio 2015 is supported")
}
......@@ -64,6 +68,7 @@ linux {
CONFIG += x86_64
CONFIG -= x86
DEFINES += QGC_GST_TAISYNC_ENABLED
DEFINES += QGC_GST_MICROHARD_ENABLED
equals(QT_MAJOR_VERSION, 5) | greaterThan(QT_MINOR_VERSION, 5) {
QMAKE_MACOSX_DEPLOYMENT_TARGET = 10.7
} else {
......
......@@ -1148,6 +1148,23 @@ contains (DEFINES, QGC_GST_TAISYNC_ENABLED) {
}
}
#-------------------------------------------------------------------------------------
# Microhard
contains (DEFINES, QGC_GST_MICROHARD_ENABLED) {
INCLUDEPATH += \
src/Microhard
HEADERS += \
src/Microhard/MicrohardManager.h \
src/Microhard/MicrohardHandler.h \
src/Microhard/MicrohardSettings.h \
SOURCES += \
src/Microhard/MicrohardManager.cc \
src/Microhard/MicrohardHandler.cc \
src/Microhard/MicrohardSettings.cc \
}
#-------------------------------------------------------------------------------------
# AirMap
......
......@@ -201,6 +201,7 @@
<file alias="SyslinkComponent.qml">src/AutoPilotPlugins/Common/SyslinkComponent.qml</file>
<file alias="TcpSettings.qml">src/ui/preferences/TcpSettings.qml</file>
<file alias="TaisyncSettings.qml">src/Taisync/TaisyncSettings.qml</file>
<file alias="MicrohardSettings.qml">src/Microhard/MicrohardSettings.qml</file>
<file alias="test.qml">src/test.qml</file>
<file alias="UdpSettings.qml">src/ui/preferences/UdpSettings.qml</file>
<file alias="ValuePageWidget.qml">src/FlightMap/Widgets/ValuePageWidget.qml</file>
......
/****************************************************************************
*
* (c) 2019 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 "MicrohardHandler.h"
#include "SettingsManager.h"
#include "QGCApplication.h"
#include "VideoManager.h"
QGC_LOGGING_CATEGORY(MicrohardLog, "MicrohardLog")
QGC_LOGGING_CATEGORY(MicrohardVerbose, "MicrohardVerbose")
//-----------------------------------------------------------------------------
MicrohardHandler::MicrohardHandler(QObject* parent)
: QObject (parent)
{
}
//-----------------------------------------------------------------------------
MicrohardHandler::~MicrohardHandler()
{
close();
}
//-----------------------------------------------------------------------------
bool
MicrohardHandler::close()
{
bool res = false;
if(_tcpSocket) {
qCDebug(MicrohardLog) << "Close Microhard TCP socket on port" << _tcpSocket->localPort();
_tcpSocket->close();
_tcpSocket->deleteLater();
_tcpSocket = nullptr;
res = true;
}
return res;
}
//-----------------------------------------------------------------------------
bool
MicrohardHandler::_start(uint16_t port, QHostAddress addr)
{
close();
_tcpSocket = new QTcpSocket();
QObject::connect(_tcpSocket, &QIODevice::readyRead, this, &MicrohardHandler::_readBytes);
qCDebug(MicrohardLog) << "Connecting to" << addr;
_tcpSocket->connectToHost(addr, port);
if (!_tcpSocket->waitForConnected(1000)) {
close();
return false;
}
emit connected();
return true;
}
/****************************************************************************
*
* (c) 2019 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.
*
****************************************************************************/
#pragma once
#include "QGCLoggingCategory.h"
#include <QHostAddress>
#include <QTcpSocket>
#define MICROHARD_SETTINGS_PORT 23
Q_DECLARE_LOGGING_CATEGORY(MicrohardLog)
Q_DECLARE_LOGGING_CATEGORY(MicrohardVerbose)
class MicrohardHandler : public QObject
{
Q_OBJECT
public:
explicit MicrohardHandler (QObject* parent = nullptr);
~MicrohardHandler ();
virtual bool start () = 0;
virtual bool close ();
protected:
virtual bool _start (uint16_t port, QHostAddress addr = QHostAddress::AnyIPv4);
protected slots:
virtual void _readBytes () = 0;
signals:
void connected ();
void rssiUpdated (int rssi);
protected:
QTcpSocket* _tcpSocket = nullptr;
};
/****************************************************************************
*
* (c) 2019 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 "MicrohardManager.h"
#include "MicrohardSettings.h"
#include "SettingsManager.h"
#include "QGCApplication.h"
#include "QGCCorePlugin.h"
#include <QSettings>
#define LONG_TIMEOUT 5000
static const char *kMICROHARD_GROUP = "Microhard";
static const char *kLOCAL_IP = "LocalIP";
static const char *kREMOTE_IP = "RemoteIP";
static const char *kGROUND_IP = "GroundIP";
static const char *kAIR_IP = "AirIP";
static const char *kNET_MASK = "NetMask";
static const char *kCFG_PASSWORD = "ConfigPassword";
static const char *kENC_KEY = "EncryptionKey";
//-----------------------------------------------------------------------------
MicrohardManager::MicrohardManager(QGCApplication* app, QGCToolbox* toolbox)
: QGCTool(app, toolbox)
{
connect(&_workTimer, &QTimer::timeout, this, &MicrohardManager::_checkMicrohard);
_workTimer.setSingleShot(true);
connect(&_locTimer, &QTimer::timeout, this, &MicrohardManager::_locTimeout);
connect(&_remTimer, &QTimer::timeout, this, &MicrohardManager::_remTimeout);
QSettings settings;
settings.beginGroup(kMICROHARD_GROUP);
_localIPAddr = settings.value(kLOCAL_IP, QString("192.168.168.1")).toString();
_remoteIPAddr = settings.value(kREMOTE_IP, QString("192.168.168.2")).toString();
_groundIPAddr = settings.value(kGROUND_IP, QString("192.168.168.101")).toString();
_airIPAddr = settings.value(kAIR_IP, QString("192.168.168.213")).toString();
_netMask = settings.value(kNET_MASK, QString("255.255.255.0")).toString();
_configPassword = settings.value(kCFG_PASSWORD, QString("admin")).toString();
_encryptionKey = settings.value(kENC_KEY, QString("1234567890")).toString();
settings.endGroup();
}
//-----------------------------------------------------------------------------
MicrohardManager::~MicrohardManager()
{
_close();
}
//-----------------------------------------------------------------------------
void
MicrohardManager::_close()
{
_workTimer.stop();
_locTimer.stop();
_remTimer.stop();
if(_mhSettingsLoc) {
_mhSettingsLoc->close();
_mhSettingsLoc->deleteLater();
_mhSettingsLoc = nullptr;
}
if(_mhSettingsRem) {
_mhSettingsRem->close();
_mhSettingsRem->deleteLater();
_mhSettingsRem = nullptr;
}
}
//-----------------------------------------------------------------------------
void
MicrohardManager::_reset()
{
_close();
_isConnected = false;
emit connectedChanged();
_linkConnected = false;
emit linkConnectedChanged();
if(!_appSettings) {
_appSettings = _toolbox->settingsManager()->appSettings();
connect(_appSettings->enableMicrohard(), &Fact::rawValueChanged, this, &MicrohardManager::_setEnabled);
}
_setEnabled();
}
//-----------------------------------------------------------------------------
FactMetaData*
MicrohardManager::_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
MicrohardManager::setToolbox(QGCToolbox* toolbox)
{
QGCTool::setToolbox(toolbox);
//-- Start it all
_reset();
}
//-----------------------------------------------------------------------------
bool
MicrohardManager::setIPSettings(QString localIP_, QString remoteIP_, QString groundIP_, QString airIP_, QString netMask_, QString cfgPassword_, QString encryptionKey_)
{
if (_localIPAddr != localIP_ || _remoteIPAddr != remoteIP_ || _netMask != netMask_ ||
_configPassword != cfgPassword_ || _encryptionKey != encryptionKey_ || _groundIPAddr != groundIP_ || _airIPAddr != airIP_)
{
if (_mhSettingsLoc && _encryptionKey != encryptionKey_) {
_mhSettingsLoc->setEncryptionKey(encryptionKey_);
}
_localIPAddr = localIP_;
_remoteIPAddr = remoteIP_;
_groundIPAddr = groundIP_;
_airIPAddr = airIP_;
_netMask = netMask_;
_configPassword = cfgPassword_;
_encryptionKey = encryptionKey_;
QSettings settings;
settings.beginGroup(kMICROHARD_GROUP);
settings.setValue(kLOCAL_IP, localIP_);
settings.setValue(kREMOTE_IP, remoteIP_);
settings.setValue(kGROUND_IP, groundIP_);
settings.setValue(kAIR_IP, airIP_);
settings.setValue(kNET_MASK, netMask_);
settings.setValue(kCFG_PASSWORD, cfgPassword_);
settings.setValue(kENC_KEY, encryptionKey_);
settings.endGroup();
_reset();
return true;
}
return false;
}
//-----------------------------------------------------------------------------
void
MicrohardManager::_setEnabled()
{
bool enable = _appSettings->enableMicrohard()->rawValue().toBool();
if(enable) {
if(!_mhSettingsLoc) {
_mhSettingsLoc = new MicrohardSettings(localIPAddr(), this, true);
connect(_mhSettingsLoc, &MicrohardSettings::connected, this, &MicrohardManager::_connectedLoc);
connect(_mhSettingsLoc, &MicrohardSettings::rssiUpdated, this, &MicrohardManager::_rssiUpdatedLoc);
}
if(!_mhSettingsRem) {
_mhSettingsRem = new MicrohardSettings(remoteIPAddr(), this);
connect(_mhSettingsRem, &MicrohardSettings::connected, this, &MicrohardManager::_connectedRem);
connect(_mhSettingsRem, &MicrohardSettings::rssiUpdated, this, &MicrohardManager::_rssiUpdatedRem);
}
_workTimer.start(1000);
} else {
//-- Stop everything
_close();
}
_enabled = enable;
}
//-----------------------------------------------------------------------------
void
MicrohardManager::_connectedLoc()
{
qCDebug(MicrohardLog) << "GND Microhard Settings Connected";
_isConnected = true;
_locTimer.start(LONG_TIMEOUT);
emit connectedChanged();
}
//-----------------------------------------------------------------------------
void
MicrohardManager::_connectedRem()
{
qCDebug(MicrohardLog) << "AIR Microhard Settings Connected";
_linkConnected = true;
_remTimer.start(LONG_TIMEOUT);
emit linkConnectedChanged();
}
//-----------------------------------------------------------------------------
void
MicrohardManager::_rssiUpdatedLoc(int rssi)
{
_downlinkRSSI = rssi;
_locTimer.stop();
_locTimer.start(LONG_TIMEOUT);
emit connectedChanged();
emit linkChanged();
}
//-----------------------------------------------------------------------------
void
MicrohardManager::_rssiUpdatedRem(int rssi)
{
_uplinkRSSI = rssi;
_remTimer.stop();
_remTimer.start(LONG_TIMEOUT);
emit linkConnectedChanged();
emit linkChanged();
}
//-----------------------------------------------------------------------------
void
MicrohardManager::_locTimeout()
{
_locTimer.stop();
_isConnected = false;
if(_mhSettingsLoc) {
_mhSettingsLoc->close();
_mhSettingsLoc->deleteLater();
_mhSettingsLoc = nullptr;
}
emit connectedChanged();
}
//-----------------------------------------------------------------------------
void
MicrohardManager::_remTimeout()
{
_remTimer.stop();
_linkConnected = false;
if(_mhSettingsRem) {
_mhSettingsRem->close();
_mhSettingsRem->deleteLater();
_mhSettingsRem = nullptr;
}
emit linkConnectedChanged();
}
//-----------------------------------------------------------------------------
void
MicrohardManager::_checkMicrohard()
{
if(_enabled) {
if(!_mhSettingsLoc || !_mhSettingsRem) {
_setEnabled();
return;
}
if(!_isConnected) {
_mhSettingsLoc->start();
} else {
_mhSettingsLoc->getStatus();
}
if(!_linkConnected) {
_mhSettingsRem->start();
} else {
_mhSettingsRem->getStatus();
}
}
_workTimer.start(_isConnected ? 1000 : LONG_TIMEOUT);
}
/****************************************************************************
*
* (c) 2019 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.
*
****************************************************************************/
#pragma once
#include "QGCToolbox.h"
#include "QGCLoggingCategory.h"
#include "MicrohardSettings.h"
#include "Fact.h"
#include <QTimer>
#include <QTime>
class AppSettings;
class QGCApplication;
//-----------------------------------------------------------------------------
class MicrohardManager : public QGCTool
{
Q_OBJECT
public:
Q_PROPERTY(bool connected READ connected NOTIFY connectedChanged)
Q_PROPERTY(bool linkConnected READ linkConnected NOTIFY linkConnectedChanged)
Q_PROPERTY(int uplinkRSSI READ uplinkRSSI NOTIFY linkChanged)
Q_PROPERTY(int downlinkRSSI READ downlinkRSSI NOTIFY linkChanged)
Q_PROPERTY(QString localIPAddr READ localIPAddr NOTIFY localIPAddrChanged)
Q_PROPERTY(QString remoteIPAddr READ remoteIPAddr NOTIFY remoteIPAddrChanged)
Q_PROPERTY(QString groundIPAddr READ groundIPAddr NOTIFY groundIPAddrChanged)
Q_PROPERTY(QString airIPAddr READ airIPAddr NOTIFY airIPAddrChanged)
Q_PROPERTY(QString netMask READ netMask NOTIFY netMaskChanged)
Q_PROPERTY(QString configPassword READ configPassword NOTIFY configPasswordChanged)
Q_PROPERTY(QString encryptionKey READ encryptionKey NOTIFY encryptionKeyChanged)
Q_INVOKABLE bool setIPSettings (QString localIP, QString remoteIP, QString groundIP, QString airIP, QString netMask, QString cfgPassword, QString encyrptionKey);
explicit MicrohardManager (QGCApplication* app, QGCToolbox* toolbox);
~MicrohardManager () override;
void setToolbox (QGCToolbox* toolbox) override;
bool connected () { return _isConnected && _mhSettingsLoc && _mhSettingsLoc->loggedIn(); }
bool linkConnected () { return _linkConnected && _mhSettingsRem && _mhSettingsRem->loggedIn(); }
int uplinkRSSI () { return _downlinkRSSI; }
int downlinkRSSI () { return _uplinkRSSI; }
QString localIPAddr () { return _localIPAddr; }
QString remoteIPAddr () { return _remoteIPAddr; }
QString airIPAddr () { return _airIPAddr; }
QString groundIPAddr () { return _groundIPAddr; }
QString netMask () { return _netMask; }
QString configPassword () { return _configPassword; }
QString encryptionKey () { return _encryptionKey; }
signals:
void linkChanged ();
void linkConnectedChanged ();
void connectedChanged ();
void localIPAddrChanged ();
void remoteIPAddrChanged ();
void airIPAddrChanged ();
void groundIPAddrChanged ();
void netMaskChanged ();
void configPasswordChanged ();
void encryptionKeyChanged ();
private slots:
void _connectedLoc ();
void _rssiUpdatedLoc (int rssi);
void _connectedRem ();
void _rssiUpdatedRem (int rssi);
void _checkMicrohard ();
void _setEnabled ();
void _locTimeout ();
void _remTimeout ();
private:
void _close ();
void _reset ();
FactMetaData *_createMetadata (const char *name, QStringList enums);
private:
bool _isConnected = false;
AppSettings* _appSettings = nullptr;
MicrohardSettings* _mhSettingsLoc = nullptr;
MicrohardSettings* _mhSettingsRem = nullptr;
bool _enabled = true;
bool _linkConnected = false;
QTimer _workTimer;
QTimer _locTimer;
QTimer _remTimer;
int _downlinkRSSI = 0;
int _uplinkRSSI = 0;
QString _localIPAddr;
QString _remoteIPAddr;
QString _groundIPAddr;
QString _airIPAddr;
QString _netMask;
QString _configPassword;
QString _encryptionKey;
QTime _timeoutTimer;
};
/****************************************************************************
*
* (c) 2019 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 "MicrohardSettings.h"
#include "MicrohardManager.h"
#include "SettingsManager.h"
#include "QGCApplication.h"
#include "VideoManager.h"
//-----------------------------------------------------------------------------
MicrohardSettings::MicrohardSettings(QString address_, QObject* parent, bool setEncryptionKey)
: MicrohardHandler(parent)
{
_address = address_;
_setEncryptionKey = setEncryptionKey;
}
//-----------------------------------------------------------------------------
bool
MicrohardSettings::start()
{
qCDebug(MicrohardLog) << "Start Microhard Settings";
_loggedIn = false;
return _start(MICROHARD_SETTINGS_PORT, QHostAddress(_address));
}
//-----------------------------------------------------------------------------
void
MicrohardSettings::getStatus()
{
if (_loggedIn) {
_tcpSocket->write("AT+MWSTATUS\n");
}
}
//-----------------------------------------------------------------------------
void
MicrohardSettings::setEncryptionKey(QString key)
{
QString cmd = "AT+MWVENCRYPT=1," + key + "\n";
_tcpSocket->write(cmd.toStdString().c_str());
qCDebug(MicrohardLog) << "setEncryptionKey: " << cmd;
}
//-----------------------------------------------------------------------------
void
MicrohardSettings::_readBytes()
{
QByteArray bytesIn = _tcpSocket->read(_tcpSocket->bytesAvailable());
// qCDebug(MicrohardVerbose) << "Read bytes: " << bytesIn;
if (_loggedIn) {
int i1 = bytesIn.indexOf("RSSI (dBm)");
if (i1 > 0) {
int i2 = bytesIn.indexOf(": ", i1);
if (i2 > 0) {
i2 += 2;
int i3 = bytesIn.indexOf(" ", i2);
int val = bytesIn.mid(i2, i3 - i2).toInt();
if (val < 0) {
_rssiVal = val;
}
}
}
} else if (bytesIn.contains("UserDevice login:")) {
_tcpSocket->write("admin\n");
} else if (bytesIn.contains("Password:")) {
std::string pwd = qgcApp()->toolbox()->microhardManager()->configPassword().toStdString() + "\n";
_tcpSocket->write(pwd.c_str());
} else if (bytesIn.contains("UserDevice>")) {
if (!loggedIn() && _setEncryptionKey) {
setEncryptionKey(qgcApp()->toolbox()->microhardManager()->encryptionKey());
}
_loggedIn = true;
}
emit rssiUpdated(_rssiVal);
}
/****************************************************************************
*
* (c) 2019 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.
*
****************************************************************************/
#pragma once
#include "MicrohardHandler.h"
class MicrohardSettings : public MicrohardHandler
{
Q_OBJECT
public:
explicit MicrohardSettings (QString address, QObject* parent = nullptr, bool setEncryptionKey = false);
bool start () override;
void getStatus ();
void setEncryptionKey (QString key);
bool loggedIn () { return _loggedIn; }
protected slots:
void _readBytes () override;
signals:
void updateRSSI (int rssi);
private:
bool _loggedIn;
int _rssiVal;
QString _address;
bool _setEncryptionKey;
};
This diff is collapsed.
......@@ -38,6 +38,9 @@
#if defined(QGC_GST_TAISYNC_ENABLED)
#include "TaisyncManager.h"
#endif
#if defined(QGC_GST_MICROHARD_ENABLED)
#include "MicrohardManager.h"
#endif
#if defined(QGC_CUSTOM_BUILD)
#include CUSTOMHEADER
......@@ -78,6 +81,9 @@ QGCToolbox::QGCToolbox(QGCApplication* app)
#if defined(QGC_GST_TAISYNC_ENABLED)
_taisyncManager = new TaisyncManager (app, this);
#endif
#if defined(QGC_GST_MICROHARD_ENABLED)
_microhardManager = new MicrohardManager (app, this);
#endif
}
void QGCToolbox::setChildToolboxes(void)
......@@ -107,6 +113,9 @@ void QGCToolbox::setChildToolboxes(void)
#if defined(QGC_GST_TAISYNC_ENABLED)
_taisyncManager->setToolbox(this);
#endif
#if defined(QGC_GST_MICROHARD_ENABLED)
_microhardManager->setToolbox(this);
#endif
}
void QGCToolbox::_scanAndLoadPlugins(QGCApplication* app)
......
......@@ -36,6 +36,9 @@ class AirspaceManager;
#if defined(QGC_GST_TAISYNC_ENABLED)
class TaisyncManager;
#endif
#if defined(QGC_GST_MICROHARD_ENABLED)
class MicrohardManager;
#endif
/// This is used to manage all of our top level services/tools
class QGCToolbox : public QObject {
......@@ -67,6 +70,9 @@ public:
#if defined(QGC_GST_TAISYNC_ENABLED)
TaisyncManager* taisyncManager () { return _taisyncManager; }
#endif
#if defined(QGC_GST_MICROHARD_ENABLED)
MicrohardManager* microhardManager () { return _microhardManager; }
#endif
private:
void setChildToolboxes(void);
......@@ -96,6 +102,9 @@ private:
AirspaceManager* _airspaceManager = nullptr;
#if defined(QGC_GST_TAISYNC_ENABLED)
TaisyncManager* _taisyncManager = nullptr;
#endif
#if defined(QGC_GST_MICROHARD_ENABLED)
MicrohardManager* _microhardManager = nullptr;
#endif
friend class QGCApplication;
};
......
......@@ -69,6 +69,9 @@ void QGroundControlQmlGlobal::setToolbox(QGCToolbox* toolbox)
#if defined(QGC_GST_TAISYNC_ENABLED)
_taisyncManager = toolbox->taisyncManager();
#endif
#if defined(QGC_GST_MICROHARD_ENABLED)
_microhardManager = toolbox->microhardManager();
#endif
}
void QGroundControlQmlGlobal::saveGlobalSetting (const QString& key, const QString& value)
......
......@@ -28,6 +28,11 @@
#else
class TaisyncManager;
#endif
#if defined(QGC_GST_MICROHARD_ENABLED)
#include "MicrohardManager.h"
#else
class MicrohardManager;
#endif
#ifdef QT_DEBUG
#include "MockLink.h"
......@@ -68,6 +73,8 @@ public:
Q_PROPERTY(bool airmapSupported READ airmapSupported CONSTANT)
Q_PROPERTY(TaisyncManager* taisyncManager READ taisyncManager CONSTANT)
Q_PROPERTY(bool taisyncSupported READ taisyncSupported CONSTANT)
Q_PROPERTY(MicrohardManager* microhardManager READ microhardManager CONSTANT)
Q_PROPERTY(bool microhardSupported READ microhardSupported CONSTANT)
Q_PROPERTY(int supportedFirmwareCount READ supportedFirmwareCount CONSTANT)
Q_PROPERTY(bool px4ProFirmwareSupported READ px4ProFirmwareSupported CONSTANT)
......@@ -170,6 +177,13 @@ public:
bool taisyncSupported () { return false; }
#endif
MicrohardManager* microhardManager () { return _microhardManager; }
#if defined(QGC_GST_TAISYNC_ENABLED)
bool microhardSupported () { return true; }
#else
bool microhardSupported () { return false; }
#endif
qreal zOrderTopMost () { return 1000; }
qreal zOrderWidgets () { return 100; }
qreal zOrderMapItems () { return 50; }
......@@ -230,6 +244,7 @@ private:
FactGroup* _gpsRtkFactGroup = nullptr;
AirspaceManager* _airspaceManager = nullptr;
TaisyncManager* _taisyncManager = nullptr;
MicrohardManager* _microhardManager = nullptr;
bool _skipSetupPage = false;
......
......@@ -221,4 +221,11 @@
"type": "bool",
"defaultValue": true
}
]
,
{
"name": "enableMicrohard",
"shortDescription": "Enable Microhard Module Support",
"longDescription": "Enable Microhard Module Support",
"type": "bool",
"defaultValue": false
}]
......@@ -87,6 +87,7 @@ DECLARE_SETTINGSFACT(AppSettings, followTarget)
DECLARE_SETTINGSFACT(AppSettings, apmStartMavlinkStreams)
DECLARE_SETTINGSFACT(AppSettings, enableTaisync)
DECLARE_SETTINGSFACT(AppSettings, enableTaisyncVideo)
DECLARE_SETTINGSFACT(AppSettings, enableMicrohard)
DECLARE_SETTINGSFACT_NO_FUNC(AppSettings, indoorPalette)
{
......
......@@ -45,6 +45,7 @@ public:
DEFINE_SETTINGFACT(followTarget)
DEFINE_SETTINGFACT(enableTaisync)
DEFINE_SETTINGFACT(enableTaisyncVideo)
DEFINE_SETTINGFACT(enableMicrohard)
// Although this is a global setting it only affects ArduPilot vehicle since PX4 automatically starts the stream from the vehicle side
DEFINE_SETTINGFACT(apmStartMavlinkStreams)
......
......@@ -48,6 +48,10 @@ public:
if(pTaisync)
delete pTaisync;
#endif
#if defined(QGC_GST_MICROHARD_ENABLED)
if(pMicrohard)
delete pMicrohard;
#endif
#if defined(QGC_AIRMAP_ENABLED)
if(pAirmap)
delete pAirmap;
......@@ -72,6 +76,9 @@ public:
#if defined(QGC_GST_TAISYNC_ENABLED)
QmlComponentInfo* pTaisync = nullptr;
#endif
#if defined(QGC_GST_MICROHARD_ENABLED)
QmlComponentInfo* pMicrohard = nullptr;
#endif
#if defined(QGC_AIRMAP_ENABLED)
QmlComponentInfo* pAirmap = nullptr;
#endif
......@@ -140,6 +147,12 @@ QVariantList &QGCCorePlugin::settingsPages()
QUrl::fromUserInput(""));
_p->settingsList.append(QVariant::fromValue(reinterpret_cast<QmlComponentInfo*>(_p->pTaisync)));
#endif
#if defined(QGC_GST_MICROHARD_ENABLED)
_p->pMicrohard = new QmlComponentInfo(tr("Microhard"),
QUrl::fromUserInput("qrc:/qml/MicrohardSettings.qml"),
QUrl::fromUserInput(""));
_p->settingsList.append(QVariant::fromValue(reinterpret_cast<QmlComponentInfo*>(_p->pMicrohard)));
#endif
#if defined(QGC_AIRMAP_ENABLED)
_p->pAirmap = new QmlComponentInfo(tr("AirMap"),
QUrl::fromUserInput("qrc:/qml/AirmapSettings.qml"),
......
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