Commit 12ac1893 authored by Don Gagne's avatar Don Gagne Committed by GitHub

Merge pull request #4585 from DonLakeFlyer/AutoConnectSettings

Moving more settings to new SettingGroup mechanism
parents f14af89f 5c1f56dd
......@@ -8,15 +8,85 @@
****************************************************************************/
#include "AutoConnectSettings.h"
#include "LinkManager.h"
#include <QQmlEngine>
#include <QtQml>
const char* AutoConnectSettings::_settingsGroup = "LinkManager";
const char* AutoConnectSettings:: autoConnectUDPSettingsName = "AutoconnectUDP";
const char* AutoConnectSettings:: autoConnectPixhawkSettingsName = "AutoconnectPixhawk";
const char* AutoConnectSettings:: autoConnectSiKRadioSettingsName = "Autoconnect3DRRadio";
const char* AutoConnectSettings:: autoConnectPX4FlowSettingsName = "AutoconnectPX4Flow";
const char* AutoConnectSettings:: autoConnectRTKGPSSettingsName = "AutoconnectRTKGPS";
const char* AutoConnectSettings:: autoConnectLibrePilotSettingsName = "AutoconnectLibrePilot";
const char* AutoConnectSettings::autoConnectSettingsGroupName = "autoConnect";
AutoConnectSettings::AutoConnectSettings(QObject* parent)
: SettingsGroup(autoConnectSettingsGroupName, QString() /* root settings group */, parent)
: SettingsGroup(autoConnectSettingsGroupName, _settingsGroup, parent)
, _autoConnectUDPFact(NULL)
, _autoConnectPixhawkFact(NULL)
, _autoConnectSiKRadioFact(NULL)
, _autoConnectPX4FlowFact(NULL)
, _autoConnectRTKGPSFact(NULL)
, _autoConnectLibrePilotFact(NULL)
{
QQmlEngine::setObjectOwnership(this, QQmlEngine::CppOwnership);
qmlRegisterUncreatableType<AutoConnectSettings>("QGroundControl.SettingsManager", 1, 0, "AutoConnectSettings", "Reference only");
}
Fact* AutoConnectSettings::autoConnectUDP(void)
{
if (!_autoConnectUDPFact) {
_autoConnectUDPFact = _createSettingsFact(autoConnectUDPSettingsName);
}
return _autoConnectUDPFact;
}
Fact* AutoConnectSettings::autoConnectPixhawk(void)
{
if (!_autoConnectPixhawkFact) {
_autoConnectPixhawkFact = _createSettingsFact(autoConnectPixhawkSettingsName);
}
return _autoConnectPixhawkFact;
}
Fact* AutoConnectSettings::autoConnectSiKRadio(void)
{
if (!_autoConnectSiKRadioFact) {
_autoConnectSiKRadioFact = _createSettingsFact(autoConnectSiKRadioSettingsName);
}
return _autoConnectSiKRadioFact;
}
Fact* AutoConnectSettings::autoConnectPX4Flow(void)
{
if (!_autoConnectPX4FlowFact) {
_autoConnectPX4FlowFact = _createSettingsFact(autoConnectPX4FlowSettingsName);
}
return _autoConnectPX4FlowFact;
}
Fact* AutoConnectSettings::autoConnectRTKGPS(void)
{
if (!_autoConnectRTKGPSFact) {
_autoConnectRTKGPSFact = _createSettingsFact(autoConnectRTKGPSSettingsName);
}
return _autoConnectRTKGPSFact;
}
Fact* AutoConnectSettings::autoConnectLibrePilot(void)
{
if (!_autoConnectLibrePilotFact) {
_autoConnectLibrePilotFact = _createSettingsFact(autoConnectLibrePilotSettingsName);
}
return _autoConnectLibrePilotFact;
}
......@@ -19,9 +19,38 @@ class AutoConnectSettings : public SettingsGroup
public:
AutoConnectSettings(QObject* parent = NULL);
Q_PROPERTY(Fact* autoConnectUDP READ autoConnectUDP CONSTANT)
Q_PROPERTY(Fact* autoConnectPixhawk READ autoConnectPixhawk CONSTANT)
Q_PROPERTY(Fact* autoConnectSiKRadio READ autoConnectSiKRadio CONSTANT)
Q_PROPERTY(Fact* autoConnectPX4Flow READ autoConnectPX4Flow CONSTANT)
Q_PROPERTY(Fact* autoConnectRTKGPS READ autoConnectRTKGPS CONSTANT)
Q_PROPERTY(Fact* autoConnectLibrePilot READ autoConnectLibrePilot CONSTANT)
Fact* autoConnectUDP (void);
Fact* autoConnectPixhawk (void);
Fact* autoConnectSiKRadio (void);
Fact* autoConnectPX4Flow (void);
Fact* autoConnectRTKGPS (void);
Fact* autoConnectLibrePilot (void);
static const char* autoConnectSettingsGroupName;
static const char* autoConnectUDPSettingsName;
static const char* autoConnectPixhawkSettingsName;
static const char* autoConnectSiKRadioSettingsName;
static const char* autoConnectPX4FlowSettingsName;
static const char* autoConnectRTKGPSSettingsName;
static const char* autoConnectLibrePilotSettingsName;
private:
SettingsFact* _autoConnectUDPFact;
SettingsFact* _autoConnectPixhawkFact;
SettingsFact* _autoConnectSiKRadioFact;
SettingsFact* _autoConnectPX4FlowFact;
SettingsFact* _autoConnectRTKGPSFact;
SettingsFact* _autoConnectLibrePilotFact;
static const char* _settingsGroup;
};
#endif
[
{
"name": "AutoconnectUDP",
"shortDescription": "Automatically open a connection over UDP",
"longDescription": "If this option is enabled GroundControl will automatically connect to a vehicle which is detected on a UDP communication link.",
"type": "bool",
"defaultValue": true
},
{
"name": "AutoconnectPixhawk",
"shortDescription": "Automatically connect to a Pixhawk board",
"longDescription": "If this option is enabled GroundControl will automatically connect to a Pixhawk board which is connected via USB.",
"type": "bool",
"defaultValue": true
},
{
"name": "Autoconnect3DRRadio",
"shortDescription": "Automatically connect to a SiK Radio",
"longDescription": "If this option is enabled GroundControl will automatically connect to a vehicle which is detected on a SiK Radio communication link.",
"type": "bool",
"defaultValue": true
},
{
"name": "AutoconnectPX4Flow",
"shortDescription": "Automatically connect to a P4 Flow",
"longDescription": "If this option is enabled GroundControl will automatically connect to a PX4 Flow board which is connected via USB.",
"type": "bool",
"defaultValue": true
},
{
"name": "AutoconnectRTKGPS",
"shortDescription": "Automatically connect to an RTK GPS",
"longDescription": "If this option is enabled GroundControl will automatically connect to an RTK GPS which is connected via USB.",
"type": "bool",
"defaultValue": true
},
{
"name": "AutoconnectLibrePilot",
"shortDescription": "Automatically connect to a LibrePilot",
"longDescription": "If this option is enabled GroundControl will automatically connect to a LibrePilot board which is connected via USB.",
"type": "bool",
"defaultValue": true
}
]
......@@ -20,6 +20,7 @@
#include "QGCApplication.h"
#include "UDPLink.h"
#include "TCPLink.h"
#include "SettingsManager.h"
#ifdef QGC_ENABLE_BLUETOOTH
#include "BluetoothLink.h"
#endif
......@@ -31,13 +32,6 @@
QGC_LOGGING_CATEGORY(LinkManagerLog, "LinkManagerLog")
QGC_LOGGING_CATEGORY(LinkManagerVerboseLog, "LinkManagerVerboseLog")
const char* LinkManager::_settingsGroup = "LinkManager";
const char* LinkManager::_autoconnectUDPKey = "AutoconnectUDP";
const char* LinkManager::_autoconnectPixhawkKey = "AutoconnectPixhawk";
const char* LinkManager::_autoconnect3DRRadioKey = "Autoconnect3DRRadio";
const char* LinkManager::_autoconnectPX4FlowKey = "AutoconnectPX4Flow";
const char* LinkManager::_autoconnectRTKGPSKey = "AutoconnectRTKGPS";
const char* LinkManager::_autoconnectLibrePilotKey = "AutoconnectLibrePilot";
const char* LinkManager::_defaultUPDLinkName = "UDP Link (AutoConnect)";
const int LinkManager::_autoconnectUpdateTimerMSecs = 1000;
......@@ -49,33 +43,18 @@ const int LinkManager::_autoconnectConnectDelayMSecs = 1000;
#endif
LinkManager::LinkManager(QGCApplication* app)
: QGCTool(app)
: QGCTool(app)
, _configUpdateSuspended(false)
, _configurationsLoaded(false)
, _connectionsSuspended(false)
, _mavlinkChannelsUsedBitMask(1) // We never use channel 0 to avoid sequence numbering problems
, _autoConnectSettings(NULL)
, _mavlinkProtocol(NULL)
, _autoconnectUDP(true)
, _autoconnectPixhawk(true)
, _autoconnect3DRRadio(true)
, _autoconnectPX4Flow(true)
, _autoconnectRTKGPS(true)
, _autoconnectLibrePilot(true)
{
qmlRegisterUncreatableType<LinkManager> ("QGroundControl", 1, 0, "LinkManager", "Reference only");
qmlRegisterUncreatableType<LinkConfiguration> ("QGroundControl", 1, 0, "LinkConfiguration", "Reference only");
qmlRegisterUncreatableType<LinkInterface> ("QGroundControl", 1, 0, "LinkInterface", "Reference only");
QSettings settings;
settings.beginGroup(_settingsGroup);
_autoconnectUDP = settings.value(_autoconnectUDPKey, true).toBool();
_autoconnectPixhawk = settings.value(_autoconnectPixhawkKey, true).toBool();
_autoconnect3DRRadio = settings.value(_autoconnect3DRRadioKey, true).toBool();
_autoconnectPX4Flow = settings.value(_autoconnectPX4FlowKey, true).toBool();
_autoconnectRTKGPS = settings.value(_autoconnectRTKGPSKey, true).toBool();
_autoconnectLibrePilot = settings.value(_autoconnectLibrePilotKey, true).toBool();
#ifndef NO_SERIAL_LINK
_activeLinkCheckTimer.setInterval(_activeLinkCheckTimeoutMSecs);
_activeLinkCheckTimer.setSingleShot(false);
......@@ -92,6 +71,7 @@ void LinkManager::setToolbox(QGCToolbox *toolbox)
{
QGCTool::setToolbox(toolbox);
_autoConnectSettings = toolbox->settingsManager()->autoConnectSettings();
_mavlinkProtocol = _toolbox->mavlinkProtocol();
connect(&_portListTimer, &QTimer::timeout, this, &LinkManager::_updateAutoConnectLinks);
......@@ -485,7 +465,7 @@ void LinkManager::_updateAutoConnectLinks(void)
break;
}
}
if (!foundUDP && _autoconnectUDP) {
if (!foundUDP && _autoConnectSettings->autoConnectUDP()->rawValue().toBool()) {
qCDebug(LinkManagerLog) << "New auto-connect UDP port added";
UDPConfiguration* udpConfig = new UDPConfiguration(_defaultUPDLinkName);
udpConfig->setLocalPort(QGC_UDP_LOCAL_PORT);
......@@ -549,29 +529,29 @@ void LinkManager::_updateAutoConnectLinks(void)
switch (boardType) {
case QGCSerialPortInfo::BoardTypePixhawk:
if (_autoconnectPixhawk) {
if (_autoConnectSettings->autoConnectPixhawk()->rawValue().toBool()) {
pSerialConfig = new SerialConfiguration(tr("%1 on %2 (AutoConnect)").arg(boardName).arg(portInfo.portName().trimmed()));
pSerialConfig->setUsbDirect(true);
}
break;
case QGCSerialPortInfo::BoardTypePX4Flow:
if (_autoconnectPX4Flow) {
if (_autoConnectSettings->autoConnectPX4Flow()->rawValue().toBool()) {
pSerialConfig = new SerialConfiguration(tr("%1 on %2 (AutoConnect)").arg(boardName).arg(portInfo.portName().trimmed()));
}
break;
case QGCSerialPortInfo::BoardTypeSiKRadio:
if (_autoconnect3DRRadio) {
if (_autoConnectSettings->autoConnectSiKRadio()->rawValue().toBool()) {
pSerialConfig = new SerialConfiguration(tr("%1 on %2 (AutoConnect)").arg(boardName).arg(portInfo.portName().trimmed()));
}
break;
case QGCSerialPortInfo::BoardTypeOpenPilot:
if (_autoconnectLibrePilot) {
if (_autoConnectSettings->autoConnectLibrePilot()->rawValue().toBool()) {
pSerialConfig = new SerialConfiguration(tr("%1 on %2 (AutoConnect)").arg(boardName).arg(portInfo.portName().trimmed()));
}
break;
#ifndef __mobile__
case QGCSerialPortInfo::BoardTypeRTKGPS:
if (_autoconnectRTKGPS && !_toolbox->gpsManager()->connected()) {
if (_autoConnectSettings->autoConnectRTKGPS()->rawValue().toBool() && !_toolbox->gpsManager()->connected()) {
qCDebug(LinkManagerLog) << "RTK GPS auto-connected";
_toolbox->gpsManager()->connectGPS(portInfo.systemLocation());
}
......@@ -647,62 +627,6 @@ void LinkManager::shutdown(void)
disconnectAll();
}
bool LinkManager::_setAutoconnectWorker(bool& currentAutoconnect, bool newAutoconnect, const char* autoconnectKey)
{
if (currentAutoconnect != newAutoconnect) {
QSettings settings;
settings.beginGroup(_settingsGroup);
settings.setValue(autoconnectKey, newAutoconnect);
currentAutoconnect = newAutoconnect;
return true;
}
return false;
}
void LinkManager::setAutoconnectUDP(bool autoconnect)
{
if (_setAutoconnectWorker(_autoconnectUDP, autoconnect, _autoconnectUDPKey)) {
emit autoconnectUDPChanged(autoconnect);
}
}
void LinkManager::setAutoconnectPixhawk(bool autoconnect)
{
if (_setAutoconnectWorker(_autoconnectPixhawk, autoconnect, _autoconnectPixhawkKey)) {
emit autoconnectPixhawkChanged(autoconnect);
}
}
void LinkManager::setAutoconnect3DRRadio(bool autoconnect)
{
if (_setAutoconnectWorker(_autoconnect3DRRadio, autoconnect, _autoconnect3DRRadioKey)) {
emit autoconnect3DRRadioChanged(autoconnect);
}
}
void LinkManager::setAutoconnectPX4Flow(bool autoconnect)
{
if (_setAutoconnectWorker(_autoconnectPX4Flow, autoconnect, _autoconnectPX4FlowKey)) {
emit autoconnectPX4FlowChanged(autoconnect);
}
}
void LinkManager::setAutoconnectRTKGPS(bool autoconnect)
{
if (_setAutoconnectWorker(_autoconnectRTKGPS, autoconnect, _autoconnectRTKGPSKey)) {
emit autoconnectRTKGPSChanged(autoconnect);
}
}
void LinkManager::setAutoconnectLibrePilot(bool autoconnect)
{
if (_setAutoconnectWorker(_autoconnectLibrePilot, autoconnect, _autoconnectLibrePilotKey)) {
emit autoconnectLibrePilotChanged(autoconnect);
}
}
QStringList LinkManager::linkTypeStrings(void) const
{
//-- Must follow same order as enum LinkType in LinkConfiguration.h
......
......@@ -37,12 +37,12 @@
#include "MockLink.h"
#endif
class UDPConfiguration;
Q_DECLARE_LOGGING_CATEGORY(LinkManagerLog)
Q_DECLARE_LOGGING_CATEGORY(LinkManagerVerboseLog)
class QGCApplication;
class UDPConfiguration;
class AutoConnectSettings;
/// Manage communication links
///
......@@ -61,14 +61,7 @@ public:
LinkManager(QGCApplication* app);
~LinkManager();
Q_PROPERTY(bool autoconnectUDP READ autoconnectUDP WRITE setAutoconnectUDP NOTIFY autoconnectUDPChanged)
Q_PROPERTY(bool autoconnectPixhawk READ autoconnectPixhawk WRITE setAutoconnectPixhawk NOTIFY autoconnectPixhawkChanged)
Q_PROPERTY(bool autoconnect3DRRadio READ autoconnect3DRRadio WRITE setAutoconnect3DRRadio NOTIFY autoconnect3DRRadioChanged)
Q_PROPERTY(bool autoconnectPX4Flow READ autoconnectPX4Flow WRITE setAutoconnectPX4Flow NOTIFY autoconnectPX4FlowChanged)
Q_PROPERTY(bool autoconnectRTKGPS READ autoconnectRTKGPS WRITE setAutoconnectRTKGPS NOTIFY autoconnectRTKGPSChanged)
Q_PROPERTY(bool autoconnectLibrePilot READ autoconnectLibrePilot WRITE setAutoconnectLibrePilot NOTIFY autoconnectLibrePilotChanged)
Q_PROPERTY(bool isBluetoothAvailable READ isBluetoothAvailable CONSTANT)
Q_PROPERTY(QmlObjectListModel* linkConfigurations READ _qmlLinkConfigurations NOTIFY linkConfigurationsChanged)
Q_PROPERTY(QStringList linkTypeStrings READ linkTypeStrings CONSTANT)
Q_PROPERTY(QStringList serialBaudRates READ serialBaudRates CONSTANT)
......@@ -85,12 +78,6 @@ public:
// Property accessors
bool autoconnectUDP (void) { return _autoconnectUDP; }
bool autoconnectPixhawk (void) { return _autoconnectPixhawk; }
bool autoconnect3DRRadio (void) { return _autoconnect3DRRadio; }
bool autoconnectPX4Flow (void) { return _autoconnectPX4Flow; }
bool autoconnectRTKGPS (void) { return _autoconnectRTKGPS; }
bool autoconnectLibrePilot (void) { return _autoconnectLibrePilot; }
bool isBluetoothAvailable (void);
QList<LinkInterface*> links (void);
......@@ -99,13 +86,6 @@ public:
QStringList serialPortStrings (void);
QStringList serialPorts (void);
void setAutoconnectUDP (bool autoconnect);
void setAutoconnectPixhawk (bool autoconnect);
void setAutoconnect3DRRadio (bool autoconnect);
void setAutoconnectPX4Flow (bool autoconnect);
void setAutoconnectRTKGPS (bool autoconnect);
void setAutoconnectLibrePilot (bool autoconnect);
/// Load list of link configurations from disk
void loadLinkConfigurationList();
......@@ -173,15 +153,9 @@ public:
void startAutoConnectedLinks(void);
signals:
void autoconnectUDPChanged (bool autoconnect);
void autoconnectPixhawkChanged (bool autoconnect);
void autoconnect3DRRadioChanged (bool autoconnect);
void autoconnectPX4FlowChanged (bool autoconnect);
void autoconnectRTKGPSChanged (bool autoconnect);
void autoconnectLibrePilotChanged (bool autoconnect);
static const char* settingsGroup;
signals:
void newLink(LinkInterface* link);
// Link has been deleted. You may not necessarily get a linkInactive before the link is deleted.
......@@ -217,7 +191,6 @@ private:
void _updateAutoConnectLinks(void);
void _updateSerialPorts();
void _fixUnnamed(LinkConfiguration* config);
bool _setAutoconnectWorker(bool& currentAutoconnect, bool newAutoconnect, const char* autoconnectKey);
void _removeConfiguration(LinkConfiguration* config);
#ifndef NO_SERIAL_LINK
......@@ -231,8 +204,8 @@ private:
QTimer _portListTimer;
uint32_t _mavlinkChannelsUsedBitMask;
MAVLinkProtocol* _mavlinkProtocol;
AutoConnectSettings* _autoConnectSettings;
MAVLinkProtocol* _mavlinkProtocol;
QList<SharedLinkInterfacePointer> _sharedLinks;
QList<SharedLinkConfigurationPointer> _sharedConfigurations;
......@@ -243,25 +216,12 @@ private:
QStringList _commPortList;
QStringList _commPortDisplayList;
bool _autoconnectUDP;
bool _autoconnectPixhawk;
bool _autoconnect3DRRadio;
bool _autoconnectPX4Flow;
bool _autoconnectRTKGPS;
bool _autoconnectLibrePilot;
#ifndef NO_SERIAL_LINK
QTimer _activeLinkCheckTimer; ///< Timer which checks for a vehicle showing up on a usb direct link
QList<SerialLink*> _activeLinkCheckList; ///< List of links we are waiting for a vehicle to show up on
static const int _activeLinkCheckTimeoutMSecs = 15000; ///< Amount of time to wait for a heatbeat. Keep in mind ArduPilot stack heartbeat is slow to come.
#endif
static const char* _settingsGroup;
static const char* _autoconnectUDPKey;
static const char* _autoconnectPixhawkKey;
static const char* _autoconnect3DRRadioKey;
static const char* _autoconnectPX4FlowKey;
static const char* _autoconnectRTKGPSKey;
static const char* _autoconnectLibrePilotKey;
static const char* _defaultUPDLinkName;
static const int _autoconnectUpdateTimerMSecs;
static const int _autoconnectConnectDelayMSecs;
......
......@@ -424,38 +424,32 @@ QGCView {
//-- Autoconnect settings
Row {
spacing: ScreenTools.defaultFontPixelWidth * 2
QGCCheckBox {
FactCheckBox {
text: qsTr("Pixhawk")
fact: QGroundControl.settingsManager.autoConnectSettings.autoConnectPixhawk
visible: !ScreenTools.isiOS
checked: QGroundControl.linkManager.autoconnectPixhawk
onClicked: QGroundControl.linkManager.autoconnectPixhawk = checked
}
QGCCheckBox {
FactCheckBox {
text: qsTr("SiK Radio")
fact: QGroundControl.settingsManager.autoConnectSettings.autoConnectSiKRadio
visible: !ScreenTools.isiOS
checked: QGroundControl.linkManager.autoconnect3DRRadio
onClicked: QGroundControl.linkManager.autoconnect3DRRadio = checked
}
QGCCheckBox {
FactCheckBox {
text: qsTr("PX4 Flow")
fact: QGroundControl.settingsManager.autoConnectSettings.autoConnectPX4Flow
visible: !ScreenTools.isiOS
checked: QGroundControl.linkManager.autoconnectPX4Flow
onClicked: QGroundControl.linkManager.autoconnectPX4Flow = checked
}
QGCCheckBox {
FactCheckBox {
text: qsTr("LibrePilot")
checked: QGroundControl.linkManager.autoconnectLibrePilot
onClicked: QGroundControl.linkManager.autoconnectLibrePilot = checked
fact: QGroundControl.settingsManager.autoConnectSettings.autoConnectLibrePilot
}
QGCCheckBox {
FactCheckBox {
text: qsTr("UDP")
checked: QGroundControl.linkManager.autoconnectUDP
onClicked: QGroundControl.linkManager.autoconnectUDP = checked
fact: QGroundControl.settingsManager.autoConnectSettings.autoConnectUDP
}
QGCCheckBox {
FactCheckBox {
text: qsTr("RTK GPS")
checked: QGroundControl.linkManager.autoconnectRTKGPS
onClicked: QGroundControl.linkManager.autoconnectRTKGPS = checked
fact: QGroundControl.settingsManager.autoConnectSettings.autoConnectRTKGPS
}
}
}
......
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