Commit e07b730b authored by Don Gagne's avatar Don Gagne

parent 9a49a206
...@@ -46,12 +46,12 @@ linux { ...@@ -46,12 +46,12 @@ linux {
error("Unsuported Linux toolchain, only GCC 32- or 64-bit is supported") error("Unsuported Linux toolchain, only GCC 32- or 64-bit is supported")
} }
} else : win32 { } else : win32 {
win32-msvc2010 | win32-msvc2012 | win32-msvc2013 | win32-msvc2015 { win32-msvc2015 {
message("Windows build") message("Windows build")
CONFIG += WindowsBuild CONFIG += WindowsBuild
DEFINES += __STDC_LIMIT_MACROS DEFINES += __STDC_LIMIT_MACROS
} else { } else {
error("Unsupported Windows toolchain, only Visual Studio 2010, 2012, and 2013 are supported") error("Unsupported Windows toolchain, only Visual Studio 2015 is supported")
} }
} else : macx { } else : macx {
macx-clang | macx-llvm { macx-clang | macx-llvm {
......
Subproject commit e84bb0a7a702320fedade6c83bbdf2324e3be8fb Subproject commit 8828fb9ad3a2cad568feac2b46de7d6d3af32ca8
...@@ -41,7 +41,17 @@ void GPSManager::connectGPS(const QString& device, const QString& gps_type) ...@@ -41,7 +41,17 @@ void GPSManager::connectGPS(const QString& device, const QString& gps_type)
disconnectGPS(); disconnectGPS();
_requestGpsStop = false; _requestGpsStop = false;
_gpsProvider = new GPSProvider(device, type, true, rtkSettings->surveyInAccuracyLimit()->rawValue().toDouble(), rtkSettings->surveyInMinObservationDuration()->rawValue().toInt(), _requestGpsStop); _gpsProvider = new GPSProvider(device,
type,
true, /* enableSatInfo */
rtkSettings->surveyInAccuracyLimit()->rawValue().toDouble(),
rtkSettings->surveyInMinObservationDuration()->rawValue().toInt(),
rtkSettings->useFixedBasePosition()->rawValue().toBool(),
rtkSettings->fixedBasePositionLatitude()->rawValue().toDouble(),
rtkSettings->fixedBasePositionLongitude()->rawValue().toDouble(),
rtkSettings->fixedBasePositionAltitude()->rawValue().toFloat(),
rtkSettings->fixedBasePositionAccuracy()->rawValue().toFloat(),
_requestGpsStop);
_gpsProvider->start(); _gpsProvider->start();
//create RTCM device //create RTCM device
...@@ -50,10 +60,10 @@ void GPSManager::connectGPS(const QString& device, const QString& gps_type) ...@@ -50,10 +60,10 @@ void GPSManager::connectGPS(const QString& device, const QString& gps_type)
connect(_gpsProvider, &GPSProvider::RTCMDataUpdate, _rtcmMavlink, &RTCMMavlink::RTCMDataUpdate); connect(_gpsProvider, &GPSProvider::RTCMDataUpdate, _rtcmMavlink, &RTCMMavlink::RTCMDataUpdate);
//test: connect to position update //test: connect to position update
connect(_gpsProvider, &GPSProvider::positionUpdate, this, &GPSManager::GPSPositionUpdate); connect(_gpsProvider, &GPSProvider::positionUpdate, this, &GPSManager::GPSPositionUpdate);
connect(_gpsProvider, &GPSProvider::satelliteInfoUpdate, this, &GPSManager::GPSSatelliteUpdate); connect(_gpsProvider, &GPSProvider::satelliteInfoUpdate, this, &GPSManager::GPSSatelliteUpdate);
connect(_gpsProvider, &GPSProvider::finished, this, &GPSManager::onDisconnect); connect(_gpsProvider, &GPSProvider::finished, this, &GPSManager::onDisconnect);
connect(_gpsProvider, &GPSProvider::surveyInStatus, this, &GPSManager::surveyInStatus); connect(_gpsProvider, &GPSProvider::surveyInStatus, this, &GPSManager::surveyInStatus);
emit onConnect(); emit onConnect();
} }
......
...@@ -35,7 +35,7 @@ public: ...@@ -35,7 +35,7 @@ public:
signals: signals:
void onConnect(); void onConnect();
void onDisconnect(); void onDisconnect();
void surveyInStatus(float duration, float accuracyMM, bool valid, bool active); void surveyInStatus(float duration, float accuracyMM, double latitude, double longitude, float altitude, bool valid, bool active);
void satelliteUpdate(int numSats); void satelliteUpdate(int numSats);
private slots: private slots:
......
...@@ -10,6 +10,8 @@ ...@@ -10,6 +10,8 @@
#include "GPSProvider.h" #include "GPSProvider.h"
#include "QGCLoggingCategory.h" #include "QGCLoggingCategory.h"
#include "QGCApplication.h"
#include "SettingsManager.h"
#define GPS_RECEIVE_TIMEOUT 1200 #define GPS_RECEIVE_TIMEOUT 1200
...@@ -17,7 +19,7 @@ ...@@ -17,7 +19,7 @@
#include "Drivers/src/ubx.h" #include "Drivers/src/ubx.h"
#include "Drivers/src/ashtech.h" #include "Drivers/src/ashtech.h"
#include "Drivers/src/gps_helper.h" #include "Drivers/src/base_station.h"
#include "definitions.h" #include "definitions.h"
//#define SIMULATE_RTCM_OUTPUT //if defined, generate simulated RTCM messages //#define SIMULATE_RTCM_OUTPUT //if defined, generate simulated RTCM messages
...@@ -44,8 +46,21 @@ void GPSProvider::run() ...@@ -44,8 +46,21 @@ void GPSProvider::run()
_serial = new QSerialPort(); _serial = new QSerialPort();
_serial->setPortName(_device); _serial->setPortName(_device);
if (!_serial->open(QIODevice::ReadWrite)) { if (!_serial->open(QIODevice::ReadWrite)) {
qWarning() << "GPS: Failed to open Serial Device" << _device; int retries = 60;
return; // Give the device some time to come up. In some cases the device is not
// immediately accessible right after startup for some reason. This can take 10-20s.
while (retries-- > 0 && _serial->error() == QSerialPort::PermissionError) {
qCDebug(RTKGPSLog) << "Cannot open device... retrying";
msleep(500);
if (_serial->open(QIODevice::ReadWrite)) {
_serial->clearError();
break;
}
}
if (_serial->error() != QSerialPort::NoError) {
qWarning() << "GPS: Failed to open Serial Device" << _device << _serial->errorString();
return;
}
} }
_serial->setBaudRate(QSerialPort::Baud9600); _serial->setBaudRate(QSerialPort::Baud9600);
_serial->setDataBits(QSerialPort::Data8); _serial->setDataBits(QSerialPort::Data8);
...@@ -54,7 +69,7 @@ void GPSProvider::run() ...@@ -54,7 +69,7 @@ void GPSProvider::run()
_serial->setFlowControl(QSerialPort::NoFlowControl); _serial->setFlowControl(QSerialPort::NoFlowControl);
unsigned int baudrate; unsigned int baudrate;
GPSHelper* gpsDriver = nullptr; GPSBaseStationSupport* gpsDriver = nullptr;
while (!_requestStop) { while (!_requestStop) {
...@@ -70,7 +85,11 @@ void GPSProvider::run() ...@@ -70,7 +85,11 @@ void GPSProvider::run()
gpsDriver = new GPSDriverUBX(GPSDriverUBX::Interface::UART, &callbackEntry, this, &_reportGpsPos, _pReportSatInfo); gpsDriver = new GPSDriverUBX(GPSDriverUBX::Interface::UART, &callbackEntry, this, &_reportGpsPos, _pReportSatInfo);
baudrate = 0; // auto-configure baudrate = 0; // auto-configure
} }
gpsDriver->setSurveyInSpecs(_surveyInAccMeters * 10000, _surveryInDurationSecs); gpsDriver->setSurveyInSpecs(_surveyInAccMeters * 10000.0f, _surveryInDurationSecs);
if (_useFixedBaseLoction) {
gpsDriver->setBasePosition(_fixedBaseLatitude, _fixedBaseLongitude, _fixedBaseAltitudeMeters * 10000.0f, _fixedBaseAccuracyMeters * 10000.0f);
}
if (gpsDriver->configure(baudrate, GPSDriverUBX::OutputMode::RTCM) == 0) { if (gpsDriver->configure(baudrate, GPSDriverUBX::OutputMode::RTCM) == 0) {
...@@ -108,12 +127,27 @@ void GPSProvider::run() ...@@ -108,12 +127,27 @@ void GPSProvider::run()
qCDebug(RTKGPSLog) << "Exiting GPS thread"; qCDebug(RTKGPSLog) << "Exiting GPS thread";
} }
GPSProvider::GPSProvider(const QString& device, GPSType type, bool enableSatInfo, double surveyInAccMeters, int surveryInDurationSecs, const std::atomic_bool& requestStop) GPSProvider::GPSProvider(const QString& device,
: _device(device) GPSType type,
, _type(type) bool enableSatInfo,
, _requestStop(requestStop) double surveyInAccMeters,
, _surveyInAccMeters(surveyInAccMeters) int surveryInDurationSecs,
, _surveryInDurationSecs(surveryInDurationSecs) bool useFixedBaseLocation,
double fixedBaseLatitude,
double fixedBaseLongitude,
float fixedBaseAltitudeMeters,
float fixedBaseAccuracyMeters,
const std::atomic_bool& requestStop)
: _device (device)
, _type (type)
, _requestStop (requestStop)
, _surveyInAccMeters (surveyInAccMeters)
, _surveryInDurationSecs (surveryInDurationSecs)
, _useFixedBaseLoction (useFixedBaseLocation)
, _fixedBaseLatitude (fixedBaseLatitude)
, _fixedBaseLongitude (fixedBaseLongitude)
, _fixedBaseAltitudeMeters (fixedBaseAltitudeMeters)
, _fixedBaseAccuracyMeters (fixedBaseAccuracyMeters)
{ {
qCDebug(RTKGPSLog) << "Survey in accuracy:duration" << surveyInAccMeters << surveryInDurationSecs; qCDebug(RTKGPSLog) << "Survey in accuracy:duration" << surveyInAccMeters << surveryInDurationSecs;
if (enableSatInfo) _pReportSatInfo = new satellite_info_s(); if (enableSatInfo) _pReportSatInfo = new satellite_info_s();
...@@ -179,8 +213,10 @@ int GPSProvider::callback(GPSCallbackType type, void *data1, int data2) ...@@ -179,8 +213,10 @@ int GPSProvider::callback(GPSCallbackType type, void *data1, int data2)
case GPSCallbackType::surveyInStatus: case GPSCallbackType::surveyInStatus:
{ {
SurveyInStatus* status = (SurveyInStatus*)data1; SurveyInStatus* status = (SurveyInStatus*)data1;
qCDebug(RTKGPSLog) << "Position: " << status->latitude << status->longitude << status->altitude;
qCDebug(RTKGPSLog) << QString("Survey-in status: %1s cur accuracy: %2mm valid: %3 active: %4").arg(status->duration).arg(status->mean_accuracy).arg((int)(status->flags & 1)).arg((int)((status->flags>>1) & 1)); qCDebug(RTKGPSLog) << QString("Survey-in status: %1s cur accuracy: %2mm valid: %3 active: %4").arg(status->duration).arg(status->mean_accuracy).arg((int)(status->flags & 1)).arg((int)((status->flags>>1) & 1));
emit surveyInStatus(status->duration, status->mean_accuracy, (int)(status->flags & 1), (int)((status->flags>>1) & 1)); emit surveyInStatus(status->duration, status->mean_accuracy, status->latitude, status->longitude, status->altitude, (int)(status->flags & 1), (int)((status->flags>>1) & 1));
} }
break; break;
......
...@@ -35,19 +35,29 @@ public: ...@@ -35,19 +35,29 @@ public:
trimble trimble
}; };
GPSProvider(const QString& device, GPSType type, bool enableSatInfo, double surveyInAccMeters, int surveryInDurationSecs, GPSProvider(const QString& device,
const std::atomic_bool& requestStop); GPSType type,
bool enableSatInfo,
double surveyInAccMeters,
int surveryInDurationSecs,
bool useFixedBaseLocation,
double fixedBaseLatitude,
double fixedBaseLongitude,
float fixedBaseAltitudeMeters,
float fixedBaseAccuracyMeters,
const std::atomic_bool& requestStop);
~GPSProvider(); ~GPSProvider();
/** /**
* this is called by the callback method * this is called by the callback method
*/ */
void gotRTCMData(uint8_t *data, size_t len); void gotRTCMData(uint8_t *data, size_t len);
signals: signals:
void positionUpdate(GPSPositionMessage message); void positionUpdate(GPSPositionMessage message);
void satelliteInfoUpdate(GPSSatelliteMessage message); void satelliteInfoUpdate(GPSSatelliteMessage message);
void RTCMDataUpdate(QByteArray message); void RTCMDataUpdate(QByteArray message);
void surveyInStatus(float duration, float accuracyMM, bool valid, bool active); void surveyInStatus(float duration, float accuracyMM, double latitude, double longitude, float altitude, bool valid, bool active);
protected: protected:
void run(); void run();
...@@ -68,6 +78,11 @@ private: ...@@ -68,6 +78,11 @@ private:
const std::atomic_bool& _requestStop; const std::atomic_bool& _requestStop;
double _surveyInAccMeters; double _surveyInAccMeters;
int _surveryInDurationSecs; int _surveryInDurationSecs;
bool _useFixedBaseLoction;
double _fixedBaseLatitude;
double _fixedBaseLongitude;
float _fixedBaseAltitudeMeters;
float _fixedBaseAccuracyMeters;
struct vehicle_gps_position_s _reportGpsPos; struct vehicle_gps_position_s _reportGpsPos;
struct satellite_info_s *_pReportSatInfo = nullptr; struct satellite_info_s *_pReportSatInfo = nullptr;
......
...@@ -101,6 +101,7 @@ ...@@ -101,6 +101,7 @@
#include "MainWindow.h" #include "MainWindow.h"
#include "GeoTagController.h" #include "GeoTagController.h"
#include "MavlinkConsoleController.h" #include "MavlinkConsoleController.h"
#include "GPS/GPSManager.h"
#endif #endif
#ifdef QGC_RTLAB_ENABLED #ifdef QGC_RTLAB_ENABLED
...@@ -164,6 +165,7 @@ QGCApplication::QGCApplication(int &argc, char* argv[], bool unitTesting) ...@@ -164,6 +165,7 @@ QGCApplication::QGCApplication(int &argc, char* argv[], bool unitTesting)
, _minorVersion (0) , _minorVersion (0)
, _buildVersion (0) , _buildVersion (0)
, _currentVersionDownload (nullptr) , _currentVersionDownload (nullptr)
, _gpsRtkFactGroup (nullptr)
, _toolbox (nullptr) , _toolbox (nullptr)
, _bluetoothAvailable (false) , _bluetoothAvailable (false)
{ {
...@@ -197,7 +199,7 @@ QGCApplication::QGCApplication(int &argc, char* argv[], bool unitTesting) ...@@ -197,7 +199,7 @@ QGCApplication::QGCApplication(int &argc, char* argv[], bool unitTesting)
QMessageBox msgBox; QMessageBox msgBox;
msgBox.setInformativeText(tr("You are running %1 as root. " msgBox.setInformativeText(tr("You are running %1 as root. "
"You should not do this since it will cause other issues with %1. " "You should not do this since it will cause other issues with %1. "
"%1 will now exit. " "%1 will now exiQGroundControl.gpsRtkt. "
"If you are having serial port issues on Ubuntu, execute the following commands to fix most issues:\n" "If you are having serial port issues on Ubuntu, execute the following commands to fix most issues:\n"
"sudo usermod -a -G dialout $USER\n" "sudo usermod -a -G dialout $USER\n"
"sudo apt-get remove modemmanager").arg(qgcApp()->applicationName())); "sudo apt-get remove modemmanager").arg(qgcApp()->applicationName()));
...@@ -337,6 +339,17 @@ QGCApplication::QGCApplication(int &argc, char* argv[], bool unitTesting) ...@@ -337,6 +339,17 @@ QGCApplication::QGCApplication(int &argc, char* argv[], bool unitTesting)
_toolbox = new QGCToolbox(this); _toolbox = new QGCToolbox(this);
_toolbox->setChildToolboxes(); _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(); _checkForNewVersion();
} }
...@@ -775,3 +788,31 @@ bool QGCApplication::_parseVersionText(const QString& versionString, int& majorV ...@@ -775,3 +788,31 @@ bool QGCApplication::_parseVersionText(const QString& versionString, int& majorV
return false; 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(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);
}
...@@ -33,6 +33,7 @@ ...@@ -33,6 +33,7 @@
#include "AudioOutput.h" #include "AudioOutput.h"
#include "UASMessageHandler.h" #include "UASMessageHandler.h"
#include "FactSystem.h" #include "FactSystem.h"
#include "GPSRTKFactGroup.h"
#ifdef QGC_RTLAB_ENABLED #ifdef QGC_RTLAB_ENABLED
#include "OpalLink.h" #include "OpalLink.h"
...@@ -95,6 +96,8 @@ public: ...@@ -95,6 +96,8 @@ public:
/// Is Internet available? /// Is Internet available?
bool isInternetAvailable(); bool isInternetAvailable();
FactGroup* gpsRtkFactGroup(void) { return _gpsRtkFactGroup; }
public slots: public slots:
/// You can connect to this slot to show an information message box from a different thread. /// You can connect to this slot to show an information message box from a different thread.
void informationMessageBoxOnMainThread(const QString& title, const QString& msg); void informationMessageBoxOnMainThread(const QString& title, const QString& msg);
...@@ -152,6 +155,10 @@ private slots: ...@@ -152,6 +155,10 @@ private slots:
void _currentVersionDownloadFinished(QString remoteFile, QString localFile); void _currentVersionDownloadFinished(QString remoteFile, QString localFile);
void _currentVersionDownloadError(QString errorMsg); void _currentVersionDownloadError(QString errorMsg);
bool _parseVersionText(const QString& versionString, int& majorVersion, int& minorVersion, int& buildVersion); bool _parseVersionText(const QString& versionString, int& majorVersion, int& minorVersion, int& buildVersion);
void _onGPSConnect();
void _onGPSDisconnect();
void _gpsSurveyInStatus(float duration, float accuracyMM, double latitude, double longitude, float altitude, bool valid, bool active);
void _gpsNumSatellites(int numSatellites);
private: private:
QObject* _rootQmlObject(void); QObject* _rootQmlObject(void);
...@@ -175,6 +182,7 @@ private: ...@@ -175,6 +182,7 @@ private:
int _minorVersion; int _minorVersion;
int _buildVersion; int _buildVersion;
QGCFileDownload* _currentVersionDownload; QGCFileDownload* _currentVersionDownload;
GPSRTKFactGroup* _gpsRtkFactGroup;
QGCToolbox* _toolbox; QGCToolbox* _toolbox;
......
...@@ -226,8 +226,13 @@ QGCViewDialog { ...@@ -226,8 +226,13 @@ QGCViewDialog {
} }
QGCLabel { QGCLabel {
visible: fact.rebootRequired visible: fact.vehicleRebootRequired
text: "Reboot required after change" text: "Vehicle reboot required after change"
}
QGCLabel {
visible: fact.qgcRebootRequired
text: "Appliction restart required after change"
} }
QGCLabel { QGCLabel {
......
...@@ -28,20 +28,21 @@ QGeoCoordinate QGroundControlQmlGlobal::_coord = QGeoCoordinate(0.0,0.0); ...@@ -28,20 +28,21 @@ QGeoCoordinate QGroundControlQmlGlobal::_coord = QGeoCoordinate(0.0,0.0);
double QGroundControlQmlGlobal::_zoom = 2; double QGroundControlQmlGlobal::_zoom = 2;
QGroundControlQmlGlobal::QGroundControlQmlGlobal(QGCApplication* app, QGCToolbox* toolbox) QGroundControlQmlGlobal::QGroundControlQmlGlobal(QGCApplication* app, QGCToolbox* toolbox)
: QGCTool(app, toolbox) : QGCTool (app, toolbox)
, _flightMapInitialZoom(17.0) , _flightMapInitialZoom (17.0)
, _linkManager(NULL) , _linkManager (NULL)
, _multiVehicleManager(NULL) , _multiVehicleManager (NULL)
, _mapEngineManager(NULL) , _mapEngineManager (NULL)
, _qgcPositionManager(NULL) , _qgcPositionManager (NULL)
, _missionCommandTree(NULL) , _missionCommandTree (NULL)
, _videoManager(NULL) , _videoManager (NULL)
, _mavlinkLogManager(NULL) , _mavlinkLogManager (NULL)
, _corePlugin(NULL) , _corePlugin (NULL)
, _firmwarePluginManager(NULL) , _firmwarePluginManager(NULL)
, _settingsManager(NULL) , _settingsManager (NULL)
, _airspaceManager(NULL) , _gpsRtkFactGroup (nullptr)
, _skipSetupPage(false) , _airspaceManager (NULL)
, _skipSetupPage (false)
{ {
// We clear the parent on this object since we run into shutdown problems caused by hybrid qml app. Instead we let it leak on shutdown. // We clear the parent on this object since we run into shutdown problems caused by hybrid qml app. Instead we let it leak on shutdown.
setParent(NULL); setParent(NULL);
...@@ -77,17 +78,8 @@ void QGroundControlQmlGlobal::setToolbox(QGCToolbox* toolbox) ...@@ -77,17 +78,8 @@ void QGroundControlQmlGlobal::setToolbox(QGCToolbox* toolbox)
_corePlugin = toolbox->corePlugin(); _corePlugin = toolbox->corePlugin();
_firmwarePluginManager = toolbox->firmwarePluginManager(); _firmwarePluginManager = toolbox->firmwarePluginManager();
_settingsManager = toolbox->settingsManager(); _settingsManager = toolbox->settingsManager();
_gpsRtkFactGroup = qgcApp()->gpsRtkFactGroup();
_airspaceManager = toolbox->airspaceManager(); _airspaceManager = toolbox->airspaceManager();
#ifndef __mobile__
GPSManager *gpsManager = toolbox->gpsManager();
if (gpsManager) {
connect(gpsManager, &GPSManager::onConnect, this, &QGroundControlQmlGlobal::_onGPSConnect);
connect(gpsManager, &GPSManager::onDisconnect, this, &QGroundControlQmlGlobal::_onGPSDisconnect);
connect(gpsManager, &GPSManager::surveyInStatus, this, &QGroundControlQmlGlobal::_GPSSurveyInStatus);
connect(gpsManager, &GPSManager::satelliteUpdate, this, &QGroundControlQmlGlobal::_GPSNumSatellites);
}
#endif /* __mobile__ */
} }
void QGroundControlQmlGlobal::saveGlobalSetting (const QString& key, const QString& value) void QGroundControlQmlGlobal::saveGlobalSetting (const QString& key, const QString& value)
...@@ -231,24 +223,3 @@ void QGroundControlQmlGlobal::setFlightMapZoom(double zoom) ...@@ -231,24 +223,3 @@ void QGroundControlQmlGlobal::setFlightMapZoom(double zoom)
emit flightMapZoomChanged(zoom); emit flightMapZoomChanged(zoom);
} }
} }
void QGroundControlQmlGlobal::_onGPSConnect()
{
_gpsRtkFactGroup.connected()->setRawValue(true);
}
void QGroundControlQmlGlobal::_onGPSDisconnect()
{
_gpsRtkFactGroup.connected()->setRawValue(false);
}
void QGroundControlQmlGlobal::_GPSSurveyInStatus(float duration, float accuracyMM, bool valid, bool active)
{
_gpsRtkFactGroup.currentDuration()->setRawValue(duration);
_gpsRtkFactGroup.currentAccuracy()->setRawValue(accuracyMM/1000.0);
_gpsRtkFactGroup.valid()->setRawValue(valid);
_gpsRtkFactGroup.active()->setRawValue(active);
}
void QGroundControlQmlGlobal::_GPSNumSatellites(int numSatellites)
{
_gpsRtkFactGroup.numSatellites()->setRawValue(numSatellites);
}
...@@ -23,10 +23,6 @@ ...@@ -23,10 +23,6 @@
#include "QGCLoggingCategory.h" #include "QGCLoggingCategory.h"
#include "AppSettings.h" #include "AppSettings.h"
#include "AirspaceManager.h" #include "AirspaceManager.h"
#ifndef __mobile__
#include "GPS/GPSManager.h"
#endif /* __mobile__ */
#include "GPSRTKFactGroup.h"
#ifdef QT_DEBUG #ifdef QT_DEBUG
#include "MockLink.h" #include "MockLink.h"
...@@ -144,7 +140,7 @@ public: ...@@ -144,7 +140,7 @@ public:
MAVLinkLogManager* mavlinkLogManager () { return _mavlinkLogManager; } MAVLinkLogManager* mavlinkLogManager () { return _mavlinkLogManager; }
QGCCorePlugin* corePlugin () { return _corePlugin; } QGCCorePlugin* corePlugin () { return _corePlugin; }
SettingsManager* settingsManager () { return _settingsManager; } SettingsManager* settingsManager () { return _settingsManager; }
FactGroup* gpsRtkFactGroup () { return &_gpsRtkFactGroup; } FactGroup* gpsRtkFactGroup () { return _gpsRtkFactGroup; }
AirspaceManager* airspaceManager () { return _airspaceManager; } AirspaceManager* airspaceManager () { return _airspaceManager; }
static QGeoCoordinate flightMapPosition () { return _coord; } static QGeoCoordinate flightMapPosition () { return _coord; }
static double flightMapZoom () { return _zoom; } static double flightMapZoom () { return _zoom; }
...@@ -192,12 +188,6 @@ signals: ...@@ -192,12 +188,6 @@ signals:
void flightMapZoomChanged (double flightMapZoom); void flightMapZoomChanged (double flightMapZoom);
void skipSetupPageChanged (); void skipSetupPageChanged ();
private slots:
void _onGPSConnect();
void _onGPSDisconnect();
void _GPSSurveyInStatus(float duration, float accuracyMM, bool valid, bool active);
void _GPSNumSatellites(int numSatellites);
private: private:
double _flightMapInitialZoom; double _flightMapInitialZoom;
LinkManager* _linkManager; LinkManager* _linkManager;
...@@ -210,7 +200,7 @@ private: ...@@ -210,7 +200,7 @@ private:
QGCCorePlugin* _corePlugin; QGCCorePlugin* _corePlugin;
FirmwarePluginManager* _firmwarePluginManager; FirmwarePluginManager* _firmwarePluginManager;
SettingsManager* _settingsManager; SettingsManager* _settingsManager;
GPSRTKFactGroup _gpsRtkFactGroup; FactGroup* _gpsRtkFactGroup;
AirspaceManager* _airspaceManager; AirspaceManager* _airspaceManager;
bool _skipSetupPage; bool _skipSetupPage;
......
...@@ -20,5 +20,55 @@ ...@@ -20,5 +20,55 @@
"units": "secs", "units": "secs",
"decimalPlaces": 0, "decimalPlaces": 0,
"qgcRebootRequired": true "qgcRebootRequired": true
},
{
"name": "UseFixedBasePosition",
"shortDescription": "Use specified base position",
"longDescription": "Specify the values for the RTK base position without having to do a survey in.",
"type": "bool",
"defaultValue": false,
"qgcRebootRequired": true
},
{
"name": "FixedBasePositionLatitude",
"shortDescription": "Base Position Latitude",
"longDescription": "Defines the latitude of the fixed RTK base position.",
"type": "double",
"defaultValue": 0,
"min": -90,
"max": 90,
"decimalPlaces": 7,
"qgcRebootRequired": true
},
{
"name": "FixedBasePositionLongitude",
"shortDescription": "Base Position Longitude",
"longDescription": "Defines the longitude of the fixed RTK base position.",
"type": "double",
"defaultValue": 0,
"min": -180,
"max": 180,
"decimalPlaces": 7,
"qgcRebootRequired": true
},
{
"name": "FixedBasePositionAltitude",
"shortDescription": "Base Position Altitude",
"longDescription": "Defines the altitude of the fixed RTK base position.",
"type": "float",
"defaultValue": 0,
"units": "m",
"decimalPlaces": 2,
"qgcRebootRequired": true
},
{
"name": "FixedBasePositionAccuracy",
"shortDescription": "Base Position Accuracy",
"longDescription": "Defines the accuracy of the fixed RTK base position.",
"type": "float",
"defaultValue": 0,
"units": "m",
"decimalPlaces": 2,
"qgcRebootRequired": true
} }
] ]
...@@ -17,11 +17,21 @@ const char* RTKSettings::settingsGroup = "RTK"; ...@@ -17,11 +17,21 @@ const char* RTKSettings::settingsGroup = "RTK";
const char* RTKSettings::surveyInAccuracyLimitName = "SurveyInAccuracyLimit"; const char* RTKSettings::surveyInAccuracyLimitName = "SurveyInAccuracyLimit";
const char* RTKSettings::surveyInMinObservationDurationName = "SurveyInMinObservationDuration"; const char* RTKSettings::surveyInMinObservationDurationName = "SurveyInMinObservationDuration";
const char* RTKSettings::useFixedBasePositionName = "UseFixedBasePosition";
const char* RTKSettings::fixedBasePositionLatitudeName = "FixedBasePositionLatitude";
const char* RTKSettings::fixedBasePositionLongitudeName = "FixedBasePositionLongitude";
const char* RTKSettings::fixedBasePositionAltitudeName = "FixedBasePositionAltitude";
const char* RTKSettings::fixedBasePositionAccuracyName = "FixedBasePositionAccuracy";
RTKSettings::RTKSettings(QObject* parent) RTKSettings::RTKSettings(QObject* parent)
: SettingsGroup(name, settingsGroup, parent) : SettingsGroup (name, settingsGroup, parent)
, _surveyInAccuracyLimitFact(NULL) , _surveyInAccuracyLimitFact (nullptr)
, _surveyInMinObservationDurationFact(NULL) , _surveyInMinObservationDurationFact (nullptr)
, _useFixedBasePositionFact (nullptr)
, _fixedBasePositionLatitudeFact (nullptr)
, _fixedBasePositionLongitudeFact (nullptr)
, _fixedBasePositionAltitudeFact (nullptr)
, _fixedBasePositionAccuracyFact (nullptr)
{ {
QQmlEngine::setObjectOwnership(this, QQmlEngine::CppOwnership); QQmlEngine::setObjectOwnership(this, QQmlEngine::CppOwnership);
qmlRegisterUncreatableType<RTKSettings>("QGroundControl.SettingsManager", 1, 0, "RTKSettings", "Reference only"); qmlRegisterUncreatableType<RTKSettings>("QGroundControl.SettingsManager", 1, 0, "RTKSettings", "Reference only");
...@@ -44,3 +54,48 @@ Fact* RTKSettings::surveyInMinObservationDuration(void) ...@@ -44,3 +54,48 @@ Fact* RTKSettings::surveyInMinObservationDuration(void)
return _surveyInMinObservationDurationFact; return _surveyInMinObservationDurationFact;
} }
Fact* RTKSettings::useFixedBasePosition(void)
{
if (!_useFixedBasePositionFact) {
_useFixedBasePositionFact = _createSettingsFact(useFixedBasePositionName);
}
return _useFixedBasePositionFact;
}
Fact* RTKSettings::fixedBasePositionLatitude(void)
{
if (!_fixedBasePositionLatitudeFact) {
_fixedBasePositionLatitudeFact = _createSettingsFact(fixedBasePositionLatitudeName);
}
return _fixedBasePositionLatitudeFact;
}
Fact* RTKSettings::fixedBasePositionLongitude(void)
{
if (!_fixedBasePositionLongitudeFact) {
_fixedBasePositionLongitudeFact = _createSettingsFact(fixedBasePositionLongitudeName);
}
return _fixedBasePositionLongitudeFact;
}
Fact* RTKSettings::fixedBasePositionAltitude(void)
{
if (!_fixedBasePositionAltitudeFact) {
_fixedBasePositionAltitudeFact = _createSettingsFact(fixedBasePositionAltitudeName);
}
return _fixedBasePositionAltitudeFact;
}
Fact* RTKSettings::fixedBasePositionAccuracy(void)
{
if (!_fixedBasePositionAccuracyFact) {
_fixedBasePositionAccuracyFact = _createSettingsFact(fixedBasePositionAccuracyName);
}
return _fixedBasePositionAccuracyFact;
}
...@@ -20,17 +20,37 @@ public: ...@@ -20,17 +20,37 @@ public:
Q_PROPERTY(Fact* surveyInAccuracyLimit READ surveyInAccuracyLimit CONSTANT) Q_PROPERTY(Fact* surveyInAccuracyLimit READ surveyInAccuracyLimit CONSTANT)
Q_PROPERTY(Fact* surveyInMinObservationDuration READ surveyInMinObservationDuration CONSTANT) Q_PROPERTY(Fact* surveyInMinObservationDuration READ surveyInMinObservationDuration CONSTANT)
Q_PROPERTY(Fact* useFixedBasePosition READ useFixedBasePosition CONSTANT)
Q_PROPERTY(Fact* fixedBasePositionLatitude READ fixedBasePositionLatitude CONSTANT)
Q_PROPERTY(Fact* fixedBasePositionLongitude READ fixedBasePositionLongitude CONSTANT)
Q_PROPERTY(Fact* fixedBasePositionAltitude READ fixedBasePositionAltitude CONSTANT)
Q_PROPERTY(Fact* fixedBasePositionAccuracy READ fixedBasePositionAccuracy CONSTANT)
Fact* surveyInAccuracyLimit (void); Fact* surveyInAccuracyLimit (void);
Fact* surveyInMinObservationDuration(void); Fact* surveyInMinObservationDuration(void);
Fact* useFixedBasePosition (void);
Fact* fixedBasePositionLatitude (void);
Fact* fixedBasePositionLongitude (void);
Fact* fixedBasePositionAltitude (void);
Fact* fixedBasePositionAccuracy (void);
static const char* name; static const char* name;
static const char* settingsGroup; static const char* settingsGroup;
static const char* surveyInAccuracyLimitName; static const char* surveyInAccuracyLimitName;
static const char* surveyInMinObservationDurationName; static const char* surveyInMinObservationDurationName;
static const char* useFixedBasePositionName;
static const char* fixedBasePositionLatitudeName;
static const char* fixedBasePositionLongitudeName;
static const char* fixedBasePositionAltitudeName;
static const char* fixedBasePositionAccuracyName;
private: private:
SettingsFact* _surveyInAccuracyLimitFact; SettingsFact* _surveyInAccuracyLimitFact;
SettingsFact* _surveyInMinObservationDurationFact; SettingsFact* _surveyInMinObservationDurationFact;
SettingsFact* _useFixedBasePositionFact;
SettingsFact* _fixedBasePositionLatitudeFact;
SettingsFact* _fixedBasePositionLongitudeFact;
SettingsFact* _fixedBasePositionAltitudeFact;
SettingsFact* _fixedBasePositionAccuracyFact;
}; };
...@@ -2,35 +2,62 @@ ...@@ -2,35 +2,62 @@
{ {
"name": "connected", "name": "connected",
"shortDescription": "Connected", "shortDescription": "Connected",
"type": "bool" "type": "bool",
"default": false
}, },
{ {
"name": "currentAccuracy", "name": "currentAccuracy",
"shortDescription": "Current Accuracy", "shortDescription": "Current Survey-In Accuracy",
"type": "double", "type": "double",
"decimalPlaces": 1, "decimalPlaces": 1,
"units": "m" "units": "m",
"default": null
},
{
"name": "currentLatitude",
"shortDescription": "Current Survey-In Latitude",
"type": "double",
"decimalPlaces": 7,
"default": null
},
{
"name": "currentLongitude",
"shortDescription": "Current Survey-In Longitude",
"type": "double",
"decimalPlaces": 7,
"default": null
},
{
"name": "currentAltitude",
"shortDescription": "Current Survey-In Altitude",
"type": "float",
"decimalPlaces": 2,
"default": null
}, },
{ {
"name": "currentDuration", "name": "currentDuration",
"shortDescription": "Current Duration", "shortDescription": "Current Survey-In Duration",
"type": "double", "type": "double",
"decimalPlaces": 0, "decimalPlaces": 0,
"units": "s" "units": "s",
"default": 0
}, },
{ {
"name": "valid", "name": "valid",
"shortDescription": "Survey-in Valid", "shortDescription": "Survey-In Valid",
"type": "bool" "type": "bool",
"default": false
}, },
{ {
"name": "active", "name": "active",
"shortDescription": "Survey-in Active", "shortDescription": "Survey-In Active",
"type": "bool" "type": "bool",
"default": false
}, },
{ {
"name": "numSatellites", "name": "numSatellites",
"shortDescription": "Number of Satellites", "shortDescription": "Number of Satellites",
"type": "int32" "type": "int32",
"default": 0
} }
] ]
...@@ -12,22 +12,31 @@ ...@@ -12,22 +12,31 @@
const char* GPSRTKFactGroup::_connectedFactName = "connected"; const char* GPSRTKFactGroup::_connectedFactName = "connected";
const char* GPSRTKFactGroup::_currentAccuracyFactName = "currentAccuracy"; const char* GPSRTKFactGroup::_currentAccuracyFactName = "currentAccuracy";
const char* GPSRTKFactGroup::_currentDurationFactName = "currentDuration"; const char* GPSRTKFactGroup::_currentDurationFactName = "currentDuration";
const char* GPSRTKFactGroup::_currentLatitudeFactName = "currentLatitude";
const char* GPSRTKFactGroup::_currentLongitudeFactName = "currentLongitude";
const char* GPSRTKFactGroup::_currentAltitudeFactName = "currentAltitude";
const char* GPSRTKFactGroup::_validFactName = "valid"; const char* GPSRTKFactGroup::_validFactName = "valid";
const char* GPSRTKFactGroup::_activeFactName = "active"; const char* GPSRTKFactGroup::_activeFactName = "active";
const char* GPSRTKFactGroup::_numSatellitesFactName = "numSatellites"; const char* GPSRTKFactGroup::_numSatellitesFactName = "numSatellites";
GPSRTKFactGroup::GPSRTKFactGroup(QObject* parent) GPSRTKFactGroup::GPSRTKFactGroup(QObject* parent)
: FactGroup(1000, ":/json/Vehicle/GPSRTKFact.json", parent) : FactGroup (1000, ":/json/Vehicle/GPSRTKFact.json", parent)
, _connected (false, _connectedFactName, FactMetaData::valueTypeBool) , _connected (0, _connectedFactName, FactMetaData::valueTypeBool)
, _currentDuration (0, _currentDurationFactName, FactMetaData::valueTypeDouble) , _currentDuration (0, _currentDurationFactName, FactMetaData::valueTypeDouble)
, _currentAccuracy (0, _currentAccuracyFactName, FactMetaData::valueTypeDouble) , _currentAccuracy (0, _currentAccuracyFactName, FactMetaData::valueTypeDouble)
, _valid (false, _validFactName, FactMetaData::valueTypeBool) , _currentLatitude (0, _currentLatitudeFactName, FactMetaData::valueTypeDouble)
, _active (false, _activeFactName, FactMetaData::valueTypeBool) , _currentLongitude (0, _currentLongitudeFactName, FactMetaData::valueTypeDouble)
, _numSatellites (false, _numSatellitesFactName, FactMetaData::valueTypeInt32) , _currentAltitude (0, _currentAltitudeFactName, FactMetaData::valueTypeFloat)
, _valid (0, _validFactName, FactMetaData::valueTypeBool)
, _active (0, _activeFactName, FactMetaData::valueTypeBool)
, _numSatellites (0, _numSatellitesFactName, FactMetaData::valueTypeInt32)
{ {
_addFact(&_connected, _connectedFactName); _addFact(&_connected, _connectedFactName);
_addFact(&_currentDuration, _currentDurationFactName); _addFact(&_currentDuration, _currentDurationFactName);
_addFact(&_currentAccuracy, _currentAccuracyFactName); _addFact(&_currentAccuracy, _currentAccuracyFactName);
_addFact(&_currentLatitude, _currentLatitudeFactName);
_addFact(&_currentLongitude, _currentLongitudeFactName);
_addFact(&_currentAltitude, _currentAltitudeFactName);
_addFact(&_valid, _validFactName); _addFact(&_valid, _validFactName);
_addFact(&_active, _activeFactName); _addFact(&_active, _activeFactName);
_addFact(&_numSatellites, _numSatellitesFactName); _addFact(&_numSatellites, _numSatellitesFactName);
......
...@@ -22,29 +22,41 @@ public: ...@@ -22,29 +22,41 @@ public:
Q_PROPERTY(Fact* connected READ connected CONSTANT) Q_PROPERTY(Fact* connected READ connected CONSTANT)
Q_PROPERTY(Fact* currentDuration READ currentDuration CONSTANT) Q_PROPERTY(Fact* currentDuration READ currentDuration CONSTANT)
Q_PROPERTY(Fact* currentAccuracy READ currentAccuracy CONSTANT) Q_PROPERTY(Fact* currentAccuracy READ currentAccuracy CONSTANT)
Q_PROPERTY(Fact* currentLatitude READ currentLatitude CONSTANT)
Q_PROPERTY(Fact* currentLongitude READ currentLongitude CONSTANT)
Q_PROPERTY(Fact* currentAltitude READ currentAltitude CONSTANT)
Q_PROPERTY(Fact* valid READ valid CONSTANT) Q_PROPERTY(Fact* valid READ valid CONSTANT)
Q_PROPERTY(Fact* active READ active CONSTANT) Q_PROPERTY(Fact* active READ active CONSTANT)
Q_PROPERTY(Fact* numSatellites READ numSatellites CONSTANT) Q_PROPERTY(Fact* numSatellites READ numSatellites CONSTANT)
Fact* connected (void) { return &_connected; } Fact* connected (void) { return &_connected; }
Fact* currentDuration (void) { return &_currentDuration; } Fact* currentDuration (void) { return &_currentDuration; }
Fact* currentAccuracy (void) { return &_currentAccuracy; } Fact* currentAccuracy (void) { return &_currentAccuracy; }
Fact* valid (void) { return &_valid; } Fact* currentLatitude (void) { return &_currentLatitude; }
Fact* active (void) { return &_active; } Fact* currentLongitude (void) { return &_currentLongitude; }
Fact* numSatellites (void) { return &_numSatellites; } Fact* currentAltitude (void) { return &_currentAltitude; }
Fact* valid (void) { return &_valid; }
Fact* active (void) { return &_active; }
Fact* numSatellites (void) { return &_numSatellites; }
static const char* _connectedFactName; static const char* _connectedFactName;
static const char* _currentDurationFactName; static const char* _currentDurationFactName;
static const char* _currentAccuracyFactName; static const char* _currentAccuracyFactName;
static const char* _currentLatitudeFactName;
static const char* _currentLongitudeFactName;
static const char* _currentAltitudeFactName;
static const char* _validFactName; static const char* _validFactName;
static const char* _activeFactName; static const char* _activeFactName;
static const char* _numSatellitesFactName; static const char* _numSatellitesFactName;
private: private:
Fact _connected; ///< is an RTK gps connected? Fact _connected; ///< is an RTK gps connected?
Fact _currentDuration; ///< survey-in status in [s] Fact _currentDuration; ///< survey-in status in [s]
Fact _currentAccuracy; ///< survey-in accuracy in [mm] Fact _currentAccuracy; ///< survey-in accuracy in [mm]
Fact _valid; ///< survey-in valid? Fact _currentLatitude; ///< survey-in latitude
Fact _active; ///< survey-in active? Fact _currentLongitude; ///< survey-in latitude
Fact _numSatellites; ///< number of satellites Fact _currentAltitude; ///< survey-in latitude
Fact _valid; ///< survey-in complete?
Fact _active; ///< survey-in active?
Fact _numSatellites; ///< number of satellites
}; };
...@@ -393,22 +393,99 @@ QGCView { ...@@ -393,22 +393,99 @@ QGCView {
id: rtkGrid id: rtkGrid
anchors.topMargin: _margins anchors.topMargin: _margins
anchors.top: parent.top anchors.top: parent.top
Layout.fillWidth: false Layout.fillWidth: true
anchors.horizontalCenter: parent.horizontalCenter anchors.horizontalCenter: parent.horizontalCenter
columns: 2 columns: 2
property var rtkSettings: QGroundControl.settingsManager.rtkSettings property var rtkSettings: QGroundControl.settingsManager.rtkSettings
property bool useFixedPosition: rtkSettings.useFixedBasePosition.rawValue
QGCLabel { text: rtkGrid.rtkSettings.surveyInAccuracyLimit.shortDescription } QGCLabel {
text: rtkGrid.rtkSettings.surveyInAccuracyLimit.shortDescription
visible: rtkGrid.rtkSettings.surveyInAccuracyLimit.visible
}
FactTextField { FactTextField {
Layout.preferredWidth: _valueFieldWidth
fact: rtkGrid.rtkSettings.surveyInAccuracyLimit fact: rtkGrid.rtkSettings.surveyInAccuracyLimit
visible: rtkGrid.rtkSettings.surveyInAccuracyLimit.visible
Layout.preferredWidth: _valueFieldWidth
} }
QGCLabel { text: rtkGrid.rtkSettings.surveyInMinObservationDuration.shortDescription } QGCLabel {
text: rtkGrid.rtkSettings.surveyInMinObservationDuration.shortDescription
visible: rtkGrid.rtkSettings.surveyInMinObservationDuration.visible
}
FactTextField { FactTextField {
Layout.preferredWidth: _valueFieldWidth
fact: rtkGrid.rtkSettings.surveyInMinObservationDuration fact: rtkGrid.rtkSettings.surveyInMinObservationDuration
visible: rtkGrid.rtkSettings.surveyInMinObservationDuration.visible
Layout.preferredWidth: _valueFieldWidth
}
FactCheckBox {
text: rtkGrid.rtkSettings.useFixedBasePosition.shortDescription
visible: rtkGrid.rtkSettings.useFixedBasePosition.visible
fact: rtkGrid.rtkSettings.useFixedBasePosition
Layout.columnSpan: 2
}
QGCLabel {
text: rtkGrid.rtkSettings.fixedBasePositionLatitude.shortDescription
visible: rtkGrid.rtkSettings.fixedBasePositionLatitude.visible
enabled: rtkGrid.useFixedPosition
}
FactTextField {
fact: rtkGrid.rtkSettings.fixedBasePositionLatitude
visible: rtkGrid.rtkSettings.fixedBasePositionLatitude.visible
enabled: rtkGrid.useFixedPosition
Layout.fillWidth: true
}
QGCLabel {
text: rtkGrid.rtkSettings.fixedBasePositionLongitude.shortDescription
visible: rtkGrid.rtkSettings.fixedBasePositionLongitude.visible
enabled: rtkGrid.useFixedPosition
}
FactTextField {
fact: rtkGrid.rtkSettings.fixedBasePositionLongitude
visible: rtkGrid.rtkSettings.fixedBasePositionLongitude.visible
enabled: rtkGrid.useFixedPosition
Layout.fillWidth: true
}
QGCLabel {
text: rtkGrid.rtkSettings.fixedBasePositionAltitude.shortDescription
visible: rtkGrid.rtkSettings.fixedBasePositionAltitude.visible
enabled: rtkGrid.useFixedPosition
}
FactTextField {
fact: rtkGrid.rtkSettings.fixedBasePositionAltitude
visible: rtkGrid.rtkSettings.fixedBasePositionAltitude.visible
enabled: rtkGrid.useFixedPosition
Layout.fillWidth: true
}
QGCLabel {
text: rtkGrid.rtkSettings.fixedBasePositionAccuracy.shortDescription
visible: rtkGrid.rtkSettings.fixedBasePositionAccuracy.visible
enabled: rtkGrid.useFixedPosition
}
FactTextField {
fact: rtkGrid.rtkSettings.fixedBasePositionAccuracy
visible: rtkGrid.rtkSettings.fixedBasePositionAccuracy.visible
enabled: rtkGrid.useFixedPosition
Layout.fillWidth: true
}
QGCButton {
text: qsTr("Save Current Base Position")
Layout.columnSpan: 2
enabled: QGroundControl.gpsRtk.valid.value
onClicked: {
rtkGrid.rtkSettings.fixedBasePositionLatitude.rawValue = QGroundControl.gpsRtk.currentLatitude.rawValue
rtkGrid.rtkSettings.fixedBasePositionLongitude.rawValue = QGroundControl.gpsRtk.currentLongitude.rawValue
rtkGrid.rtkSettings.fixedBasePositionAltitude.rawValue = QGroundControl.gpsRtk.currentAltitude.rawValue
rtkGrid.rtkSettings.fixedBasePositionAccuracy.rawValue = QGroundControl.gpsRtk.currentAccuracy.rawValue
}
} }
} }
} }
......
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