diff --git a/qgroundcontrol.pro b/qgroundcontrol.pro index 04f879ec2c5..aae6421b9da 100644 --- a/qgroundcontrol.pro +++ b/qgroundcontrol.pro @@ -660,7 +660,7 @@ HEADERS += \ src/GPS/GPSManager.h \ src/GPS/GPSPositionMessage.h \ src/GPS/GPSProvider.h \ - src/GPS/RTCM/RTCMMavlink.h \ + src/GPS/RTCMMavlink.h \ src/GPS/definitions.h \ src/GPS/satellite_info.h \ src/GPS/sensor_gps.h \ @@ -905,7 +905,7 @@ SOURCES += \ src/GPS/Drivers/src/sbf.cpp \ src/GPS/GPSManager.cc \ src/GPS/GPSProvider.cc \ - src/GPS/RTCM/RTCMMavlink.cc \ + src/GPS/RTCMMavlink.cc \ src/Joystick/JoystickSDL.cc \ src/RunGuard.cc \ } diff --git a/src/GPS/CMakeLists.txt b/src/GPS/CMakeLists.txt index 4ff486868c9..277098800a6 100644 --- a/src/GPS/CMakeLists.txt +++ b/src/GPS/CMakeLists.txt @@ -19,8 +19,8 @@ qt_add_library(gps STATIC GPSPositionMessage.h GPSProvider.cc GPSProvider.h - RTCM/RTCMMavlink.cc - RTCM/RTCMMavlink.h + RTCMMavlink.cc + RTCMMavlink.h satellite_info.h sensor_gnss_relative.h sensor_gps.h @@ -37,5 +37,4 @@ target_include_directories(gps PUBLIC ${CMAKE_CURRENT_SOURCE_DIR} Drivers/src - RTCM ) diff --git a/src/GPS/GPSManager.cc b/src/GPS/GPSManager.cc index 1693a4a92b5..e57e601ea07 100644 --- a/src/GPS/GPSManager.cc +++ b/src/GPS/GPSManager.cc @@ -24,6 +24,47 @@ GPSManager::GPSManager(QGCApplication* app, QGCToolbox* toolbox) GPSManager::~GPSManager() { disconnectGPS(); + + delete _gpsRtkFactGroup; + _gpsRtkFactGroup = nullptr; +} + +void GPSManager::setToolbox(QGCToolbox *toolbox) +{ + QGCTool::setToolbox(toolbox); + + _gpsRtkFactGroup = new GPSRTKFactGroup(this); + + connect(this, &GPSManager::onConnect, this, &GPSManager::_onGPSConnect); + connect(this, &GPSManager::onDisconnect, this, &GPSManager::_onGPSDisconnect); + connect(this, &GPSManager::surveyInStatus, this, &GPSManager::_gpsSurveyInStatus); + connect(this, &GPSManager::satelliteUpdate, this, &GPSManager::_gpsNumSatellites); +} + +void GPSManager::_onGPSConnect() +{ + _gpsRtkFactGroup->connected()->setRawValue(true); +} + +void GPSManager::_onGPSDisconnect() +{ + _gpsRtkFactGroup->connected()->setRawValue(false); +} + +void GPSManager::_gpsSurveyInStatus(float duration, float accuracyMM, double latitude, double longitude, float altitude, bool valid, bool active) +{ + _gpsRtkFactGroup->currentDuration()->setRawValue(duration); + _gpsRtkFactGroup->currentAccuracy()->setRawValue(static_cast(accuracyMM) / 1000.0); + _gpsRtkFactGroup->currentLatitude()->setRawValue(latitude); + _gpsRtkFactGroup->currentLongitude()->setRawValue(longitude); + _gpsRtkFactGroup->currentAltitude()->setRawValue(altitude); + _gpsRtkFactGroup->valid()->setRawValue(valid); + _gpsRtkFactGroup->active()->setRawValue(active); +} + +void GPSManager::_gpsNumSatellites(int numSatellites) +{ + _gpsRtkFactGroup->numSatellites()->setRawValue(numSatellites); } void GPSManager::connectGPS(const QString& device, const QString& gps_type) @@ -88,7 +129,6 @@ void GPSManager::disconnectGPS(void) _rtcmMavlink = nullptr; } - void GPSManager::GPSPositionUpdate(GPSPositionMessage msg) { qCDebug(RTKGPSLog) << QString("GPS: got position update: alt=%1, long=%2, lat=%3").arg(msg.position_data.altitude_msl_m).arg(msg.position_data.longitude_deg).arg(msg.position_data.latitude_deg); diff --git a/src/GPS/GPSManager.h b/src/GPS/GPSManager.h index eb2264255a3..07233abb4b7 100644 --- a/src/GPS/GPSManager.h +++ b/src/GPS/GPSManager.h @@ -11,7 +11,8 @@ #pragma once #include "GPSProvider.h" -#include "RTCM/RTCMMavlink.h" +#include "RTCMMavlink.h" +#include "GPSRTKFactGroup.h" #include #include @@ -28,9 +29,12 @@ class GPSManager : public QGCTool GPSManager(QGCApplication* app, QGCToolbox* toolbox); ~GPSManager(); + void setToolbox(QGCToolbox* toolbox) override; + void connectGPS (const QString& device, const QString& gps_type); void disconnectGPS (void); bool connected (void) const { return _gpsProvider && _gpsProvider->isRunning(); } + FactGroup* gpsRtkFactGroup(void) { return _gpsRtkFactGroup; } signals: void onConnect(); @@ -41,10 +45,15 @@ class GPSManager : public QGCTool private slots: void GPSPositionUpdate(GPSPositionMessage msg); void GPSSatelliteUpdate(GPSSatelliteMessage msg); + void _onGPSConnect(void); + void _onGPSDisconnect(void); + void _gpsSurveyInStatus(float duration, float accuracyMM, double latitude, double longitude, float altitude, bool valid, bool active); + void _gpsNumSatellites(int numSatellites); private: GPSProvider* _gpsProvider = nullptr; RTCMMavlink* _rtcmMavlink = nullptr; + GPSRTKFactGroup* _gpsRtkFactGroup = nullptr; std::atomic_bool _requestGpsStop; ///< signals the thread to quit }; diff --git a/src/GPS/RTCM/RTCMMavlink.cc b/src/GPS/RTCMMavlink.cc similarity index 100% rename from src/GPS/RTCM/RTCMMavlink.cc rename to src/GPS/RTCMMavlink.cc diff --git a/src/GPS/RTCM/RTCMMavlink.h b/src/GPS/RTCMMavlink.h similarity index 100% rename from src/GPS/RTCM/RTCMMavlink.h rename to src/GPS/RTCMMavlink.h diff --git a/src/QGCApplication.cc b/src/QGCApplication.cc index f885b9f778f..968a6d64691 100644 --- a/src/QGCApplication.cc +++ b/src/QGCApplication.cc @@ -120,10 +120,6 @@ #include "SerialLink.h" #endif -#ifndef __mobile__ -#include "GPS/GPSManager.h" -#endif - #ifdef QGC_RTLAB_ENABLED #include "OpalLink.h" #endif @@ -337,17 +333,6 @@ QGCApplication::QGCApplication(int &argc, char* argv[], bool unitTesting) _toolbox = new QGCToolbox(this); _toolbox->setChildToolboxes(); -#ifndef __mobile__ - _gpsRtkFactGroup = new GPSRTKFactGroup(this); - GPSManager *gpsManager = _toolbox->gpsManager(); - if (gpsManager) { - connect(gpsManager, &GPSManager::onConnect, this, &QGCApplication::_onGPSConnect); - connect(gpsManager, &GPSManager::onDisconnect, this, &QGCApplication::_onGPSDisconnect); - connect(gpsManager, &GPSManager::surveyInStatus, this, &QGCApplication::_gpsSurveyInStatus); - connect(gpsManager, &GPSManager::satelliteUpdate, this, &QGCApplication::_gpsNumSatellites); - } -#endif /* __mobile__ */ - _checkForNewVersion(); } @@ -413,7 +398,6 @@ void QGCApplication::_shutdown() // Close out all Qml before we delete toolbox. This way we don't get all sorts of null reference complaints from Qml. delete _qmlAppEngine; delete _toolbox; - delete _gpsRtkFactGroup; } QGCApplication::~QGCApplication() @@ -891,33 +875,6 @@ bool QGCApplication::_parseVersionText(const QString& versionString, int& majorV return false; } - -void QGCApplication::_onGPSConnect() -{ - _gpsRtkFactGroup->connected()->setRawValue(true); -} - -void QGCApplication::_onGPSDisconnect() -{ - _gpsRtkFactGroup->connected()->setRawValue(false); -} - -void QGCApplication::_gpsSurveyInStatus(float duration, float accuracyMM, double latitude, double longitude, float altitude, bool valid, bool active) -{ - _gpsRtkFactGroup->currentDuration()->setRawValue(duration); - _gpsRtkFactGroup->currentAccuracy()->setRawValue(static_cast(accuracyMM) / 1000.0); - _gpsRtkFactGroup->currentLatitude()->setRawValue(latitude); - _gpsRtkFactGroup->currentLongitude()->setRawValue(longitude); - _gpsRtkFactGroup->currentAltitude()->setRawValue(altitude); - _gpsRtkFactGroup->valid()->setRawValue(valid); - _gpsRtkFactGroup->active()->setRawValue(active); -} - -void QGCApplication::_gpsNumSatellites(int numSatellites) -{ - _gpsRtkFactGroup->numSatellites()->setRawValue(numSatellites); -} - QString QGCApplication::cachedParameterMetaDataFile(void) { QSettings settings; diff --git a/src/QGCApplication.h b/src/QGCApplication.h index 79c31be7c96..b15e63706f3 100644 --- a/src/QGCApplication.h +++ b/src/QGCApplication.h @@ -31,7 +31,6 @@ #include "AudioOutput.h" #include "UASMessageHandler.h" #include "FactSystem.h" -#include "GPSRTKFactGroup.h" #ifdef QGC_RTLAB_ENABLED #include "OpalLink.h" @@ -89,8 +88,6 @@ class QGCApplication : public QApplication /// Is Internet available? bool isInternetAvailable(); - FactGroup* gpsRtkFactGroup(void) { return _gpsRtkFactGroup; } - QTranslator& qgcJSONTranslator(void) { return _qgcTranslatorJSON; } void setLanguage(); @@ -180,10 +177,6 @@ private slots: void _missingParamsDisplay (void); void _qgcCurrentStableVersionDownloadComplete (QString remoteFile, QString localFile, QString errorMsg); bool _parseVersionText (const QString& versionString, int& majorVersion, int& minorVersion, int& buildVersion); - void _onGPSConnect (void); - void _onGPSDisconnect (void); - void _gpsSurveyInStatus (float duration, float accuracyMM, double latitude, double longitude, float altitude, bool valid, bool active); - void _gpsNumSatellites (int numSatellites); void _showDelayedAppMessages (void); private: @@ -206,7 +199,6 @@ private slots: int _majorVersion = 0; int _minorVersion = 0; int _buildVersion = 0; - GPSRTKFactGroup* _gpsRtkFactGroup = nullptr; QGCToolbox* _toolbox = nullptr; QQuickWindow* _mainRootWindow = nullptr; bool _bluetoothAvailable = false; diff --git a/src/QmlControls/QGroundControlQmlGlobal.cc b/src/QmlControls/QGroundControlQmlGlobal.cc index 6ae12094d5a..b1431d9862d 100644 --- a/src/QmlControls/QGroundControlQmlGlobal.cc +++ b/src/QmlControls/QGroundControlQmlGlobal.cc @@ -9,7 +9,9 @@ #include "QGroundControlQmlGlobal.h" #include "LinkManager.h" - +#ifndef __mobile__ +#include "GPSManager.h" +#endif #include #include #include @@ -79,7 +81,9 @@ void QGroundControlQmlGlobal::setToolbox(QGCToolbox* toolbox) _corePlugin = toolbox->corePlugin(); _firmwarePluginManager = toolbox->firmwarePluginManager(); _settingsManager = toolbox->settingsManager(); - _gpsRtkFactGroup = qgcApp()->gpsRtkFactGroup(); +#ifndef __mobile__ + _gpsRtkFactGroup = toolbox->gpsManager()->gpsRtkFactGroup(); +#endif _adsbVehicleManager = toolbox->adsbVehicleManager(); _globalPalette = new QGCPalette(this); #ifndef QGC_AIRLINK_DISABLED