Commit f6d02084 authored by Don Gagne's avatar Don Gagne

AutoConnect for RT GPS

parent c92cd774
......@@ -36,7 +36,7 @@ GPSManager::~GPSManager()
cleanup();
}
void GPSManager::setupGPS(const QString& device)
void GPSManager::connectGPS(const QString& device)
{
Q_ASSERT(_toolbox);
......
......@@ -41,7 +41,8 @@ public:
GPSManager(QGCApplication* app);
~GPSManager();
void setupGPS(const QString& device);
void connectGPS(const QString& device);
bool connected(void) const { return _gpsProvider != nullptr; }
private slots:
void GPSPositionUpdate(GPSPositionMessage msg);
......
......@@ -47,6 +47,9 @@ QGCToolbox::QGCToolbox(QGCApplication* app)
, _factSystem(NULL)
, _firmwarePluginManager(NULL)
, _flightMapSettings(NULL)
#ifndef __mobile
, _gpsManager(NULL)
#endif
, _homePositionManager(NULL)
, _imageProvider(NULL)
, _joystickManager(NULL)
......@@ -97,8 +100,6 @@ QGCToolbox::QGCToolbox(QGCApplication* app)
_mapEngineManager->setToolbox(this);
_uasMessageHandler->setToolbox(this);
_followMe->setToolbox(this);
//FIXME: make this configurable...
//_gpsManager->setupGPS("ttyACM0");
_qgcPositionManager->setToolbox(this);
}
......
......@@ -67,6 +67,9 @@ public:
UASMessageHandler* uasMessageHandler(void) { return _uasMessageHandler; }
FollowMe* followMe(void) { return _followMe; }
QGCPositionManager* qgcPositionManager(void) { return _qgcPositionManager; }
#ifndef __mobile__
GPSManager* gpsManager(void) { return _gpsManager; }
#endif
private:
GAudioOutput* _audioOutput;
......@@ -74,7 +77,9 @@ private:
FactSystem* _factSystem;
FirmwarePluginManager* _firmwarePluginManager;
FlightMapSettings* _flightMapSettings;
#ifndef __mobile__
GPSManager* _gpsManager;
#endif
HomePositionManager* _homePositionManager;
QGCImageProvider* _imageProvider;
JoystickManager* _joystickManager;
......
......@@ -46,6 +46,10 @@ This file is part of the QGROUNDCONTROL project
#include "BluetoothLink.h"
#endif
#ifndef __mobile__
#include "GPSManager.h"
#endif
QGC_LOGGING_CATEGORY(LinkManagerLog, "LinkManagerLog")
QGC_LOGGING_CATEGORY(LinkManagerVerboseLog, "LinkManagerVerboseLog")
......@@ -54,6 +58,7 @@ 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::_defaultUPDLinkName = "Default UDP Link";
const int LinkManager::_autoconnectUpdateTimerMSecs = 1000;
......@@ -75,7 +80,7 @@ LinkManager::LinkManager(QGCApplication* app)
, _autoconnectPixhawk(true)
, _autoconnect3DRRadio(true)
, _autoconnectPX4Flow(true)
, _autoconnectRTKGPS(true)
{
qmlRegisterUncreatableType<LinkManager> ("QGroundControl", 1, 0, "LinkManager", "Reference only");
qmlRegisterUncreatableType<LinkConfiguration> ("QGroundControl", 1, 0, "LinkConfiguration", "Reference only");
......@@ -88,6 +93,7 @@ LinkManager::LinkManager(QGCApplication* app)
_autoconnectPixhawk = settings.value(_autoconnectPixhawkKey, true).toBool();
_autoconnect3DRRadio = settings.value(_autoconnect3DRRadioKey, true).toBool();
_autoconnectPX4Flow = settings.value(_autoconnectPX4FlowKey, true).toBool();
_autoconnectRTKGPS = settings.value(_autoconnectRTKGPSKey, true).toBool();
#ifndef __ios__
_activeLinkCheckTimer.setInterval(_activeLinkCheckTimeoutMSecs);
......@@ -553,6 +559,14 @@ void LinkManager::_updateAutoConnectLinks(void)
pSerialConfig = new SerialConfiguration(QString("SiK Radio on %1").arg(portInfo.portName().trimmed()));
}
break;
#ifndef __mobile__
case QGCSerialPortInfo::BoardTypeRTKGPS:
if (_autoconnectRTKGPS && !_toolbox->gpsManager()->connected()) {
qCDebug(LinkManagerLog) << "RTK GPS auto-connected";
_toolbox->gpsManager()->connectGPS(portInfo.systemLocation());
}
break;
#endif
default:
qWarning() << "Internal error";
continue;
......@@ -611,59 +625,53 @@ void LinkManager::shutdown(void)
disconnectAll();
}
void LinkManager::setAutoconnectUDP(bool autoconnect)
bool LinkManager::_setAutoconnectWorker(bool& currentAutoconnect, bool newAutoconnect, const char* autoconnectKey)
{
if (_autoconnectUDP != autoconnect) {
if (currentAutoconnect != newAutoconnect) {
QSettings settings;
settings.beginGroup(_settingsGroup);
settings.setValue(_autoconnectUDPKey, autoconnect);
settings.setValue(autoconnectKey, newAutoconnect);
currentAutoconnect = newAutoconnect;
return true;
}
return false;
}
_autoconnectUDP = autoconnect;
void LinkManager::setAutoconnectUDP(bool autoconnect)
{
if (_setAutoconnectWorker(_autoconnectUDP, autoconnect, _autoconnectUDPKey)) {
emit autoconnectUDPChanged(autoconnect);
}
}
void LinkManager::setAutoconnectPixhawk(bool autoconnect)
{
if (_autoconnectPixhawk != autoconnect) {
QSettings settings;
settings.beginGroup(_settingsGroup);
settings.setValue(_autoconnectPixhawkKey, autoconnect);
_autoconnectPixhawk = autoconnect;
if (_setAutoconnectWorker(_autoconnectPixhawk, autoconnect, _autoconnectPixhawkKey)) {
emit autoconnectPixhawkChanged(autoconnect);
}
}
void LinkManager::setAutoconnect3DRRadio(bool autoconnect)
{
if (_autoconnect3DRRadio != autoconnect) {
QSettings settings;
settings.beginGroup(_settingsGroup);
settings.setValue(_autoconnect3DRRadioKey, autoconnect);
_autoconnect3DRRadio = autoconnect;
if (_setAutoconnectWorker(_autoconnect3DRRadio, autoconnect, _autoconnect3DRRadioKey)) {
emit autoconnect3DRRadioChanged(autoconnect);
}
}
void LinkManager::setAutoconnectPX4Flow(bool autoconnect)
{
if (_autoconnectPX4Flow != autoconnect) {
QSettings settings;
settings.beginGroup(_settingsGroup);
settings.setValue(_autoconnectPX4FlowKey, autoconnect);
_autoconnectPX4Flow = autoconnect;
if (_setAutoconnectWorker(_autoconnectPX4Flow, autoconnect, _autoconnectPX4FlowKey)) {
emit autoconnectPX4FlowChanged(autoconnect);
}
}
void LinkManager::setAutoconnectRTKGPS(bool autoconnect)
{
if (_setAutoconnectWorker(_autoconnectRTKGPS, autoconnect, _autoconnectRTKGPSKey)) {
emit autoconnectRTKGPSChanged(autoconnect);
}
}
QStringList LinkManager::linkTypeStrings(void) const
......
......@@ -78,6 +78,7 @@ public:
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 isBluetoothAvailable READ isBluetoothAvailable CONSTANT)
/// LinkInterface Accessor
......@@ -107,6 +108,7 @@ public:
bool autoconnectPixhawk (void) { return _autoconnectPixhawk; }
bool autoconnect3DRRadio (void) { return _autoconnect3DRRadio; }
bool autoconnectPX4Flow (void) { return _autoconnectPX4Flow; }
bool autoconnectRTKGPS (void) { return _autoconnectRTKGPS; }
bool isBluetoothAvailable (void);
QmlObjectListModel* links (void) { return &_links; }
......@@ -120,6 +122,7 @@ public:
void setAutoconnectPixhawk (bool autoconnect);
void setAutoconnect3DRRadio (bool autoconnect);
void setAutoconnectPX4Flow (bool autoconnect);
void setAutoconnectRTKGPS (bool autoconnect);
/// Load list of link configurations from disk
void loadLinkConfigurationList();
......@@ -173,10 +176,11 @@ public:
virtual void setToolbox(QGCToolbox *toolbox);
signals:
void autoconnectUDPChanged(bool autoconnect);
void autoconnectPixhawkChanged(bool autoconnect);
void autoconnect3DRRadioChanged(bool autoconnect);
void autoconnectPX4FlowChanged(bool autoconnect);
void autoconnectUDPChanged (bool autoconnect);
void autoconnectPixhawkChanged (bool autoconnect);
void autoconnect3DRRadioChanged (bool autoconnect);
void autoconnectPX4FlowChanged (bool autoconnect);
void autoconnectRTKGPSChanged (bool autoconnect);
void newLink(LinkInterface* link);
......@@ -212,6 +216,7 @@ private:
void _updateAutoConnectLinks(void);
void _updateSerialPorts();
void _fixUnnamed(LinkConfiguration* config);
bool _setAutoconnectWorker(bool& currentAutoconnect, bool newAutoconnect, const char* autoconnectKey);
#ifndef __ios__
SerialConfiguration* _autoconnectConfigurationsContainsPort(const QString& portName);
......@@ -238,6 +243,7 @@ private:
bool _autoconnectPixhawk;
bool _autoconnect3DRRadio;
bool _autoconnectPX4Flow;
bool _autoconnectRTKGPS;
#ifndef __ios__
QTimer _activeLinkCheckTimer; ///< Timer which checks for a vehicle showing up on a usb direct link
......@@ -250,6 +256,7 @@ private:
static const char* _autoconnectPixhawkKey;
static const char* _autoconnect3DRRadioKey;
static const char* _autoconnectPX4FlowKey;
static const char* _autoconnectRTKGPSKey;
static const char* _defaultUPDLinkName;
static const int _autoconnectUpdateTimerMSecs;
static const int _autoconnectConnectDelayMSecs;
......
......@@ -309,6 +309,12 @@ Rectangle {
checked: QGroundControl.linkManager.autoconnectUDP
onClicked: QGroundControl.linkManager.autoconnectUDP = checked
}
QGCCheckBox {
text: qsTr("RTK GPS")
checked: QGroundControl.linkManager.autoconnectRTKGPS
onClicked: QGroundControl.linkManager.autoconnectRTKGPS = checked
}
}
Item {
......
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