QGroundControlQmlGlobal.h 14.2 KB
Newer Older
1 2 3 4 5 6 7 8
/****************************************************************************
 *
 *   (c) 2009-2016 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
 *
 * QGroundControl is licensed according to the terms in the file
 * COPYING.md in the root of the source code directory.
 *
 ****************************************************************************/
Gus Grubba's avatar
Gus Grubba committed
9

10 11 12 13 14 15 16

/// @file
///     @author Don Gagne <don@thegagnes.com>

#ifndef QGroundControlQmlGlobal_H
#define QGroundControlQmlGlobal_H

17
#include "QGCToolbox.h"
dogmaphobic's avatar
dogmaphobic committed
18
#include "QGCApplication.h"
Don Gagne's avatar
Don Gagne committed
19
#include "LinkManager.h"
20
#include "SettingsFact.h"
21
#include "FactMetaData.h"
Jimmy Johnson's avatar
Jimmy Johnson committed
22
#include "SimulatedPosition.h"
23
#include "QGCLoggingCategory.h"
24
#include "AppSettings.h"
25
#include "AirspaceManager.h"
26 27 28 29 30
#if defined(QGC_GST_TAISYNC_ENABLED)
#include "TaisyncManager.h"
#else
class TaisyncManager;
#endif
31 32 33 34 35
#if defined(QGC_GST_MICROHARD_ENABLED)
#include "MicrohardManager.h"
#else
class MicrohardManager;
#endif
36

37 38 39 40
#ifdef QT_DEBUG
#include "MockLink.h"
#endif

41 42
class QGCToolbox;

43
class QGroundControlQmlGlobal : public QGCTool
44 45 46 47
{
    Q_OBJECT

public:
48
    QGroundControlQmlGlobal(QGCApplication* app, QGCToolbox* toolbox);
49 50
    ~QGroundControlQmlGlobal();

51 52 53 54 55 56 57 58 59
    enum AltitudeMode {
        AltitudeModeNone,           // Being used as distance value unrelated to ground (for example distance to structure)
        AltitudeModeRelative,       // MAV_FRAME_GLOBAL_RELATIVE_ALT
        AltitudeModeAbsolute,       // MAV_FRAME_GLOBAL
        AltitudeModeAboveTerrain,   // Absolute altitude above terrain calculated from terrain data
        AltitudeModeTerrainFrame    // MAV_FRAME_GLOBAL_TERRAIN_ALT
    };
    Q_ENUM(AltitudeMode)

60 61
    Q_PROPERTY(QString              appName             READ appName                CONSTANT)

Don Gagne's avatar
Don Gagne committed
62 63
    Q_PROPERTY(LinkManager*         linkManager         READ linkManager            CONSTANT)
    Q_PROPERTY(MultiVehicleManager* multiVehicleManager READ multiVehicleManager    CONSTANT)
Don Gagne's avatar
Don Gagne committed
64
    Q_PROPERTY(QGCMapEngineManager* mapEngineManager    READ mapEngineManager       CONSTANT)
Jimmy Johnson's avatar
Jimmy Johnson committed
65
    Q_PROPERTY(QGCPositionManager*  qgcPositionManger   READ qgcPositionManger      CONSTANT)
66
    Q_PROPERTY(MissionCommandTree*  missionCommandTree  READ missionCommandTree     CONSTANT)
67
    Q_PROPERTY(VideoManager*        videoManager        READ videoManager           CONSTANT)
Gus Grubba's avatar
Gus Grubba committed
68
    Q_PROPERTY(MAVLinkLogManager*   mavlinkLogManager   READ mavlinkLogManager      CONSTANT)
69
    Q_PROPERTY(QGCCorePlugin*       corePlugin          READ corePlugin             CONSTANT)
70
    Q_PROPERTY(SettingsManager*     settingsManager     READ settingsManager        CONSTANT)
71
    Q_PROPERTY(FactGroup*           gpsRtk              READ gpsRtkFactGroup        CONSTANT)
72
    Q_PROPERTY(AirspaceManager*     airspaceManager     READ airspaceManager        CONSTANT)
73
    Q_PROPERTY(bool                 airmapSupported     READ airmapSupported        CONSTANT)
74 75
    Q_PROPERTY(TaisyncManager*      taisyncManager      READ taisyncManager         CONSTANT)
    Q_PROPERTY(bool                 taisyncSupported    READ taisyncSupported       CONSTANT)
76 77
    Q_PROPERTY(MicrohardManager*    microhardManager    READ microhardManager       CONSTANT)
    Q_PROPERTY(bool                 microhardSupported  READ microhardSupported     CONSTANT)
78

79
    Q_PROPERTY(int      supportedFirmwareCount          READ supportedFirmwareCount CONSTANT)
80
    Q_PROPERTY(int      supportedVehicleCount           READ supportedVehicleCount  CONSTANT)
81
    Q_PROPERTY(bool     px4ProFirmwareSupported         READ px4ProFirmwareSupported CONSTANT)
82
    Q_PROPERTY(int      apmFirmwareSupported            READ apmFirmwareSupported   CONSTANT)
Gus Grubba's avatar
Gus Grubba committed
83

DonLakeFlyer's avatar
DonLakeFlyer committed
84 85 86 87 88 89 90
    Q_PROPERTY(qreal zOrderTopMost              READ zOrderTopMost              CONSTANT) ///< z order for top most items, toolbar, main window sub view
    Q_PROPERTY(qreal zOrderWidgets              READ zOrderWidgets              CONSTANT) ///< z order value to widgets, for example: zoom controls, hud widgetss
    Q_PROPERTY(qreal zOrderMapItems             READ zOrderMapItems             CONSTANT)
    Q_PROPERTY(qreal zOrderVehicles             READ zOrderVehicles             CONSTANT)
    Q_PROPERTY(qreal zOrderWaypointIndicators   READ zOrderWaypointIndicators   CONSTANT)
    Q_PROPERTY(qreal zOrderTrajectoryLines      READ zOrderTrajectoryLines      CONSTANT)
    Q_PROPERTY(qreal zOrderWaypointLines        READ zOrderWaypointLines        CONSTANT)
Gus Grubba's avatar
Gus Grubba committed
91

Gus Grubba's avatar
Gus Grubba committed
92
    //-------------------------------------------------------------------------
93
    // MavLink Protocol
Don Gagne's avatar
Don Gagne committed
94
    Q_PROPERTY(bool     isVersionCheckEnabled   READ isVersionCheckEnabled      WRITE setIsVersionCheckEnabled      NOTIFY isVersionCheckEnabledChanged)
95
    Q_PROPERTY(int      mavlinkSystemID         READ mavlinkSystemID            WRITE setMavlinkSystemID            NOTIFY mavlinkSystemIDChanged)
96
    Q_PROPERTY(bool     hasAPMSupport           READ hasAPMSupport              CONSTANT)
dogmaphobic's avatar
dogmaphobic committed
97

98 99
    Q_PROPERTY(QGeoCoordinate flightMapPosition     READ flightMapPosition      WRITE setFlightMapPosition          NOTIFY flightMapPositionChanged)
    Q_PROPERTY(double         flightMapZoom         READ flightMapZoom          WRITE setFlightMapZoom              NOTIFY flightMapZoomChanged)
100
    Q_PROPERTY(double         flightMapInitialZoom  MEMBER _flightMapInitialZoom                                    CONSTANT)                               ///< Zoom level to use when either gcs or vehicle shows up for first time
Don Gagne's avatar
Don Gagne committed
101

Don Gagne's avatar
Don Gagne committed
102 103 104 105
    Q_PROPERTY(QString  parameterFileExtension  READ parameterFileExtension CONSTANT)
    Q_PROPERTY(QString  missionFileExtension    READ missionFileExtension   CONSTANT)
    Q_PROPERTY(QString  telemetryFileExtension  READ telemetryFileExtension CONSTANT)

106 107
    /// Returns the string for distance units which has configued by user
    Q_PROPERTY(QString appSettingsDistanceUnitsString READ appSettingsDistanceUnitsString CONSTANT)
108
    Q_PROPERTY(QString appSettingsAreaUnitsString READ appSettingsAreaUnitsString CONSTANT)
109

110 111
    Q_PROPERTY(QString qgcVersion       READ qgcVersion         CONSTANT)
    Q_PROPERTY(bool    skipSetupPage    READ skipSetupPage      WRITE setSkipSetupPage NOTIFY skipSetupPageChanged)
112

113 114 115 116 117
    Q_INVOKABLE void    saveGlobalSetting       (const QString& key, const QString& value);
    Q_INVOKABLE QString loadGlobalSetting       (const QString& key, const QString& defaultValue);
    Q_INVOKABLE void    saveBoolGlobalSetting   (const QString& key, bool value);
    Q_INVOKABLE bool    loadBoolGlobalSetting   (const QString& key, bool defaultValue);

118 119
    Q_INVOKABLE void    deleteAllSettingsNextBoot       () { _app->deleteAllSettingsNextBoot(); }
    Q_INVOKABLE void    clearDeleteAllSettingsNextBoot  () { _app->clearDeleteAllSettingsNextBoot(); }
120

121 122 123 124
    Q_INVOKABLE void    startPX4MockLink            (bool sendStatusText);
    Q_INVOKABLE void    startGenericMockLink        (bool sendStatusText);
    Q_INVOKABLE void    startAPMArduCopterMockLink  (bool sendStatusText);
    Q_INVOKABLE void    startAPMArduPlaneMockLink   (bool sendStatusText);
125
    Q_INVOKABLE void    startAPMArduSubMockLink     (bool sendStatusText);
126
    Q_INVOKABLE void    startAPMArduRoverMockLink   (bool sendStatusText);
Don Gagne's avatar
Don Gagne committed
127
    Q_INVOKABLE void    stopOneMockLink             (void);
128

129 130 131 132 133 134 135 136
    /// Converts from meters to the user specified distance unit
    Q_INVOKABLE QVariant metersToAppSettingsDistanceUnits(const QVariant& meters) const { return FactMetaData::metersToAppSettingsDistanceUnits(meters); }

    /// Converts from user specified distance unit to meters
    Q_INVOKABLE QVariant appSettingsDistanceUnitsToMeters(const QVariant& distance) const { return FactMetaData::appSettingsDistanceUnitsToMeters(distance); }

    QString appSettingsDistanceUnitsString(void) const { return FactMetaData::appSettingsDistanceUnitsString(); }

137 138 139 140 141 142 143 144
    /// Converts from square meters to the user specified area unit
    Q_INVOKABLE QVariant squareMetersToAppSettingsAreaUnits(const QVariant& meters) const { return FactMetaData::squareMetersToAppSettingsAreaUnits(meters); }

    /// Converts from user specified area unit to square meters
    Q_INVOKABLE QVariant appSettingsAreaUnitsToSquareMeters(const QVariant& area) const { return FactMetaData::appSettingsAreaUnitsToSquareMeters(area); }

    QString appSettingsAreaUnitsString(void) const { return FactMetaData::appSettingsAreaUnitsString(); }

145 146 147 148
    /// Returns the list of available logging category names.
    Q_INVOKABLE QStringList loggingCategories(void) const { return QGCLoggingCategoryRegister::instance()->registeredCategories(); }

    /// Turns on/off logging for the specified category. State is saved in app settings.
Don Gagne's avatar
Don Gagne committed
149
    Q_INVOKABLE void setCategoryLoggingOn(const QString& category, bool enable) { QGCLoggingCategoryRegister::instance()->setCategoryLoggingOn(category, enable); }
150 151

    /// Returns true if logging is turned on for the specified category.
Don Gagne's avatar
Don Gagne committed
152
    Q_INVOKABLE bool categoryLoggingOn(const QString& category) { return QGCLoggingCategoryRegister::instance()->categoryLoggingOn(category); }
153 154 155 156

    /// Updates the logging filter rules after settings have changed
    Q_INVOKABLE void updateLoggingFilterRules(void) { QGCLoggingCategoryRegister::instance()->setFilterRulesFromSettings(QString()); }

157 158
    Q_INVOKABLE bool linesIntersect(QPointF xLine1, QPointF yLine1, QPointF xLine2, QPointF yLine2);

159
    // Property accesors
Gus Grubba's avatar
Gus Grubba committed
160

161
    QString                 appName             ()  { return qgcApp()->applicationName(); }
162 163 164 165 166 167 168 169 170
    LinkManager*            linkManager         ()  { return _linkManager; }
    MultiVehicleManager*    multiVehicleManager ()  { return _multiVehicleManager; }
    QGCMapEngineManager*    mapEngineManager    ()  { return _mapEngineManager; }
    QGCPositionManager*     qgcPositionManger   ()  { return _qgcPositionManager; }
    MissionCommandTree*     missionCommandTree  ()  { return _missionCommandTree; }
    VideoManager*           videoManager        ()  { return _videoManager; }
    MAVLinkLogManager*      mavlinkLogManager   ()  { return _mavlinkLogManager; }
    QGCCorePlugin*          corePlugin          ()  { return _corePlugin; }
    SettingsManager*        settingsManager     ()  { return _settingsManager; }
171
    FactGroup*              gpsRtkFactGroup     ()  { return _gpsRtkFactGroup; }
172
    AirspaceManager*        airspaceManager     ()  { return _airspaceManager; }
173 174
    static QGeoCoordinate   flightMapPosition   ()  { return _coord; }
    static double           flightMapZoom       ()  { return _zoom; }
175

176 177 178 179 180 181 182
    TaisyncManager*         taisyncManager      ()  { return _taisyncManager; }
#if defined(QGC_GST_TAISYNC_ENABLED)
    bool                    taisyncSupported    () { return true; }
#else
    bool                    taisyncSupported    () { return false; }
#endif

183 184 185 186 187 188 189
    MicrohardManager*       microhardManager    ()  { return _microhardManager; }
#if defined(QGC_GST_TAISYNC_ENABLED)
    bool                    microhardSupported  () { return true; }
#else
    bool                    microhardSupported  () { return false; }
#endif

DonLakeFlyer's avatar
DonLakeFlyer committed
190 191 192 193 194 195 196
    qreal zOrderTopMost             () { return 1000; }
    qreal zOrderWidgets             () { return 100; }
    qreal zOrderMapItems            () { return 50; }
    qreal zOrderWaypointIndicators  () { return 50; }
    qreal zOrderVehicles            () { return 49; }
    qreal zOrderTrajectoryLines     () { return 48; }
    qreal zOrderWaypointLines       () { return 47; }
Gus Grubba's avatar
Gus Grubba committed
197

Don Gagne's avatar
Don Gagne committed
198
    bool    isVersionCheckEnabled   () { return _toolbox->mavlinkProtocol()->versionCheckEnabled(); }
199
    int     mavlinkSystemID         () { return _toolbox->mavlinkProtocol()->getSystemId(); }
200 201 202 203 204
#if defined(NO_ARDUPILOT_DIALECT)
    bool    hasAPMSupport           () { return false; }
#else
    bool    hasAPMSupport           () { return true; }
#endif
205

206
    int     supportedFirmwareCount  ();
207
    int     supportedVehicleCount   ();
208 209
    bool    px4ProFirmwareSupported ();
    bool    apmFirmwareSupported    ();
210 211
    bool    skipSetupPage           () { return _skipSetupPage; }
    void    setSkipSetupPage        (bool skip);
Gus Grubba's avatar
Gus Grubba committed
212

Don Gagne's avatar
Don Gagne committed
213
    void    setIsVersionCheckEnabled    (bool enable);
214
    void    setMavlinkSystemID          (int  id);
215 216
    void    setFlightMapPosition        (QGeoCoordinate& coordinate);
    void    setFlightMapZoom            (double zoom);
dogmaphobic's avatar
dogmaphobic committed
217

218 219 220
    QString parameterFileExtension(void) const  { return AppSettings::parameterFileExtension; }
    QString missionFileExtension(void) const    { return AppSettings::missionFileExtension; }
    QString telemetryFileExtension(void) const  { return AppSettings::telemetryFileExtension; }
Don Gagne's avatar
Don Gagne committed
221

222 223
    QString qgcVersion(void) const { return qgcApp()->applicationVersion(); }

224 225 226 227 228
#if defined(QGC_AIRMAP_ENABLED)
    bool    airmapSupported() { return true; }
#else
    bool    airmapSupported() { return false; }
#endif
229

230 231 232
    // Overrides from QGCTool
    virtual void setToolbox(QGCToolbox* toolbox);

dogmaphobic's avatar
dogmaphobic committed
233 234
signals:
    void isMultiplexingEnabledChanged   (bool enabled);
Don Gagne's avatar
Don Gagne committed
235
    void isVersionCheckEnabledChanged   (bool enabled);
236
    void mavlinkSystemIDChanged         (int id);
237
    void flightMapPositionChanged       (QGeoCoordinate flightMapPosition);
238
    void flightMapZoomChanged           (double flightMapZoom);
239
    void skipSetupPageChanged           ();
dogmaphobic's avatar
dogmaphobic committed
240

241
private:
242 243 244 245 246 247 248 249 250 251 252 253 254 255
    double                  _flightMapInitialZoom   = 17.0;
    LinkManager*            _linkManager            = nullptr;
    MultiVehicleManager*    _multiVehicleManager    = nullptr;
    QGCMapEngineManager*    _mapEngineManager       = nullptr;
    QGCPositionManager*     _qgcPositionManager     = nullptr;
    MissionCommandTree*     _missionCommandTree     = nullptr;
    VideoManager*           _videoManager           = nullptr;
    MAVLinkLogManager*      _mavlinkLogManager      = nullptr;
    QGCCorePlugin*          _corePlugin             = nullptr;
    FirmwarePluginManager*  _firmwarePluginManager  = nullptr;
    SettingsManager*        _settingsManager        = nullptr;
    FactGroup*              _gpsRtkFactGroup        = nullptr;
    AirspaceManager*        _airspaceManager        = nullptr;
    TaisyncManager*         _taisyncManager         = nullptr;
256
    MicrohardManager*       _microhardManager       = nullptr;
257 258

    bool                    _skipSetupPage          = false;
259 260 261 262 263

    static const char* _flightMapPositionSettingsGroup;
    static const char* _flightMapPositionLatitudeSettingsKey;
    static const char* _flightMapPositionLongitudeSettingsKey;
    static const char* _flightMapZoomSettingsKey;
264 265 266

    static QGeoCoordinate   _coord;
    static double           _zoom;
267 268 269
};

#endif