Commit 30c9678b authored by Matej Frančeškin's avatar Matej Frančeškin

Microhard improvements

Added Configuration Username
Report Login Error on incorrect configuration username/password 
parent 78922bd8
...@@ -13,7 +13,6 @@ ...@@ -13,7 +13,6 @@
#include "VideoManager.h" #include "VideoManager.h"
QGC_LOGGING_CATEGORY(MicrohardLog, "MicrohardLog") QGC_LOGGING_CATEGORY(MicrohardLog, "MicrohardLog")
QGC_LOGGING_CATEGORY(MicrohardVerbose, "MicrohardVerbose")
//----------------------------------------------------------------------------- //-----------------------------------------------------------------------------
MicrohardHandler::MicrohardHandler(QObject* parent) MicrohardHandler::MicrohardHandler(QObject* parent)
...@@ -53,10 +52,10 @@ MicrohardHandler::_start(uint16_t port, QHostAddress addr) ...@@ -53,10 +52,10 @@ MicrohardHandler::_start(uint16_t port, QHostAddress addr)
qCDebug(MicrohardLog) << "Connecting to" << addr; qCDebug(MicrohardLog) << "Connecting to" << addr;
_tcpSocket->connectToHost(addr, port); _tcpSocket->connectToHost(addr, port);
if (!_tcpSocket->waitForConnected(1000)) { if (!_tcpSocket->waitForConnected(1000)) {
emit connected(0);
close(); close();
return false; return false;
} }
emit connected();
return true; return true;
} }
...@@ -17,7 +17,6 @@ ...@@ -17,7 +17,6 @@
#define MICROHARD_SETTINGS_PORT 23 #define MICROHARD_SETTINGS_PORT 23
Q_DECLARE_LOGGING_CATEGORY(MicrohardLog) Q_DECLARE_LOGGING_CATEGORY(MicrohardLog)
Q_DECLARE_LOGGING_CATEGORY(MicrohardVerbose)
class MicrohardHandler : public QObject class MicrohardHandler : public QObject
{ {
...@@ -36,7 +35,7 @@ protected slots: ...@@ -36,7 +35,7 @@ protected slots:
virtual void _readBytes () = 0; virtual void _readBytes () = 0;
signals: signals:
void connected (); void connected (int status);
void rssiUpdated (int rssi); void rssiUpdated (int rssi);
protected: protected:
......
...@@ -22,6 +22,7 @@ static const char *kMICROHARD_GROUP = "Microhard"; ...@@ -22,6 +22,7 @@ static const char *kMICROHARD_GROUP = "Microhard";
static const char *kLOCAL_IP = "LocalIP"; static const char *kLOCAL_IP = "LocalIP";
static const char *kREMOTE_IP = "RemoteIP"; static const char *kREMOTE_IP = "RemoteIP";
static const char *kNET_MASK = "NetMask"; static const char *kNET_MASK = "NetMask";
static const char *kCFG_USERNAME = "ConfigUserName";
static const char *kCFG_PASSWORD = "ConfigPassword"; static const char *kCFG_PASSWORD = "ConfigPassword";
static const char *kENC_KEY = "EncryptionKey"; static const char *kENC_KEY = "EncryptionKey";
...@@ -38,6 +39,7 @@ MicrohardManager::MicrohardManager(QGCApplication* app, QGCToolbox* toolbox) ...@@ -38,6 +39,7 @@ MicrohardManager::MicrohardManager(QGCApplication* app, QGCToolbox* toolbox)
_localIPAddr = settings.value(kLOCAL_IP, QString("192.168.168.1")).toString(); _localIPAddr = settings.value(kLOCAL_IP, QString("192.168.168.1")).toString();
_remoteIPAddr = settings.value(kREMOTE_IP, QString("192.168.168.2")).toString(); _remoteIPAddr = settings.value(kREMOTE_IP, QString("192.168.168.2")).toString();
_netMask = settings.value(kNET_MASK, QString("255.255.255.0")).toString(); _netMask = settings.value(kNET_MASK, QString("255.255.255.0")).toString();
_configUserName = settings.value(kCFG_USERNAME, QString("admin")).toString();
_configPassword = settings.value(kCFG_PASSWORD, QString("admin")).toString(); _configPassword = settings.value(kCFG_PASSWORD, QString("admin")).toString();
_encryptionKey = settings.value(kENC_KEY, QString("1234567890")).toString(); _encryptionKey = settings.value(kENC_KEY, QString("1234567890")).toString();
settings.endGroup(); settings.endGroup();
...@@ -73,9 +75,9 @@ void ...@@ -73,9 +75,9 @@ void
MicrohardManager::_reset() MicrohardManager::_reset()
{ {
_close(); _close();
_isConnected = false; _connectedStatus = 0;
emit connectedChanged(); emit connectedChanged();
_linkConnected = false; _linkConnectedStatus = 0;
emit linkConnectedChanged(); emit linkConnectedChanged();
if(!_appSettings) { if(!_appSettings) {
_appSettings = _toolbox->settingsManager()->appSettings(); _appSettings = _toolbox->settingsManager()->appSettings();
...@@ -114,10 +116,10 @@ MicrohardManager::setToolbox(QGCToolbox* toolbox) ...@@ -114,10 +116,10 @@ MicrohardManager::setToolbox(QGCToolbox* toolbox)
//----------------------------------------------------------------------------- //-----------------------------------------------------------------------------
bool bool
MicrohardManager::setIPSettings(QString localIP_, QString remoteIP_, QString netMask_, QString cfgPassword_, QString encryptionKey_) MicrohardManager::setIPSettings(QString localIP_, QString remoteIP_, QString netMask_, QString cfgUserName_, QString cfgPassword_, QString encryptionKey_)
{ {
if (_localIPAddr != localIP_ || _remoteIPAddr != remoteIP_ || _netMask != netMask_ || if (_localIPAddr != localIP_ || _remoteIPAddr != remoteIP_ || _netMask != netMask_ ||
_configPassword != cfgPassword_ || _encryptionKey != encryptionKey_) _configUserName != cfgUserName_ || _configPassword != cfgPassword_ || _encryptionKey != encryptionKey_)
{ {
if (_mhSettingsLoc && _encryptionKey != encryptionKey_) { if (_mhSettingsLoc && _encryptionKey != encryptionKey_) {
_mhSettingsLoc->setEncryptionKey(encryptionKey_); _mhSettingsLoc->setEncryptionKey(encryptionKey_);
...@@ -126,6 +128,7 @@ MicrohardManager::setIPSettings(QString localIP_, QString remoteIP_, QString net ...@@ -126,6 +128,7 @@ MicrohardManager::setIPSettings(QString localIP_, QString remoteIP_, QString net
_localIPAddr = localIP_; _localIPAddr = localIP_;
_remoteIPAddr = remoteIP_; _remoteIPAddr = remoteIP_;
_netMask = netMask_; _netMask = netMask_;
_configUserName = cfgUserName_;
_configPassword = cfgPassword_; _configPassword = cfgPassword_;
_encryptionKey = encryptionKey_; _encryptionKey = encryptionKey_;
...@@ -134,6 +137,7 @@ MicrohardManager::setIPSettings(QString localIP_, QString remoteIP_, QString net ...@@ -134,6 +137,7 @@ MicrohardManager::setIPSettings(QString localIP_, QString remoteIP_, QString net
settings.setValue(kLOCAL_IP, localIP_); settings.setValue(kLOCAL_IP, localIP_);
settings.setValue(kREMOTE_IP, remoteIP_); settings.setValue(kREMOTE_IP, remoteIP_);
settings.setValue(kNET_MASK, netMask_); settings.setValue(kNET_MASK, netMask_);
settings.setValue(kCFG_USERNAME, cfgUserName_);
settings.setValue(kCFG_PASSWORD, cfgPassword_); settings.setValue(kCFG_PASSWORD, cfgPassword_);
settings.setValue(kENC_KEY, encryptionKey_); settings.setValue(kENC_KEY, encryptionKey_);
settings.endGroup(); settings.endGroup();
...@@ -172,20 +176,20 @@ MicrohardManager::_setEnabled() ...@@ -172,20 +176,20 @@ MicrohardManager::_setEnabled()
//----------------------------------------------------------------------------- //-----------------------------------------------------------------------------
void void
MicrohardManager::_connectedLoc() MicrohardManager::_connectedLoc(int status)
{ {
qCDebug(MicrohardLog) << "GND Microhard Settings Connected"; qCDebug(MicrohardLog) << "GND Microhard Settings Connected";
_isConnected = true; _connectedStatus = status;
_locTimer.start(LONG_TIMEOUT); _locTimer.start(LONG_TIMEOUT);
emit connectedChanged(); emit connectedChanged();
} }
//----------------------------------------------------------------------------- //-----------------------------------------------------------------------------
void void
MicrohardManager::_connectedRem() MicrohardManager::_connectedRem(int status)
{ {
qCDebug(MicrohardLog) << "AIR Microhard Settings Connected"; qCDebug(MicrohardLog) << "AIR Microhard Settings Connected";
_linkConnected = true; _linkConnectedStatus = status;
_remTimer.start(LONG_TIMEOUT); _remTimer.start(LONG_TIMEOUT);
emit linkConnectedChanged(); emit linkConnectedChanged();
} }
...@@ -217,7 +221,7 @@ void ...@@ -217,7 +221,7 @@ void
MicrohardManager::_locTimeout() MicrohardManager::_locTimeout()
{ {
_locTimer.stop(); _locTimer.stop();
_isConnected = false; _connectedStatus = 0;
if(_mhSettingsLoc) { if(_mhSettingsLoc) {
_mhSettingsLoc->close(); _mhSettingsLoc->close();
_mhSettingsLoc->deleteLater(); _mhSettingsLoc->deleteLater();
...@@ -231,7 +235,7 @@ void ...@@ -231,7 +235,7 @@ void
MicrohardManager::_remTimeout() MicrohardManager::_remTimeout()
{ {
_remTimer.stop(); _remTimer.stop();
_linkConnected = false; _linkConnectedStatus = 0;
if(_mhSettingsRem) { if(_mhSettingsRem) {
_mhSettingsRem->close(); _mhSettingsRem->close();
_mhSettingsRem->deleteLater(); _mhSettingsRem->deleteLater();
...@@ -250,16 +254,16 @@ MicrohardManager::_checkMicrohard() ...@@ -250,16 +254,16 @@ MicrohardManager::_checkMicrohard()
return; return;
} }
if(!_isConnected) { if(_connectedStatus <= 0) {
_mhSettingsLoc->start(); _mhSettingsLoc->start();
} else { } else {
_mhSettingsLoc->getStatus(); _mhSettingsLoc->getStatus();
} }
if(!_linkConnected) { if(_linkConnectedStatus <= 0) {
_mhSettingsRem->start(); _mhSettingsRem->start();
} else { } else {
_mhSettingsRem->getStatus(); _mhSettingsRem->getStatus();
} }
} }
_workTimer.start(_isConnected ? SHORT_TIMEOUT : LONG_TIMEOUT); _workTimer.start(_connectedStatus > 0 ? SHORT_TIMEOUT : LONG_TIMEOUT);
} }
...@@ -26,30 +26,32 @@ class MicrohardManager : public QGCTool ...@@ -26,30 +26,32 @@ class MicrohardManager : public QGCTool
Q_OBJECT Q_OBJECT
public: public:
Q_PROPERTY(bool connected READ connected NOTIFY connectedChanged) Q_PROPERTY(int connected READ connected NOTIFY connectedChanged)
Q_PROPERTY(bool linkConnected READ linkConnected NOTIFY linkConnectedChanged) Q_PROPERTY(int linkConnected READ linkConnected NOTIFY linkConnectedChanged)
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 localIPAddr READ localIPAddr NOTIFY localIPAddrChanged) Q_PROPERTY(QString localIPAddr READ localIPAddr NOTIFY localIPAddrChanged)
Q_PROPERTY(QString remoteIPAddr READ remoteIPAddr NOTIFY remoteIPAddrChanged) Q_PROPERTY(QString remoteIPAddr READ remoteIPAddr NOTIFY remoteIPAddrChanged)
Q_PROPERTY(QString netMask READ netMask NOTIFY netMaskChanged) Q_PROPERTY(QString netMask READ netMask NOTIFY netMaskChanged)
Q_PROPERTY(QString configUserName READ configUserName NOTIFY configUserNameChanged)
Q_PROPERTY(QString configPassword READ configPassword NOTIFY configPasswordChanged) Q_PROPERTY(QString configPassword READ configPassword NOTIFY configPasswordChanged)
Q_PROPERTY(QString encryptionKey READ encryptionKey NOTIFY encryptionKeyChanged) Q_PROPERTY(QString encryptionKey READ encryptionKey NOTIFY encryptionKeyChanged)
Q_INVOKABLE bool setIPSettings (QString localIP, QString remoteIP, QString netMask, QString cfgPassword, QString encyrptionKey); Q_INVOKABLE bool setIPSettings (QString localIP, QString remoteIP, QString netMask, QString cfgUserName, QString cfgPassword, QString encyrptionKey);
explicit MicrohardManager (QGCApplication* app, QGCToolbox* toolbox); explicit MicrohardManager (QGCApplication* app, QGCToolbox* toolbox);
~MicrohardManager () override; ~MicrohardManager () override;
void setToolbox (QGCToolbox* toolbox) override; void setToolbox (QGCToolbox* toolbox) override;
bool connected () { return _isConnected && _mhSettingsLoc && _mhSettingsLoc->loggedIn(); } int connected () { return _connectedStatus; }
bool linkConnected () { return _linkConnected && _mhSettingsRem && _mhSettingsRem->loggedIn(); } int linkConnected () { return _linkConnectedStatus; }
int uplinkRSSI () { return _downlinkRSSI; } int uplinkRSSI () { return _downlinkRSSI; }
int downlinkRSSI () { return _uplinkRSSI; } int downlinkRSSI () { return _uplinkRSSI; }
QString localIPAddr () { return _localIPAddr; } QString localIPAddr () { return _localIPAddr; }
QString remoteIPAddr () { return _remoteIPAddr; } QString remoteIPAddr () { return _remoteIPAddr; }
QString netMask () { return _netMask; } QString netMask () { return _netMask; }
QString configUserName () { return _configUserName; }
QString configPassword () { return _configPassword; } QString configPassword () { return _configPassword; }
QString encryptionKey () { return _encryptionKey; } QString encryptionKey () { return _encryptionKey; }
...@@ -60,13 +62,14 @@ signals: ...@@ -60,13 +62,14 @@ signals:
void localIPAddrChanged (); void localIPAddrChanged ();
void remoteIPAddrChanged (); void remoteIPAddrChanged ();
void netMaskChanged (); void netMaskChanged ();
void configUserNameChanged ();
void configPasswordChanged (); void configPasswordChanged ();
void encryptionKeyChanged (); void encryptionKeyChanged ();
private slots: private slots:
void _connectedLoc (); void _connectedLoc (int status);
void _rssiUpdatedLoc (int rssi); void _rssiUpdatedLoc (int rssi);
void _connectedRem (); void _connectedRem (int status);
void _rssiUpdatedRem (int rssi); void _rssiUpdatedRem (int rssi);
void _checkMicrohard (); void _checkMicrohard ();
void _setEnabled (); void _setEnabled ();
...@@ -79,21 +82,22 @@ private: ...@@ -79,21 +82,22 @@ private:
FactMetaData *_createMetadata (const char *name, QStringList enums); FactMetaData *_createMetadata (const char *name, QStringList enums);
private: private:
bool _isConnected = false; int _connectedStatus = 0;
AppSettings* _appSettings = nullptr; AppSettings* _appSettings = nullptr;
MicrohardSettings* _mhSettingsLoc = nullptr; MicrohardSettings* _mhSettingsLoc = nullptr;
MicrohardSettings* _mhSettingsRem = nullptr; MicrohardSettings* _mhSettingsRem = nullptr;
bool _enabled = true; bool _enabled = true;
bool _linkConnected = false; int _linkConnectedStatus = 0;
QTimer _workTimer; QTimer _workTimer;
QTimer _locTimer; QTimer _locTimer;
QTimer _remTimer; QTimer _remTimer;
int _downlinkRSSI = 0; int _downlinkRSSI = 0;
int _uplinkRSSI = 0; int _uplinkRSSI = 0;
QString _localIPAddr; QString _localIPAddr;
QString _remoteIPAddr; QString _remoteIPAddr;
QString _netMask; QString _netMask;
QString _configPassword; QString _configUserName;
QString _encryptionKey; QString _configPassword;
QTime _timeoutTimer; QString _encryptionKey;
QTime _timeoutTimer;
}; };
...@@ -45,7 +45,7 @@ MicrohardSettings::setEncryptionKey(QString key) ...@@ -45,7 +45,7 @@ MicrohardSettings::setEncryptionKey(QString key)
{ {
QString cmd = "AT+MWVENCRYPT=1," + key + "\n"; QString cmd = "AT+MWVENCRYPT=1," + key + "\n";
_tcpSocket->write(cmd.toStdString().c_str()); _tcpSocket->write(cmd.toStdString().c_str());
qCDebug(MicrohardLog) << "setEncryptionKey: " << cmd; qCDebug(MicrohardLog) << "Set encryption key.";
} }
//----------------------------------------------------------------------------- //-----------------------------------------------------------------------------
...@@ -54,7 +54,7 @@ MicrohardSettings::_readBytes() ...@@ -54,7 +54,7 @@ MicrohardSettings::_readBytes()
{ {
QByteArray bytesIn = _tcpSocket->read(_tcpSocket->bytesAvailable()); QByteArray bytesIn = _tcpSocket->read(_tcpSocket->bytesAvailable());
// qCDebug(MicrohardVerbose) << "Read bytes: " << bytesIn; //qCDebug(MicrohardLog) << "Read bytes: " << bytesIn;
if (_loggedIn) { if (_loggedIn) {
int i1 = bytesIn.indexOf("RSSI (dBm)"); int i1 = bytesIn.indexOf("RSSI (dBm)");
...@@ -69,16 +69,20 @@ MicrohardSettings::_readBytes() ...@@ -69,16 +69,20 @@ MicrohardSettings::_readBytes()
} }
} }
} }
} else if (bytesIn.contains("UserDevice login:")) { } else if (bytesIn.contains("login:")) {
_tcpSocket->write("admin\n"); std::string userName = qgcApp()->toolbox()->microhardManager()->configUserName().toStdString() + "\n";
_tcpSocket->write(userName.c_str());
} else if (bytesIn.contains("Password:")) { } else if (bytesIn.contains("Password:")) {
std::string pwd = qgcApp()->toolbox()->microhardManager()->configPassword().toStdString() + "\n"; std::string pwd = qgcApp()->toolbox()->microhardManager()->configPassword().toStdString() + "\n";
_tcpSocket->write(pwd.c_str()); _tcpSocket->write(pwd.c_str());
} else if (bytesIn.contains("UserDevice>")) { } else if (bytesIn.contains("Login incorrect")) {
emit connected(-1);
} else if (bytesIn.contains("Entering")) {
if (!loggedIn() && _setEncryptionKey) { if (!loggedIn() && _setEncryptionKey) {
setEncryptionKey(qgcApp()->toolbox()->microhardManager()->encryptionKey()); setEncryptionKey(qgcApp()->toolbox()->microhardManager()->encryptionKey());
} }
_loggedIn = true; _loggedIn = true;
emit connected(1);
} }
emit rssiUpdated(_rssiVal); emit rssiUpdated(_rssiVal);
......
...@@ -121,16 +121,32 @@ Rectangle { ...@@ -121,16 +121,32 @@ Rectangle {
Layout.minimumWidth: _labelWidth Layout.minimumWidth: _labelWidth
} }
QGCLabel { QGCLabel {
text: QGroundControl.microhardManager.connected ? qsTr("Connected") : qsTr("Not Connected") function getStatus(status) {
color: QGroundControl.microhardManager.connected ? qgcPal.colorGreen : qgcPal.colorRed if (status === 1)
return qsTr("Connected");
else if (status === -1)
return qsTr("Login Error")
else
return qsTr("Not Connected")
}
text: getStatus(QGroundControl.microhardManager.connected)
color: QGroundControl.microhardManager.connected === 1 ? qgcPal.colorGreen : qgcPal.colorRed
Layout.minimumWidth: _valueWidth Layout.minimumWidth: _valueWidth
} }
QGCLabel { QGCLabel {
text: qsTr("Air Unit:") text: qsTr("Air Unit:")
} }
QGCLabel { QGCLabel {
text: QGroundControl.microhardManager.linkConnected ? qsTr("Connected") : qsTr("Not Connected") function getStatus(status) {
color: QGroundControl.microhardManager.linkConnected ? qgcPal.colorGreen : qgcPal.colorRed if (status === 1)
return qsTr("Connected");
else if (status === -1)
return qsTr("Login Error")
else
return qsTr("Not Connected")
}
text: getStatus(QGroundControl.microhardManager.linkConnected)
color: QGroundControl.microhardManager.linkConnected === 1 ? qgcPal.colorGreen : qgcPal.colorRed
} }
QGCLabel { QGCLabel {
text: qsTr("Uplink RSSI:") text: qsTr("Uplink RSSI:")
...@@ -210,7 +226,16 @@ Rectangle { ...@@ -210,7 +226,16 @@ Rectangle {
Layout.minimumWidth: _valueWidth Layout.minimumWidth: _valueWidth
} }
QGCLabel { QGCLabel {
text: qsTr("Configuration password:") text: qsTr("Configuration User Name:")
}
QGCTextField {
id: configUserName
text: QGroundControl.microhardManager.configUserName
enabled: true
Layout.minimumWidth: _valueWidth
}
QGCLabel {
text: qsTr("Configuration Password:")
} }
QGCTextField { QGCTextField {
id: configPassword id: configPassword
...@@ -244,6 +269,7 @@ Rectangle { ...@@ -244,6 +269,7 @@ Rectangle {
if(localIP.text === QGroundControl.microhardManager.localIPAddr && if(localIP.text === QGroundControl.microhardManager.localIPAddr &&
remoteIP.text === QGroundControl.microhardManager.remoteIPAddr && remoteIP.text === QGroundControl.microhardManager.remoteIPAddr &&
netMask.text === QGroundControl.microhardManager.netMask && netMask.text === QGroundControl.microhardManager.netMask &&
configUserName.text === QGroundControl.microhardManager.configUserName &&
configPassword.text === QGroundControl.microhardManager.configPassword && configPassword.text === QGroundControl.microhardManager.configPassword &&
encryptionKey.text === QGroundControl.microhardManager.encryptionKey) encryptionKey.text === QGroundControl.microhardManager.encryptionKey)
return false return false
...@@ -256,7 +282,7 @@ Rectangle { ...@@ -256,7 +282,7 @@ Rectangle {
text: qsTr("Apply") text: qsTr("Apply")
anchors.horizontalCenter: parent.horizontalCenter anchors.horizontalCenter: parent.horizontalCenter
onClicked: { onClicked: {
QGroundControl.microhardManager.setIPSettings(localIP.text, remoteIP.text, netMask.text, configPassword.text, encryptionKey.text) QGroundControl.microhardManager.setIPSettings(localIP.text, remoteIP.text, netMask.text, configUserName.text, configPassword.text, encryptionKey.text)
} }
} }
......
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