18#ifndef QGC_NO_SERIAL_LINK
26#include <QtCore/QSettings>
27#include <QtCore/QLineF>
46#ifndef QGC_NO_SERIAL_LINK
55 settings.beginGroup(_flightMapPositionSettingsGroup);
56 _coord.setLatitude(settings.value(_flightMapPositionLatitudeSettingsKey, _coord.latitude()).toDouble());
57 _coord.setLongitude(settings.value(_flightMapPositionLongitudeSettingsKey, _coord.longitude()).toDouble());
58 _zoom = settings.
value(_flightMapZoomSettingsKey, _zoom).toDouble();
59 _flightMapPositionSettledTimer.setSingleShot(
true);
60 _flightMapPositionSettledTimer.setInterval(1000);
61 (void) connect(&_flightMapPositionSettledTimer, &QTimer::timeout,
this, []() {
63 QSettings settingsInner;
64 settingsInner.beginGroup(_flightMapPositionSettingsGroup);
65 settingsInner.setValue(_flightMapPositionLatitudeSettingsKey, _coord.latitude());
66 settingsInner.setValue(_flightMapPositionLongitudeSettingsKey, _coord.longitude());
67 settingsInner.setValue(_flightMapZoomSettingsKey, _zoom);
70 if (!_flightMapPositionSettledTimer.isActive()) {
71 _flightMapPositionSettledTimer.start();
75 if (!_flightMapPositionSettledTimer.isActive()) {
76 _flightMapPositionSettledTimer.start();
85void QGroundControlQmlGlobal::saveGlobalSetting (
const QString& key,
const QString& value)
88 settings.beginGroup(kQmlGlobalKeyName);
89 settings.setValue(key,
value);
95 settings.beginGroup(kQmlGlobalKeyName);
96 return settings.value(key, defaultValue).toString();
102 settings.beginGroup(kQmlGlobalKeyName);
103 settings.setValue(key,
value);
109 settings.beginGroup(kQmlGlobalKeyName);
110 return settings.value(key, defaultValue).toBool();
118 Q_UNUSED(sendStatusText);
119 Q_UNUSED(enableCamera);
120 Q_UNUSED(enableGimbal);
129 Q_UNUSED(sendStatusText);
130 Q_UNUSED(enableCamera);
131 Q_UNUSED(enableGimbal);
140 Q_UNUSED(sendStatusText);
141 Q_UNUSED(enableCamera);
142 Q_UNUSED(enableGimbal);
151 Q_UNUSED(sendStatusText);
152 Q_UNUSED(enableCamera);
153 Q_UNUSED(enableGimbal);
162 Q_UNUSED(sendStatusText);
163 Q_UNUSED(enableCamera);
164 Q_UNUSED(enableGimbal);
173 Q_UNUSED(sendStatusText);
174 Q_UNUSED(enableCamera);
175 Q_UNUSED(enableGimbal);
182 QList<SharedLinkInterfacePtr> sharedLinks = LinkManager::instance()->links();
184 for (
int i=0; i<sharedLinks.count(); i++) {
186 MockLink* mockLink = qobject_cast<MockLink*>(link);
221 QPointF intersectPoint;
223 auto intersect = QLineF(line1A, line1B).intersects(QLineF(line2A, line2B), &intersectPoint);
225 return intersect == QLineF::BoundedIntersection &&
226 intersectPoint != line1A && intersectPoint != line1B;
232 _coord.setLatitude(coordinate.latitude());
233 _coord.setLongitude(coordinate.longitude());
248 QString versionStr = QCoreApplication::applicationVersion();
249 if(QSysInfo::buildAbi().contains(
"32"))
251 versionStr += QStringLiteral(
" %1").arg(tr(
"32 bit"));
253 else if(QSysInfo::buildAbi().contains(
"64"))
255 versionStr += QStringLiteral(
" %1").arg(tr(
"64 bit"));
271 return tr(
"(TerrC)");
275 qWarning() <<
"Internal Error: QGroundControlQmlGlobal::altitudeModeExtraUnits called with altMode == AltitudeModeMixed";
289 return tr(
"Relative");
291 return tr(
"Absolute");
293 return tr(
"TerrainC");
295 return tr(
"Terrain");
297 return tr(
"Waypoint");
306 const QString& title,
309 QJSValue acceptFunction,
310 QJSValue closeFunction)
337 return QCoreApplication::applicationName();
#define QGC_LOGGING_CATEGORY(name, categoryStr)
static constexpr const char * parameterFileExtension
static constexpr const char * telemetryFileExtension
QList< QGCMAVLink::FirmwareClass_t > supportedFirmwareClasses()
Returns list of firmwares which are supported by the system.
QList< QGCMAVLink::VehicleClass_t > supportedVehicleClasses(QGCMAVLink::FirmwareClass_t firmwareClass)
Returns the list of supported vehicle types for the specified firmware.
static FirmwarePluginManager * instance()
Fact *elevationMapProvider READ elevationMapProvider CONSTANT Fact * elevationMapProvider()
static GPSManager * instance()
The link interface defines the interface for all links used to communicate with the ground station ap...
Manage communication links The Link Manager organizes the physical Links. It can manage arbitrary lin...
static MockLink * startGenericMockLink(bool sendStatusText, bool enableCamera, bool enableGimbal, MockConfiguration::FailureMode_t failureMode=MockConfiguration::FailNone)
static MockLink * startAPMArduSubMockLink(bool sendStatusText, bool enableCamera, bool enableGimbal, MockConfiguration::FailureMode_t failureMode=MockConfiguration::FailNone)
static MockLink * startAPMArduCopterMockLink(bool sendStatusText, bool enableCamera, bool enableGimbal, MockConfiguration::FailureMode_t failureMode=MockConfiguration::FailNone)
static MockLink * startPX4MockLink(bool sendStatusText, bool enableCamera, bool enableGimbal, MockConfiguration::FailureMode_t failureMode=MockConfiguration::FailNone)
static MockLink * startAPMArduRoverMockLink(bool sendStatusText, bool enableCamera, bool enableGimbal, MockConfiguration::FailureMode_t failureMode=MockConfiguration::FailNone)
static MockLink * startAPMArduPlaneMockLink(bool sendStatusText, bool enableCamera, bool enableGimbal, MockConfiguration::FailureMode_t failureMode=MockConfiguration::FailNone)
static void clearDeleteAllSettingsNextBoot()
Clears the persistent flag to delete all settings the next time QGroundControl is started.
static void deleteAllSettingsNextBoot()
Sets the persistent flag to delete all settings the next time QGroundControl is started.
static bool categoryLoggingOn(const QString &fullCategroryName)
Returns true if logging is turned on for the specified category.
QmlObjectListModel * treeCategoryModel()
Returns the hierarchical list of available logging category names.
static QGCLoggingCategoryManager * instance()
QmlObjectListModel * flatCategoryModel()
Returns the flat list of available logging category names.
void setCategoryLoggingOn(const QString &fullCategoryName, bool enable)
Turns on/off logging for the specified category. State is saved in app settings.
void disableAllCategories()
static constexpr const FirmwareClass_t FirmwareClassPX4
static constexpr const FirmwareClass_t FirmwareClassArduPilot
void setFlightMapPosition(QGeoCoordinate &coordinate)
static bool categoryLoggingOn(const QString &category)
Returns true if logging is turned on for the specified category.
void startGenericMockLink(bool sendStatusText, bool enableCamera, bool enableGimbal)
void startAPMArduSubMockLink(bool sendStatusText, bool enableCamera, bool enableGimbal)
void setFlightMapZoom(double zoom)
static double flightMapZoom()
QString telemetryFileExtension(void) const
void showMessageDialogRequested(QObject *owner, QString title, QString text, int buttons, QJSValue acceptFunction, QJSValue closeFunction)
QString elevationProviderName()
~QGroundControlQmlGlobal()
bool singleFirmwareSupport()
void flightMapPositionChanged(QGeoCoordinate flightMapPosition)
void startAPMArduPlaneMockLink(bool sendStatusText, bool enableCamera, bool enableGimbal)
QString loadGlobalSetting(const QString &key, const QString &defaultValue)
void startPX4MockLink(bool sendStatusText, bool enableCamera, bool enableGimbal)
@ AltitudeModeCalcAboveTerrain
@ AltitudeModeTerrainFrame
static void disableAllLoggingCategories()
QString altitudeModeShortDescription(AltMode altMode)
String shown when a user needs to select an altitude mode.
QString altitudeModeExtraUnits(AltMode altMode)
String shown in the FactTextField.extraUnits ui.
bool singleVehicleSupport()
bool px4ProFirmwareSupported()
QString elevationProviderNotice()
static QGeoCoordinate flightMapPosition()
static void setCategoryLoggingOn(const QString &category, bool enable)
Turns on/off logging for the specified category. State is saved in app settings.
void startAPMArduCopterMockLink(bool sendStatusText, bool enableCamera, bool enableGimbal)
void flightMapZoomChanged(double flightMapZoom)
void stopOneMockLink(void)
static void deleteAllSettingsNextBoot()
bool loadBoolGlobalSetting(const QString &key, bool defaultValue)
static QString qgcVersion()
static void clearDeleteAllSettingsNextBoot()
QString parameterFileExtension(void) const
bool linesIntersect(QPointF xLine1, QPointF yLine1, QPointF xLine2, QPointF yLine2)
void saveBoolGlobalSetting(const QString &key, bool value)
void startAPMArduRoverMockLink(bool sendStatusText, bool enableCamera, bool enableGimbal)
void showMessageDialog(QObject *owner, const QString &title, const QString &text, int buttons=kDefaultMessageDialogButtons, QJSValue acceptFunction=QJSValue(), QJSValue closeFunction=QJSValue())
QString appName READ appName const QString & value
bool apmFirmwareSupported()
static QmlObjectListModel * treeLoggingCategoriesModel()
Returns the hierarchical list of available logging category names.
static QmlObjectListModel * flatLoggingCategoriesModel()
Returns the flat list of available logging category names.
Provides access to all app settings.