@ -46,6 +46,10 @@ This file is part of the QGROUNDCONTROL project
@@ -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";
@@ -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)
@@ -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)
@@ -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)
@@ -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)
@@ -611,59 +625,53 @@ void LinkManager::shutdown(void)
disconnectAll ( ) ;
}
void LinkManager : : setAutoconnectUDP ( bool a utoconnect)
bool LinkManager : : _setAutoconnectWorker ( bool & currentAutoconnect , bool newA utoconnect, const char * autoconnectKey )
{
if ( _autoconnectUDP ! = a utoconnect) {
if ( currentAutoconnect ! = newA utoconnect) {
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