QGroundControl
Ground Control Station for MAVLink Drones
Loading...
Searching...
No Matches
QGroundControlQmlGlobal.cc
Go to the documentation of this file.
2
3#include "QGCApplication.h"
4#include "QGCCorePlugin.h"
5#include "LinkManager.h"
6#include "MAVLinkProtocol.h"
8#include "AppSettings.h"
9#include "FlightMapSettings.h"
10#include "SettingsManager.h"
11#include "PositionManager.h"
12#include "QGCMapEngineManager.h"
13#include "ADSBVehicleManager.h"
14#include "MissionCommandTree.h"
15#include "VideoManager.h"
16#include "MultiVehicleManager.h"
17#include "QGCLoggingCategory.h"
18#ifndef QGC_NO_SERIAL_LINK
19#include "GPSManager.h"
20#include "GPSRtk.h"
21#endif
22#ifdef QT_DEBUG
23#include "MockLink.h"
24#endif
25
26#include <QtCore/QSettings>
27#include <QtCore/QLineF>
28
29QGC_LOGGING_CATEGORY(GuidedActionsControllerLog, "QMLControls.GuidedActionsController")
30
31QGeoCoordinate QGroundControlQmlGlobal::_coord = QGeoCoordinate(0.0,0.0);
32double QGroundControlQmlGlobal::_zoom = 2;
33
35 : QObject(parent)
36 , _mapEngineManager(QGCMapEngineManager::instance())
37 , _adsbVehicleManager(ADSBVehicleManager::instance())
38 , _qgcPositionManager(QGCPositionManager::instance())
39 , _missionCommandTree(MissionCommandTree::instance())
40 , _videoManager(VideoManager::instance())
41 , _linkManager(LinkManager::instance())
42 , _multiVehicleManager(MultiVehicleManager::instance())
43 , _settingsManager(SettingsManager::instance())
44 , _corePlugin(QGCCorePlugin::instance())
45 , _globalPalette(new QGCPalette(this))
46#ifndef QGC_NO_SERIAL_LINK
47 , _gpsRtkFactGroup(GPSManager::instance()->gpsRtk()->gpsRtkFactGroup())
48#endif
49{
50 // 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.
51 // setParent(nullptr);
52
53 // Load last coordinates and zoom from config file
54 QSettings settings;
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, []() {
62 // When they settle, save flightMapPosition and Zoom to the config file
63 QSettings settingsInner;
64 settingsInner.beginGroup(_flightMapPositionSettingsGroup);
65 settingsInner.setValue(_flightMapPositionLatitudeSettingsKey, _coord.latitude());
66 settingsInner.setValue(_flightMapPositionLongitudeSettingsKey, _coord.longitude());
67 settingsInner.setValue(_flightMapZoomSettingsKey, _zoom);
68 });
69 connect(this, &QGroundControlQmlGlobal::flightMapPositionChanged, this, [this](QGeoCoordinate){
70 if (!_flightMapPositionSettledTimer.isActive()) {
71 _flightMapPositionSettledTimer.start();
72 }
73 });
74 connect(this, &QGroundControlQmlGlobal::flightMapZoomChanged, this, [this](double){
75 if (!_flightMapPositionSettledTimer.isActive()) {
76 _flightMapPositionSettledTimer.start();
77 }
78 });
79}
80
84
85void QGroundControlQmlGlobal::saveGlobalSetting (const QString& key, const QString& value)
86{
87 QSettings settings;
88 settings.beginGroup(kQmlGlobalKeyName);
89 settings.setValue(key, value);
90}
91
92QString QGroundControlQmlGlobal::loadGlobalSetting (const QString& key, const QString& defaultValue)
93{
94 QSettings settings;
95 settings.beginGroup(kQmlGlobalKeyName);
96 return settings.value(key, defaultValue).toString();
97}
98
99void QGroundControlQmlGlobal::saveBoolGlobalSetting (const QString& key, bool value)
100{
101 QSettings settings;
102 settings.beginGroup(kQmlGlobalKeyName);
103 settings.setValue(key, value);
104}
105
106bool QGroundControlQmlGlobal::loadBoolGlobalSetting (const QString& key, bool defaultValue)
107{
108 QSettings settings;
109 settings.beginGroup(kQmlGlobalKeyName);
110 return settings.value(key, defaultValue).toBool();
111}
112
113void QGroundControlQmlGlobal::startPX4MockLink(bool sendStatusText, bool enableCamera, bool enableGimbal)
114{
115#ifdef QT_DEBUG
116 MockLink::startPX4MockLink(sendStatusText, enableCamera, enableGimbal);
117#else
118 Q_UNUSED(sendStatusText);
119 Q_UNUSED(enableCamera);
120 Q_UNUSED(enableGimbal);
121#endif
122}
123
124void QGroundControlQmlGlobal::startGenericMockLink(bool sendStatusText, bool enableCamera, bool enableGimbal)
125{
126#ifdef QT_DEBUG
127 MockLink::startGenericMockLink(sendStatusText, enableCamera, enableGimbal);
128#else
129 Q_UNUSED(sendStatusText);
130 Q_UNUSED(enableCamera);
131 Q_UNUSED(enableGimbal);
132#endif
133}
134
135void QGroundControlQmlGlobal::startAPMArduCopterMockLink(bool sendStatusText, bool enableCamera, bool enableGimbal)
136{
137#ifdef QT_DEBUG
138 MockLink::startAPMArduCopterMockLink(sendStatusText, enableCamera, enableGimbal);
139#else
140 Q_UNUSED(sendStatusText);
141 Q_UNUSED(enableCamera);
142 Q_UNUSED(enableGimbal);
143#endif
144}
145
146void QGroundControlQmlGlobal::startAPMArduPlaneMockLink(bool sendStatusText, bool enableCamera, bool enableGimbal)
147{
148#ifdef QT_DEBUG
149 MockLink::startAPMArduPlaneMockLink(sendStatusText, enableCamera, enableGimbal);
150#else
151 Q_UNUSED(sendStatusText);
152 Q_UNUSED(enableCamera);
153 Q_UNUSED(enableGimbal);
154#endif
155}
156
157void QGroundControlQmlGlobal::startAPMArduSubMockLink(bool sendStatusText, bool enableCamera, bool enableGimbal)
158{
159#ifdef QT_DEBUG
160 MockLink::startAPMArduSubMockLink(sendStatusText, enableCamera, enableGimbal);
161#else
162 Q_UNUSED(sendStatusText);
163 Q_UNUSED(enableCamera);
164 Q_UNUSED(enableGimbal);
165#endif
166}
167
168void QGroundControlQmlGlobal::startAPMArduRoverMockLink(bool sendStatusText, bool enableCamera, bool enableGimbal)
169{
170#ifdef QT_DEBUG
171 MockLink::startAPMArduRoverMockLink(sendStatusText, enableCamera, enableGimbal);
172#else
173 Q_UNUSED(sendStatusText);
174 Q_UNUSED(enableCamera);
175 Q_UNUSED(enableGimbal);
176#endif
177}
178
180{
181#ifdef QT_DEBUG
182 QList<SharedLinkInterfacePtr> sharedLinks = LinkManager::instance()->links();
183
184 for (int i=0; i<sharedLinks.count(); i++) {
185 LinkInterface* link = sharedLinks[i].get();
186 MockLink* mockLink = qobject_cast<MockLink*>(link);
187 if (mockLink) {
188 mockLink->disconnect();
189 return;
190 }
191 }
192#endif
193}
194
199
201{
202 if (singleFirmwareSupport()) {
203 return FirmwarePluginManager::instance()->supportedVehicleClasses(FirmwarePluginManager::instance()->supportedFirmwareClasses()[0]).count() == 1;
204 }
205
206 return false;
207}
208
213
218
219bool QGroundControlQmlGlobal::linesIntersect(QPointF line1A, QPointF line1B, QPointF line2A, QPointF line2B)
220{
221 QPointF intersectPoint;
222
223 auto intersect = QLineF(line1A, line1B).intersects(QLineF(line2A, line2B), &intersectPoint);
224
225 return intersect == QLineF::BoundedIntersection &&
226 intersectPoint != line1A && intersectPoint != line1B;
227}
228
229void QGroundControlQmlGlobal::setFlightMapPosition(QGeoCoordinate& coordinate)
230{
231 if (coordinate != flightMapPosition()) {
232 _coord.setLatitude(coordinate.latitude());
233 _coord.setLongitude(coordinate.longitude());
234 emit flightMapPositionChanged(coordinate);
235 }
236}
237
239{
240 if (zoom != flightMapZoom()) {
241 _zoom = zoom;
242 emit flightMapZoomChanged(zoom);
243 }
244}
245
247{
248 QString versionStr = QCoreApplication::applicationVersion();
249 if(QSysInfo::buildAbi().contains("32"))
250 {
251 versionStr += QStringLiteral(" %1").arg(tr("32 bit"));
252 }
253 else if(QSysInfo::buildAbi().contains("64"))
254 {
255 versionStr += QStringLiteral(" %1").arg(tr("64 bit"));
256 }
257 return versionStr;
258}
259
261{
262 switch (altMode) {
263 case AltitudeModeNone:
264 return QString();
266 // Showing (Rel) all the time ends up being too noisy
267 return QString();
269 return tr("(AMSL)");
271 return tr("(TerrC)");
273 return tr("(Terr)");
275 qWarning() << "Internal Error: QGroundControlQmlGlobal::altitudeModeExtraUnits called with altMode == AltitudeModeMixed";
276 return QString();
277 }
278
279 // Should never get here but makes some compilers happy
280 return QString();
281}
282
284{
285 switch (altMode) {
286 case AltitudeModeNone:
287 return QString();
289 return tr("Relative");
291 return tr("Absolute");
293 return tr("TerrainC");
295 return tr("Terrain");
297 return tr("Waypoint");
298 }
299
300 // Should never get here but makes some compilers happy
301 return QString();
302}
303
305 QObject* owner,
306 const QString& title,
307 const QString& text,
308 int buttons,
309 QJSValue acceptFunction,
310 QJSValue closeFunction)
311{
312 emit showMessageDialogRequested(owner, title, text, buttons, acceptFunction, closeFunction);
313}
314
316{
317 return _settingsManager->flightMapSettings()->elevationMapProvider()->rawValue().toString();
318}
319
321{
322 return _settingsManager->flightMapSettings()->elevationMapProvider()->rawValue().toString();
323}
324
329
334
336{
337 return QCoreApplication::applicationName();
338}
339
344
349
354
359
360void QGroundControlQmlGlobal::setCategoryLoggingOn(const QString &category, bool enable)
361{
363}
364
366{
368}
369
#define QGC_LOGGING_CATEGORY(name, categoryStr)
static constexpr const char * parameterFileExtension
Definition AppSettings.h:88
static constexpr const char * telemetryFileExtension
Definition AppSettings.h:91
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()
Definition GPSManager.cc:23
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...
Definition LinkManager.h:35
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 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)
QString telemetryFileExtension(void) const
void showMessageDialogRequested(QObject *owner, QString title, QString text, int buttons, QJSValue acceptFunction, QJSValue closeFunction)
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)
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.
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)
bool loadBoolGlobalSetting(const QString &key, bool defaultValue)
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
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.