20#ifndef QGC_NO_SERIAL_LINK
28#include <QtCore/QLineF>
29#include <QtCore/QSettings>
30#include <QtGui/QClipboard>
31#include <QtGui/QGuiApplication>
54#ifndef QGC_NO_SERIAL_LINK
63 settings.beginGroup(_flightMapPositionSettingsGroup);
64 _coord.setLatitude(settings.value(_flightMapPositionLatitudeSettingsKey, _coord.latitude()).toDouble());
65 _coord.setLongitude(settings.value(_flightMapPositionLongitudeSettingsKey, _coord.longitude()).toDouble());
66 _zoom = settings.value(_flightMapZoomSettingsKey, _zoom).toDouble();
67 _flightMapPositionSettledTimer.setSingleShot(
true);
68 _flightMapPositionSettledTimer.setInterval(1000);
69 (void) connect(&_flightMapPositionSettledTimer, &QTimer::timeout,
this, []() {
71 QSettings settingsInner;
72 settingsInner.beginGroup(_flightMapPositionSettingsGroup);
73 settingsInner.setValue(_flightMapPositionLatitudeSettingsKey, _coord.latitude());
74 settingsInner.setValue(_flightMapPositionLongitudeSettingsKey, _coord.longitude());
75 settingsInner.setValue(_flightMapZoomSettingsKey, _zoom);
78 if (!_flightMapPositionSettledTimer.isActive()) {
79 _flightMapPositionSettledTimer.start();
83 if (!_flightMapPositionSettledTimer.isActive()) {
84 _flightMapPositionSettledTimer.start();
96 settings.beginGroup(kQmlGlobalKeyName);
97 settings.setValue(key, value);
103 settings.beginGroup(kQmlGlobalKeyName);
104 return settings.value(key, defaultValue).toString();
110 settings.beginGroup(kQmlGlobalKeyName);
111 settings.setValue(key, value);
117 settings.beginGroup(kQmlGlobalKeyName);
118 return settings.value(key, defaultValue).toBool();
126 Q_UNUSED(sendStatusText);
127 Q_UNUSED(enableCamera);
128 Q_UNUSED(enableGimbal);
137 Q_UNUSED(sendStatusText);
138 Q_UNUSED(enableCamera);
139 Q_UNUSED(enableGimbal);
148 Q_UNUSED(sendStatusText);
149 Q_UNUSED(enableCamera);
150 Q_UNUSED(enableGimbal);
159 Q_UNUSED(sendStatusText);
160 Q_UNUSED(enableCamera);
161 Q_UNUSED(enableGimbal);
170 Q_UNUSED(sendStatusText);
171 Q_UNUSED(enableCamera);
172 Q_UNUSED(enableGimbal);
181 Q_UNUSED(sendStatusText);
182 Q_UNUSED(enableCamera);
183 Q_UNUSED(enableGimbal);
192 for (
int i=0; i<sharedLinks.count(); i++) {
194 MockLink* mockLink = qobject_cast<MockLink*>(link);
229 QPointF intersectPoint;
231 auto intersect = QLineF(line1A, line1B).intersects(QLineF(line2A, line2B), &intersectPoint);
233 return intersect == QLineF::BoundedIntersection &&
234 intersectPoint != line1A && intersectPoint != line1B;
240 _coord.setLatitude(coordinate.latitude());
241 _coord.setLongitude(coordinate.longitude());
256 QString versionStr = QCoreApplication::applicationVersion();
257 if(QSysInfo::buildAbi().contains(
"32"))
259 versionStr += QStringLiteral(
" %1").arg(tr(
"32 bit"));
261 else if(QSysInfo::buildAbi().contains(
"64"))
263 versionStr += QStringLiteral(
" %1").arg(tr(
"64 bit"));
312 const QString& title,
315 QJSValue acceptFunction,
316 QJSValue closeFunction)
328 QGuiApplication::clipboard()->setText(text);
333 return _settingsManager->
flightMapSettings()->elevationMapProvider()->rawValue().toString();
338 return _settingsManager->
flightMapSettings()->elevationMapProvider()->rawValue().toString();
353 return QCoreApplication::applicationName();
#define QGC_LOGGING_CATEGORY(name, categoryStr)
static constexpr const char * parameterFileExtension
static constexpr const char * telemetryFileExtension
void testAudioOutput()
Tests the audio output. Will stop current output before test.
static AudioOutput * instance()
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()
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 LinkManager * instance()
QList< SharedLinkInterfacePtr > links()
Bag of named MAVLink signing keys; correct key per vehicle is auto-detected from incoming signed pack...
Manages a hierarchy of MissionCommandUIInfo.
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)
Extension mechanism for generic, non-firmware-specific customization of QGC.
static constexpr const FirmwareClass_t FirmwareClassPX4
static constexpr const FirmwareClass_t FirmwareClassArduPilot
QGCPalette is used in QML ui to expose color properties for the QGC palette.
void setFlightMapPosition(QGeoCoordinate &coordinate)
Q_INVOKABLE void startGenericMockLink(bool sendStatusText, bool enableCamera, bool enableGimbal)
Q_INVOKABLE 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)
Q_INVOKABLE void startAPMArduPlaneMockLink(bool sendStatusText, bool enableCamera, bool enableGimbal)
Q_INVOKABLE QString loadGlobalSetting(const QString &key, const QString &defaultValue)
Q_INVOKABLE void startPX4MockLink(bool sendStatusText, bool enableCamera, bool enableGimbal)
@ AltitudeFrameCalcAboveTerrain
Q_INVOKABLE QString altitudeFrameExtraUnits(AltitudeFrame altFrame)
String shown in the FactTextField.extraUnits ui.
bool singleVehicleSupport()
bool px4ProFirmwareSupported()
QString elevationProviderNotice()
static QGeoCoordinate flightMapPosition()
Q_INVOKABLE void startAPMArduCopterMockLink(bool sendStatusText, bool enableCamera, bool enableGimbal)
void flightMapZoomChanged(double flightMapZoom)
Q_INVOKABLE void stopOneMockLink(void)
Q_INVOKABLE bool loadBoolGlobalSetting(const QString &key, bool defaultValue)
static QString qgcVersion()
QString parameterFileExtension(void) const
Q_INVOKABLE bool linesIntersect(QPointF xLine1, QPointF yLine1, QPointF xLine2, QPointF yLine2)
Q_INVOKABLE void saveBoolGlobalSetting(const QString &key, bool value)
Q_INVOKABLE void startAPMArduRoverMockLink(bool sendStatusText, bool enableCamera, bool enableGimbal)
Q_INVOKABLE QString altitudeFrameShortDescription(AltitudeFrame altFrame)
String shown when a user needs to select an altitude frame.
Q_INVOKABLE void showMessageDialog(QObject *owner, const QString &title, const QString &text, int buttons=kDefaultMessageDialogButtons, QJSValue acceptFunction=QJSValue(), QJSValue closeFunction=QJSValue())
bool apmFirmwareSupported()
static Q_INVOKABLE void copyToClipboard(const QString &text)
Copy text to the system clipboard.
Q_INVOKABLE void saveGlobalSetting(const QString &key, const QString &value)
Q_INVOKABLE void testAudioOutput()
Provides access to all app settings.
FlightMapSettings * flightMapSettings() const